Skip to content

Commit

Permalink
Add velocity to gripper command (#99)
Browse files Browse the repository at this point in the history
  • Loading branch information
pac48 authored Apr 9, 2024
1 parent 60f6182 commit d4be560
Show file tree
Hide file tree
Showing 2 changed files with 19 additions and 0 deletions.
1 change: 1 addition & 0 deletions control_msgs/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -39,6 +39,7 @@ set(msg_files
)

set(action_files
action/ParallelGripperCommand.action
action/FollowJointTrajectory.action
action/GripperCommand.action
action/JointTrajectory.action
Expand Down
18 changes: 18 additions & 0 deletions control_msgs/action/ParallelGripperCommand.action
Original file line number Diff line number Diff line change
@@ -0,0 +1,18 @@
# Parallel grippers refer to an end effector where two opposing fingers grasp an object from opposite sides.
sensor_msgs/JointState command
# name: the name(s) of the joint this command is requesting
# position: desired position of each gripper joint (radians or meters)
# velocity: (optional, not used if empty) max velocity of the joint allowed while moving (radians or meters / second)
# effort: (optional, not used if empty) max effort of the joint allowed while moving (Newtons or Newton-meters)
---
sensor_msgs/JointState state # The current gripper state.
# position of each joint (radians or meters)
# optional: velocity of each joint (radians or meters / second)
# optional: effort of each joint (Newtons or Newton-meters)
bool stalled # True if the gripper is exerting max effort and not moving
bool reached_goal # True if the gripper position has reached the commanded setpoint
---
sensor_msgs/JointState state # The current gripper state.
# position of each joint (radians or meters)
# optional: velocity of each joint (radians or meters / second)
# optional: effort of each joint (Newtons or Newton-meters)

0 comments on commit d4be560

Please sign in to comment.