38 #ifndef MOVEIT_PLUGINS_GRIPPER_CONTROLLER_HANDLE 39 #define MOVEIT_PLUGINS_GRIPPER_CONTROLLER_HANDLE 42 #include <control_msgs/GripperCommandAction.h> 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;
114 goal.command.max_effort = 0.0;
117 int tpoint = trajectory.joint_trajectory.points.size() - 1;
118 ROS_DEBUG_NAMED(
"GripperController",
"Sending command from trajectory point %d", tpoint);
121 for (std::size_t i = 0; i < gripper_joint_indexes.size(); ++i)
123 std::size_t idx = gripper_joint_indexes[i];
125 if (trajectory.joint_trajectory.points[tpoint].positions.size() <= idx)
127 ROS_ERROR_NAMED(
"GripperController",
"GripperController expects a joint trajectory with one \ 128 point that specifies at least the position of joint \ 129 '%s', but insufficient positions provided",
130 trajectory.joint_trajectory.joint_names[idx].c_str());
133 goal.command.position += trajectory.joint_trajectory.points[tpoint].positions[idx];
135 if (trajectory.joint_trajectory.points[tpoint].effort.size() > idx)
136 goal.command.max_effort = trajectory.joint_trajectory.points[tpoint].effort[idx];
174 const control_msgs::GripperCommandResultConstPtr& result)
222 #endif // MOVEIT_PLUGINS_GRIPPER_CONTROLLER_HANDLE
#define ROS_DEBUG_STREAM_NAMED(name, args)
#define ROS_WARN_NAMED(name,...)
moveit_controller_manager::ExecutionStatus last_exec_
bool parallel_jaw_gripper_
void controllerActiveCallback()
void setCommandJoint(const std::string &name)
void allowFailure(bool allow)
void controllerDoneCallback(const actionlib::SimpleClientGoalState &state, const control_msgs::GripperCommandResultConstPtr &result)
#define ROS_DEBUG_NAMED(name,...)
GripperControllerHandle(const std::string &name, const std::string &ns)
std::set< std::string > command_joints_
std::shared_ptr< actionlib::SimpleActionClient< control_msgs::GripperCommandAction > > controller_action_client_
#define ROS_ERROR_NAMED(name,...)
void finishControllerExecution(const actionlib::SimpleClientGoalState &state)
void setParallelJawGripper(const std::string &left, const std::string &right)
virtual bool sendTrajectory(const moveit_msgs::RobotTrajectory &trajectory)
void addCommandJoint(const std::string &name)
void controllerFeedbackCallback(const control_msgs::GripperCommandFeedbackConstPtr &feedback)