41 #include <control_msgs/GripperCommandAction.h>
50 class GripperControllerHandle :
public ActionBasedControllerHandle<control_msgs::GripperCommandAction>
62 bool sendTrajectory(
const moveit_msgs::RobotTrajectory& trajectory)
override
69 if (!trajectory.multi_dof_joint_trajectory.points.empty())
71 ROS_ERROR_NAMED(
"GripperController",
"Gripper cannot execute multi-dof trajectories.");
75 if (trajectory.joint_trajectory.points.empty())
77 ROS_ERROR_NAMED(
"GripperController",
"GripperController requires at least one joint trajectory point.");
81 if (trajectory.joint_trajectory.points.size() > 1)
86 if (trajectory.joint_trajectory.joint_names.empty())
92 std::vector<std::size_t> gripper_joint_indexes;
93 for (std::size_t i = 0; i < trajectory.joint_trajectory.joint_names.size(); ++i)
97 gripper_joint_indexes.push_back(i);
103 if (gripper_joint_indexes.empty())
105 ROS_WARN_NAMED(
"GripperController",
"No command_joint was specified for the MoveIt controller gripper handle. \
106 Please see GripperControllerHandle::addCommandJoint() and \
107 GripperControllerHandle::setCommandJoint(). Assuming index 0.");
108 gripper_joint_indexes.push_back(0);
112 control_msgs::GripperCommandGoal goal;
113 goal.command.position = 0.0;
116 int tpoint = trajectory.joint_trajectory.points.size() - 1;
117 ROS_DEBUG_NAMED(
"GripperController",
"Sending command from trajectory point %d", tpoint);
120 for (std::size_t idx : gripper_joint_indexes)
122 if (trajectory.joint_trajectory.points[tpoint].positions.size() <= idx)
124 ROS_ERROR_NAMED(
"GripperController",
"GripperController expects a joint trajectory with one \
125 point that specifies at least the position of joint \
126 '%s', but insufficient positions provided",
127 trajectory.joint_trajectory.joint_names[idx].c_str());
130 goal.command.position += trajectory.joint_trajectory.points[tpoint].positions[idx];
132 if (trajectory.joint_trajectory.points[tpoint].effort.size() > idx)
134 goal.command.max_effort = trajectory.joint_trajectory.points[tpoint].effort[idx];
176 const control_msgs::GripperCommandResultConstPtr& )