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");