Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Add velocity to gripper command #99

Merged
Merged
Show file tree
Hide file tree
Changes from 6 commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
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 iff the gripper is exerting max effort and not moving
bool reached_goal # True iff the gripper position has reached the commanded setpoint
pac48 marked this conversation as resolved.
Show resolved Hide resolved
---
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)
Loading