47 static const rclcpp::Logger
LOGGER =
48 rclcpp::get_logger(
"moveit_move_group_default_capabilities.execute_trajectory_action_capability");
56 callback_executor_.cancel();
58 if (callback_thread_.joinable())
59 callback_thread_.join();
64 using std::placeholders::_1;
65 using std::placeholders::_2;
67 auto node =
context_->moveit_cpp_->getNode();
68 callback_group_ = node->create_callback_group(rclcpp::CallbackGroupType::MutuallyExclusive,
70 callback_executor_.add_callback_group(callback_group_, node->get_node_base_interface());
71 callback_thread_ = std::thread([
this]() { callback_executor_.spin(); });
73 execute_action_server_ = rclcpp_action::create_server<ExecTrajectory>(
74 node->get_node_base_interface(), node->get_node_clock_interface(), node->get_node_logging_interface(),
75 node->get_node_waitables_interface(), EXECUTE_ACTION_NAME,
76 [](
const rclcpp_action::GoalUUID& ,
const std::shared_ptr<const ExecTrajectory::Goal>& ) {
77 RCLCPP_INFO(LOGGER,
"Received goal request");
78 return rclcpp_action::GoalResponse::ACCEPT_AND_EXECUTE;
80 [](
const std::shared_ptr<ExecTrajectoryGoal>& ) {
81 RCLCPP_INFO(LOGGER,
"Received request to cancel goal");
82 return rclcpp_action::CancelResponse::ACCEPT;
84 [
this](
const auto& goal) { executePathCallback(goal); }, rcl_action_server_get_default_options(),
88 void MoveGroupExecuteTrajectoryAction::executePathCallback(
const std::shared_ptr<ExecTrajectoryGoal>& goal)
90 auto action_res = std::make_shared<ExecTrajectory::Result>();
91 if (!
context_->trajectory_execution_manager_)
93 const std::string response =
"Cannot execute trajectory since ~allow_trajectory_execution was set to false";
94 action_res->error_code.val = moveit_msgs::msg::MoveItErrorCodes::CONTROL_FAILED;
95 goal->abort(action_res);
99 executePath(goal, action_res);
102 auto fb = std::make_shared<ExecTrajectory::Feedback>();
103 fb->state = response;
104 if (action_res->error_code.val == moveit_msgs::msg::MoveItErrorCodes::SUCCESS)
106 goal->publish_feedback(fb);
107 goal->succeed(action_res);
111 goal->publish_feedback(fb);
112 goal->abort(action_res);
115 setExecuteTrajectoryState(
IDLE, goal);
118 void MoveGroupExecuteTrajectoryAction::executePath(
const std::shared_ptr<ExecTrajectoryGoal>& goal,
119 std::shared_ptr<ExecTrajectory::Result>& action_res)
121 RCLCPP_INFO(LOGGER,
"Execution request received");
123 if (
context_->trajectory_execution_manager_->push(goal->get_goal()->trajectory))
125 setExecuteTrajectoryState(
MONITOR, goal);
126 context_->trajectory_execution_manager_->execute();
130 action_res->error_code.val = moveit_msgs::msg::MoveItErrorCodes::SUCCESS;
134 action_res->error_code.val = moveit_msgs::msg::MoveItErrorCodes::PREEMPTED;
138 action_res->error_code.val = moveit_msgs::msg::MoveItErrorCodes::TIMED_OUT;
142 action_res->error_code.val = moveit_msgs::msg::MoveItErrorCodes::CONTROL_FAILED;
144 RCLCPP_INFO_STREAM(LOGGER,
"Execution completed: " << status.
asString());
148 action_res->error_code.val = moveit_msgs::msg::MoveItErrorCodes::CONTROL_FAILED;
152 void MoveGroupExecuteTrajectoryAction::preemptExecuteTrajectoryCallback()
154 context_->trajectory_execution_manager_->stopExecution(
true);
157 void MoveGroupExecuteTrajectoryAction::setExecuteTrajectoryState(
MoveGroupState state,
158 const std::shared_ptr<ExecTrajectoryGoal>& goal)
160 auto execute_feedback = std::make_shared<ExecTrajectory::Feedback>();
162 goal->publish_feedback(execute_feedback);
167 #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() override
MoveGroupExecuteTrajectoryAction()
void initialize() override
const rclcpp::Logger LOGGER
The reported execution status.
std::string asString() const
Convert the execution status to a string.