47 static const rclcpp::Logger
LOGGER =
48 rclcpp::get_logger(
"moveit_move_group_default_capabilities.execute_trajectory_action_capability");
56 using std::placeholders::_1;
57 using std::placeholders::_2;
59 auto node =
context_->moveit_cpp_->getNode();
61 execute_action_server_ = rclcpp_action::create_server<ExecTrajectory>(
62 node->get_node_base_interface(), node->get_node_clock_interface(), node->get_node_logging_interface(),
63 node->get_node_waitables_interface(), EXECUTE_ACTION_NAME,
64 [](
const rclcpp_action::GoalUUID& ,
const std::shared_ptr<const ExecTrajectory::Goal>& ) {
65 RCLCPP_INFO(LOGGER,
"Received goal request");
66 return rclcpp_action::GoalResponse::ACCEPT_AND_EXECUTE;
68 [](
const std::shared_ptr<ExecTrajectoryGoal>& ) {
69 RCLCPP_INFO(LOGGER,
"Received request to cancel goal");
70 return rclcpp_action::CancelResponse::ACCEPT;
72 [
this](
const auto& goal) { executePathCallback(goal); });
75 void MoveGroupExecuteTrajectoryAction::executePathCallback(
const std::shared_ptr<ExecTrajectoryGoal>& goal)
77 auto action_res = std::make_shared<ExecTrajectory::Result>();
78 if (!
context_->trajectory_execution_manager_)
80 const std::string response =
"Cannot execute trajectory since ~allow_trajectory_execution was set to false";
81 action_res->error_code.val = moveit_msgs::msg::MoveItErrorCodes::CONTROL_FAILED;
82 goal->abort(action_res);
86 executePath(goal, action_res);
89 auto fb = std::make_shared<ExecTrajectory::Feedback>();
91 if (action_res->error_code.val == moveit_msgs::msg::MoveItErrorCodes::SUCCESS)
93 goal->publish_feedback(fb);
94 goal->succeed(action_res);
98 goal->publish_feedback(fb);
99 goal->abort(action_res);
102 setExecuteTrajectoryState(
IDLE, goal);
105 void MoveGroupExecuteTrajectoryAction::executePath(
const std::shared_ptr<ExecTrajectoryGoal>& goal,
106 std::shared_ptr<ExecTrajectory::Result>& action_res)
108 RCLCPP_INFO(LOGGER,
"Execution request received");
110 context_->trajectory_execution_manager_->clear();
111 if (
context_->trajectory_execution_manager_->push(goal->get_goal()->trajectory))
113 setExecuteTrajectoryState(
MONITOR, goal);
114 context_->trajectory_execution_manager_->execute();
118 action_res->error_code.val = moveit_msgs::msg::MoveItErrorCodes::SUCCESS;
122 action_res->error_code.val = moveit_msgs::msg::MoveItErrorCodes::PREEMPTED;
126 action_res->error_code.val = moveit_msgs::msg::MoveItErrorCodes::TIMED_OUT;
130 action_res->error_code.val = moveit_msgs::msg::MoveItErrorCodes::CONTROL_FAILED;
132 RCLCPP_INFO_STREAM(LOGGER,
"Execution completed: " << status.
asString());
136 action_res->error_code.val = moveit_msgs::msg::MoveItErrorCodes::CONTROL_FAILED;
140 void MoveGroupExecuteTrajectoryAction::preemptExecuteTrajectoryCallback()
142 context_->trajectory_execution_manager_->stopExecution(
true);
145 void MoveGroupExecuteTrajectoryAction::setExecuteTrajectoryState(
MoveGroupState state,
146 const std::shared_ptr<ExecTrajectoryGoal>& goal)
148 auto execute_feedback = std::make_shared<ExecTrajectory::Feedback>();
150 goal->publish_feedback(execute_feedback);
155 #include <pluginlib/class_list_macros.hpp>
PLUGINLIB_EXPORT_CLASS(cached_ik_kinematics_plugin::CachedIKKinematicsPlugin< kdl_kinematics_plugin::KDLKinematicsPlugin >, kinematics::KinematicsBase)
MoveGroupContextPtr context_
std::string getActionResultString(const moveit_msgs::msg::MoveItErrorCodes &error_code, bool planned_trajectory_empty, bool plan_only)
std::string stateToStr(MoveGroupState state) const
MoveGroupExecuteTrajectoryAction()
void initialize() override
const rclcpp::Logger LOGGER
The reported execution status.
std::string asString() const
Convert the execution status to a string.