63 bool sendTrajectory(
const moveit_msgs::msg::RobotTrajectory& trajectory)
override
65 RCLCPP_DEBUG_STREAM(
logger_,
"Received new trajectory for " <<
name_);
72 RCLCPP_ERROR_STREAM(
logger_,
"Action client not connected to action server: " <<
getActionName());
76 if (!trajectory.multi_dof_joint_trajectory.points.empty())
78 RCLCPP_ERROR(
logger_,
"%s cannot execute multi-dof trajectories.",
name_.c_str());
82 if (trajectory.joint_trajectory.points.empty())
84 RCLCPP_ERROR(
logger_,
"%s requires at least one joint trajectory point, but none received.",
name_.c_str());
88 if (trajectory.joint_trajectory.joint_names.empty())
90 RCLCPP_ERROR(
logger_,
"%s received a trajectory with no joint names specified.",
name_.c_str());
95 control_msgs::action::ParallelGripperCommand::Goal goal;
96 auto& cmd_state = goal.command;
98 auto& joint_names = trajectory.joint_trajectory.joint_names;
99 auto it = std::find(joint_names.begin(), joint_names.end(), command_joint_);
100 if (it != joint_names.end())
102 cmd_state.name.push_back(command_joint_);
103 std::size_t gripper_joint_index = std::distance(joint_names.begin(), it);
105 if (trajectory.joint_trajectory.points.back().positions.size() <= gripper_joint_index)
107 RCLCPP_ERROR(
logger_,
"ParallelGripperCommand expects a joint trajectory with one \
108 point that specifies at least the position of joint \
109 '%s', but insufficient positions provided.",
110 trajectory.joint_trajectory.joint_names[gripper_joint_index].c_str());
113 cmd_state.position.push_back(trajectory.joint_trajectory.points.back().positions[gripper_joint_index]);
115 if (max_velocity_ > 0.0)
117 cmd_state.velocity.push_back(max_velocity_);
119 if (max_effort_ > 0.0)
121 cmd_state.effort.push_back(max_effort_);
126 RCLCPP_ERROR(
logger_,
"Received trajectory does not include a command for joint name %s.", command_joint_.c_str());
130 rclcpp_action::Client<control_msgs::action::ParallelGripperCommand>::SendGoalOptions send_goal_options;
132 send_goal_options.goal_response_callback =
133 [
this](
const rclcpp_action::Client<control_msgs::action::ParallelGripperCommand>::GoalHandle::SharedPtr&
134 ) { RCLCPP_DEBUG_STREAM(
logger_,
name_ <<
" started execution."); };
140 RCLCPP_ERROR(
logger_,
"%s goal was rejected by server.",
name_.c_str());