37 #include "execute_trajectory_service_capability.h" 
   43 MoveGroupExecuteService::MoveGroupExecuteService()
 
   44   : MoveGroupCapability(
"ExecuteTrajectoryService")
 
   46   , spinner_(1 , &callback_queue_)
 
   50 MoveGroupExecuteService::~MoveGroupExecuteService()
 
   55 void MoveGroupExecuteService::initialize()
 
   62   ops.template init<moveit_msgs::ExecuteKnownTrajectory>(EXECUTE_SERVICE_NAME, [
this](
const auto& req, 
auto& res) {
 
   63     executeTrajectoryService(req, res);
 
   66   execute_service_ = root_node_handle_.advertiseService(ops);
 
   70 bool MoveGroupExecuteService::executeTrajectoryService(moveit_msgs::ExecuteKnownTrajectory::Request& req,
 
   71                                                        moveit_msgs::ExecuteKnownTrajectory::Response& res)
 
   74   if (!context_->trajectory_execution_manager_)
 
   76     ROS_ERROR_NAMED(
getName(), 
"Cannot execute trajectory since ~allow_trajectory_execution was set to false");
 
   77     res.error_code.val = moveit_msgs::MoveItErrorCodes::CONTROL_FAILED;
 
   84   context_->trajectory_execution_manager_->clear();
 
   85   if (context_->trajectory_execution_manager_->push(req.trajectory))
 
   87     context_->trajectory_execution_manager_->execute();
 
   88     if (req.wait_for_execution)
 
   92         res.error_code.val = moveit_msgs::MoveItErrorCodes::SUCCESS;
 
   94         res.error_code.val = moveit_msgs::MoveItErrorCodes::PREEMPTED;
 
   96         res.error_code.val = moveit_msgs::MoveItErrorCodes::TIMED_OUT;
 
   98         res.error_code.val = moveit_msgs::MoveItErrorCodes::CONTROL_FAILED;
 
  104       res.error_code.val = moveit_msgs::MoveItErrorCodes::SUCCESS;
 
  109     res.error_code.val = moveit_msgs::MoveItErrorCodes::CONTROL_FAILED;