41 #include <control_msgs/action/gripper_command.hpp> 
   55                           const double max_effort = 0.0)
 
   57           node, 
name, ns, 
"moveit.simple_controller_manager.gripper_controller_handle")
 
   58     , allow_failure_(false)
 
   59     , parallel_jaw_gripper_(false)
 
   60     , max_effort_(max_effort)
 
   64   bool sendTrajectory(
const moveit_msgs::msg::RobotTrajectory& trajectory)
 override 
   66     RCLCPP_DEBUG_STREAM(
LOGGER, 
"Received new trajectory for " << 
name_);
 
   73       RCLCPP_ERROR_STREAM(
LOGGER, 
"Action client not connected to action server: " << 
getActionName());
 
   77     if (!trajectory.multi_dof_joint_trajectory.points.empty())
 
   79       RCLCPP_ERROR(
LOGGER, 
"Gripper cannot execute multi-dof trajectories.");
 
   83     if (trajectory.joint_trajectory.points.empty())
 
   85       RCLCPP_ERROR(
LOGGER, 
"GripperController requires at least one joint trajectory point.");
 
   95     if (trajectory.joint_trajectory.joint_names.empty())
 
   97       RCLCPP_ERROR(
LOGGER, 
"No joint names specified");
 
  101     std::vector<std::size_t> gripper_joint_indexes;
 
  102     for (std::size_t i = 0; i < trajectory.joint_trajectory.joint_names.size(); ++i)
 
  104       if (command_joints_.find(trajectory.joint_trajectory.joint_names[i]) != command_joints_.end())
 
  106         gripper_joint_indexes.push_back(i);
 
  107         if (!parallel_jaw_gripper_)
 
  112     if (gripper_joint_indexes.empty())
 
  114       RCLCPP_WARN(
LOGGER, 
"No command_joint was specified for the MoveIt controller gripper handle. \ 
  115                       Please see GripperControllerHandle::addCommandJoint() and \ 
  116                       GripperControllerHandle::setCommandJoint(). Assuming index 0.");
 
  117       gripper_joint_indexes.push_back(0);
 
  121     control_msgs::action::GripperCommand::Goal goal;
 
  122     goal.command.position = 0.0;
 
  125     int tpoint = trajectory.joint_trajectory.points.size() - 1;
 
  126     RCLCPP_DEBUG(
LOGGER, 
"Sending command from trajectory point %d", tpoint);
 
  129     for (std::size_t idx : gripper_joint_indexes)
 
  131       if (trajectory.joint_trajectory.points[tpoint].positions.size() <= idx)
 
  133         RCLCPP_ERROR(
LOGGER, 
"GripperController expects a joint trajectory with one \ 
  134                          point that specifies at least the position of joint \ 
  135                          '%s', but insufficient positions provided",
 
  136                      trajectory.joint_trajectory.joint_names[idx].c_str());
 
  139       goal.command.position += trajectory.joint_trajectory.points[tpoint].positions[idx];
 
  141       if (trajectory.joint_trajectory.points[tpoint].effort.size() > idx)
 
  143         goal.command.max_effort = trajectory.joint_trajectory.points[tpoint].effort[idx];
 
  147         goal.command.max_effort = max_effort_;
 
  150     rclcpp_action::Client<control_msgs::action::GripperCommand>::SendGoalOptions send_goal_options;
 
  152     send_goal_options.goal_response_callback =
 
  153         [
this](
const rclcpp_action::Client<control_msgs::action::GripperCommand>::GoalHandle::SharedPtr&
 
  154                ) { RCLCPP_DEBUG_STREAM(
LOGGER, 
name_ << 
" started execution"); };
 
  160       RCLCPP_ERROR(
LOGGER, 
"Goal was rejected by server");
 
  171     command_joints_.clear();
 
  177     command_joints_.insert(
name);
 
  182     allow_failure_ = allow;
 
  189     parallel_jaw_gripper_ = 
true;
 
  193   void controllerDoneCallback(
 
  194       const rclcpp_action::ClientGoalHandle<control_msgs::action::GripperCommand>::WrappedResult& wrapped_result)
 override 
  196     if (wrapped_result.code == rclcpp_action::ResultCode::ABORTED && allow_failure_)
 
  216   bool parallel_jaw_gripper_;
 
  234   std::set<std::string> command_joints_;
 
const rclcpp::Logger LOGGER
 
Base class for controller handles that interact with a controller through a ROS action server.
 
moveit_controller_manager::ExecutionStatus last_exec_
Status after last trajectory execution.
 
std::string getActionName() const
Get the full name of the action using the action namespace and base name.
 
void finishControllerExecution(const rclcpp_action::ResultCode &state)
Indicate that the controller handle is done executing the trajectory and set the controller manager h...
 
rclcpp_action::ClientGoalHandle< control_msgs::action::GripperCommand >::SharedPtr current_goal_
Current goal that has been sent to the action server.
 
bool isConnected() const
Check if the controller's action server is ready to receive action goals.
 
bool done_
Indicates whether the controller handle is done executing its current trajectory.
 
rclcpp_action::Client< control_msgs::action::GripperCommand >::SharedPtr controller_action_client_
Action client to send trajectories to the controller's action server.
 
void allowFailure(bool allow)
 
void addCommandJoint(const std::string &name)
 
bool sendTrajectory(const moveit_msgs::msg::RobotTrajectory &trajectory) override
Send a trajectory to the controller.
 
GripperControllerHandle(const rclcpp::Node::SharedPtr &node, const std::string &name, const std::string &ns, const double max_effort=0.0)
 
void setCommandJoint(const std::string &name)
 
void setParallelJawGripper(const std::string &left, const std::string &right)