Skip to content

Commit d4be560

Browse files
authored
Add velocity to gripper command (#99)
1 parent 60f6182 commit d4be560

File tree

2 files changed

+19
-0
lines changed

2 files changed

+19
-0
lines changed

control_msgs/CMakeLists.txt

+1
Original file line numberDiff line numberDiff line change
@@ -39,6 +39,7 @@ set(msg_files
3939
)
4040

4141
set(action_files
42+
action/ParallelGripperCommand.action
4243
action/FollowJointTrajectory.action
4344
action/GripperCommand.action
4445
action/JointTrajectory.action
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,18 @@
1+
# Parallel grippers refer to an end effector where two opposing fingers grasp an object from opposite sides.
2+
sensor_msgs/JointState command
3+
# name: the name(s) of the joint this command is requesting
4+
# position: desired position of each gripper joint (radians or meters)
5+
# velocity: (optional, not used if empty) max velocity of the joint allowed while moving (radians or meters / second)
6+
# effort: (optional, not used if empty) max effort of the joint allowed while moving (Newtons or Newton-meters)
7+
---
8+
sensor_msgs/JointState state # The current gripper state.
9+
# position of each joint (radians or meters)
10+
# optional: velocity of each joint (radians or meters / second)
11+
# optional: effort of each joint (Newtons or Newton-meters)
12+
bool stalled # True if the gripper is exerting max effort and not moving
13+
bool reached_goal # True if the gripper position has reached the commanded setpoint
14+
---
15+
sensor_msgs/JointState state # The current gripper state.
16+
# position of each joint (radians or meters)
17+
# optional: velocity of each joint (radians or meters / second)
18+
# optional: effort of each joint (Newtons or Newton-meters)

0 commit comments

Comments
 (0)