50   : MoveGroupCapability(
"MoveAction"), move_state_(
IDLE), preempt_requested_{ 
false }
 
   54 void MoveGroupMoveAction::initialize()
 
   57   move_action_server_ = std::make_unique<actionlib::SimpleActionServer<moveit_msgs::MoveGroupAction>>(
 
   58       root_node_handle_, 
MOVE_ACTION, [
this](
const auto& goal) { executeMoveCallback(goal); }, 
false);
 
   59   move_action_server_->registerPreemptCallback([
this] { preemptMoveCallback(); });
 
   60   move_action_server_->start();
 
   63 void MoveGroupMoveAction::executeMoveCallback(
const moveit_msgs::MoveGroupGoalConstPtr& goal)
 
   67   context_->planning_scene_monitor_->waitForCurrentRobotState(
ros::Time::now());
 
   68   context_->planning_scene_monitor_->updateFrameTransforms();
 
   70   moveit_msgs::MoveGroupResult action_res;
 
   71   if (goal->planning_options.plan_only || !context_->allow_trajectory_execution_)
 
   73     if (!goal->planning_options.plan_only)
 
   75                                 "but the goal request has plan_only set to false. " 
   76                                 "Only a motion plan will be computed anyway.");
 
   77     executeMoveCallbackPlanOnly(goal, action_res);
 
   80     executeMoveCallbackPlanAndExecute(goal, action_res);
 
   84       getActionResultString(action_res.error_code, planned_trajectory_empty, goal->planning_options.plan_only);
 
   85   if (action_res.error_code.val == moveit_msgs::MoveItErrorCodes::SUCCESS)
 
   86     move_action_server_->setSucceeded(action_res, response);
 
   89     if (action_res.error_code.val == moveit_msgs::MoveItErrorCodes::PREEMPTED)
 
   90       move_action_server_->setPreempted(action_res, 
response);
 
   92       move_action_server_->setAborted(action_res, 
response);
 
   97   preempt_requested_ = 
false;
 
  100 void MoveGroupMoveAction::executeMoveCallbackPlanAndExecute(
const moveit_msgs::MoveGroupGoalConstPtr& goal,
 
  101                                                             moveit_msgs::MoveGroupResult& action_res)
 
  104                             "Forwarding to planning and execution pipeline.");
 
  108   const moveit_msgs::MotionPlanRequest& motion_plan_request =
 
  109       moveit::core::isEmpty(goal->request.start_state) ? goal->request : clearRequestStartState(goal->request);
 
  110   const moveit_msgs::PlanningScene& planning_scene_diff =
 
  112           goal->planning_options.planning_scene_diff :
 
  113           clearSceneRobotState(goal->planning_options.planning_scene_diff);
 
  115   opt.
replan_ = goal->planning_options.replan;
 
  121     return planUsingPlanningPipeline(motion_plan_request, plan);
 
  123   if (goal->planning_options.look_around && context_->plan_with_sensing_)
 
  126                           attempts = goal->planning_options.look_around_attempts,
 
  127                           safe_execution_cost = goal->planning_options.max_safe_execution_cost](
 
  129       return plan_with_sensing->computePlan(plan, planner, attempts, safe_execution_cost);
 
  131     context_->plan_with_sensing_->setBeforeLookCallback([
this] { 
return startMoveLookCallback(); });
 
  135   if (preempt_requested_)
 
  138     action_res.error_code.val = moveit_msgs::MoveItErrorCodes::PREEMPTED;
 
  142   context_->plan_execution_->planAndExecute(plan, planning_scene_diff, opt);
 
  144   convertToMsg(plan.
plan_components_, action_res.trajectory_start, action_res.planned_trajectory);
 
  150 void MoveGroupMoveAction::executeMoveCallbackPlanOnly(
const moveit_msgs::MoveGroupGoalConstPtr& goal,
 
  151                                                       moveit_msgs::MoveGroupResult& action_res)
 
  153   ROS_INFO_NAMED(
getName(), 
"Planning request received for MoveGroup action. Forwarding to planning pipeline.");
 
  157   if (preempt_requested_)
 
  160     action_res.error_code.val = moveit_msgs::MoveItErrorCodes::PREEMPTED;
 
  165   const planning_pipeline::PlanningPipelinePtr 
planning_pipeline = resolvePlanningPipeline(goal->request.pipeline_id);
 
  168     action_res.error_code.val = moveit_msgs::MoveItErrorCodes::FAILURE;
 
  174     auto scene = context_->planning_scene_monitor_->copyPlanningScene(goal->planning_options.planning_scene_diff);
 
  177   catch (std::exception& ex)
 
  180     res.
error_code_.val = moveit_msgs::MoveItErrorCodes::FAILURE;
 
  183   convertToMsg(res.
trajectory_, action_res.trajectory_start, action_res.planned_trajectory);
 
  197   const planning_pipeline::PlanningPipelinePtr 
planning_pipeline = resolvePlanningPipeline(req.pipeline_id);
 
  200     res.
error_code_.val = moveit_msgs::MoveItErrorCodes::FAILURE;
 
  208   catch (std::exception& ex)
 
  211     res.
error_code_.val = moveit_msgs::MoveItErrorCodes::FAILURE;
 
  223 void MoveGroupMoveAction::startMoveExecutionCallback()
 
  228 void MoveGroupMoveAction::startMoveLookCallback()
 
  233 void MoveGroupMoveAction::preemptMoveCallback()
 
  235   preempt_requested_ = 
true;
 
  236   context_->plan_execution_->stop();
 
  242   move_feedback_.state = stateToStr(state);
 
  243   move_action_server_->publishFeedback(move_feedback_);