40using namespace std::placeholders;
 
   46  RCLCPP_DEBUG_STREAM(
logger_, 
"new trajectory to " << 
name_);
 
   53    RCLCPP_ERROR_STREAM(
logger_, 
"Action client not connected to action server: " << 
getActionName());
 
   59    RCLCPP_INFO_STREAM(
logger_, 
"sending trajectory to " << 
name_);
 
   63    RCLCPP_INFO_STREAM(
logger_, 
"sending continuation for the currently executed trajectory to " << 
name_);
 
   66  control_msgs::action::FollowJointTrajectory::Goal goal = 
goal_template_;
 
   67  goal.trajectory = trajectory.joint_trajectory;
 
   68  goal.multi_dof_trajectory = trajectory.multi_dof_joint_trajectory;
 
   70  rclcpp_action::Client<control_msgs::action::FollowJointTrajectory>::SendGoalOptions send_goal_options;
 
   72  send_goal_options.goal_response_callback =
 
   74          const rclcpp_action::Client<control_msgs::action::FollowJointTrajectory>::GoalHandle::SharedPtr& goal_handle) {
 
   75        RCLCPP_INFO_STREAM(
logger_, 
name_ << 
" started execution");
 
   78          RCLCPP_WARN(
logger_, 
"Goal request rejected");
 
   82          RCLCPP_INFO(
logger_, 
"Goal request accepted!");
 
   94    RCLCPP_ERROR(
logger_, 
"Goal was rejected by server");
 
 
  113enum ToleranceVariables
 
  119template <ToleranceVariables>
 
  120double& variable(control_msgs::msg::JointTolerance& msg);
 
  123inline double& variable<POSITION>(control_msgs::msg::JointTolerance& msg)
 
  128inline double& variable<VELOCITY>(control_msgs::msg::JointTolerance& msg)
 
  133inline double& variable<ACCELERATION>(control_msgs::msg::JointTolerance& msg)
 
  135  return msg.acceleration;
 
  138const std::map<ToleranceVariables, std::string> VAR_NAME = { { 
POSITION, 
"position" },
 
  141const std::map<ToleranceVariables, 
decltype(&variable<POSITION>)> VAR_ACCESS = { { 
POSITION, &variable<POSITION> },
 
  144                                                                                   &variable<ACCELERATION> } };
 
  146const char* errorCodeToMessage(
int error_code)
 
  150    case control_msgs::action::FollowJointTrajectory::Result::SUCCESSFUL:
 
  152    case control_msgs::action::FollowJointTrajectory::Result::INVALID_GOAL:
 
  153      return "INVALID_GOAL";
 
  154    case control_msgs::action::FollowJointTrajectory::Result::INVALID_JOINTS:
 
  155      return "INVALID_JOINTS";
 
  156    case control_msgs::action::FollowJointTrajectory::Result::OLD_HEADER_TIMESTAMP:
 
  157      return "OLD_HEADER_TIMESTAMP";
 
  158    case control_msgs::action::FollowJointTrajectory::Result::PATH_TOLERANCE_VIOLATED:
 
  159      return "PATH_TOLERANCE_VIOLATED";
 
  160    case control_msgs::action::FollowJointTrajectory::Result::GOAL_TOLERANCE_VIOLATED:
 
  161      return "GOAL_TOLERANCE_VIOLATED";
 
  163      return "unknown error";
 
  210control_msgs::msg::JointTolerance&
 
  212                                                    const std::string& name)
 
  214  auto it = std::lower_bound(tolerances.begin(), tolerances.end(), name,
 
  215                             [](
const control_msgs::msg::JointTolerance& lhs, 
const std::string& rhs) {
 
  216                               return lhs.name < rhs;
 
  218  if (it == tolerances.cend() || it->name != name)
 
  220    it = tolerances.insert(it, control_msgs::msg::JointTolerance());
 
 
  227    const rclcpp_action::ClientGoalHandle<control_msgs::action::FollowJointTrajectory>::WrappedResult& wrapped_result)
 
  230  if (!wrapped_result.result)
 
  232    RCLCPP_WARN_STREAM(
logger_, 
"Controller '" << 
name_ << 
"' done, no result returned");
 
  234  else if (wrapped_result.result->error_code == control_msgs::action::FollowJointTrajectory::Result::SUCCESSFUL)
 
  236    RCLCPP_INFO_STREAM(
logger_, 
"Controller '" << 
name_ << 
"' successfully finished");
 
  240    RCLCPP_WARN_STREAM(
logger_, 
"Controller '" << 
name_ << 
"' failed with error " 
  241                                               << errorCodeToMessage(wrapped_result.result->error_code) << 
": " 
  242                                               << wrapped_result.result->error_string);
 
 
const rclcpp::Logger logger_
 
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::FollowJointTrajectory >::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::FollowJointTrajectory >::SharedPtr controller_action_client_
Action client to send trajectories to the controller's action server.
 
control_msgs::action::FollowJointTrajectory::Goal goal_template_
 
void controllerDoneCallback(const rclcpp_action::ClientGoalHandle< control_msgs::action::FollowJointTrajectory >::WrappedResult &wrapped_result) override
 
static control_msgs::msg::JointTolerance & getTolerance(std::vector< control_msgs::msg::JointTolerance > &tolerances, const std::string &name)
 
bool sendTrajectory(const moveit_msgs::msg::RobotTrajectory &trajectory) override
Send a trajectory to the controller.