From cbf637dd6ec45cdf65b7691d0706198014d950b0 Mon Sep 17 00:00:00 2001 From: Paul Gesel Date: Thu, 1 Feb 2024 16:16:05 -0700 Subject: [PATCH] add action for new gripper controller Signed-off-by: Paul Gesel --- control_msgs/CMakeLists.txt | 1 + control_msgs/action/AntipodalGripperCommand.action | 11 +++++++++++ 2 files changed, 12 insertions(+) create mode 100644 control_msgs/action/AntipodalGripperCommand.action diff --git a/control_msgs/CMakeLists.txt b/control_msgs/CMakeLists.txt index fa2ed67..4c089cf 100644 --- a/control_msgs/CMakeLists.txt +++ b/control_msgs/CMakeLists.txt @@ -39,6 +39,7 @@ set(msg_files ) set(action_files + action/AntipodalGripperCommand.action action/FollowJointTrajectory.action action/GripperCommand.action action/JointTrajectory.action diff --git a/control_msgs/action/AntipodalGripperCommand.action b/control_msgs/action/AntipodalGripperCommand.action new file mode 100644 index 0000000..a0395b2 --- /dev/null +++ b/control_msgs/action/AntipodalGripperCommand.action @@ -0,0 +1,11 @@ +sensor_msgs/JointState command # The velocity and effort fields are optionally and not used if empty. +--- +float64 position # The current gripper gap size (in meters) +float64 effort # The current effort exerted (in Newtons) +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 +--- +float64 position # The current gripper gap size (in meters) +float64 effort # The current effort exerted (in Newtons) +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