48 constexpr 
char LOGNAME[] = 
"planning_component";
 
   53   joint_model_group_ = moveit_cpp_->getRobotModel()->getJointModelGroup(group_name);
 
   54   if (!joint_model_group_)
 
   56     std::string error = 
"Could not find joint model group '" + group_name + 
"'.";
 
   58     throw std::runtime_error(error);
 
   60   plan_request_parameters_.load(nh_);
 
   62       LOGNAME, 
"Plan request parameters loaded with --" 
   63                    << 
" planning_pipeline: " << plan_request_parameters_.planning_pipeline << 
"," 
   64                    << 
" planner_id: " << plan_request_parameters_.planner_id << 
"," 
   65                    << 
" planning_time: " << plan_request_parameters_.planning_time << 
"," 
   66                    << 
" planning_attempts: " << plan_request_parameters_.planning_attempts << 
"," 
   67                    << 
" max_velocity_scaling_factor: " << plan_request_parameters_.max_velocity_scaling_factor << 
"," 
   68                    << 
" max_acceleration_scaling_factor: " << plan_request_parameters_.max_acceleration_scaling_factor);
 
   76 PlanningComponent::~PlanningComponent()
 
   82 const std::vector<std::string> PlanningComponent::getNamedTargetStates()
 
   84   if (joint_model_group_)
 
   86     return joint_model_group_->getDefaultStateNames();
 
   93   std::vector<std::string> empty;
 
   97 const std::string& PlanningComponent::getPlanningGroupName()
 const 
  102 bool PlanningComponent::setPathConstraints(
const moveit_msgs::Constraints& path_constraints)
 
  104   current_path_constraints_ = path_constraints;
 
  108 bool PlanningComponent::setTrajectoryConstraints(
const moveit_msgs::TrajectoryConstraints& trajectory_constraints)
 
  110   current_trajectory_constraints_ = trajectory_constraints;
 
  115                                                                const bool store_solution)
 
  118   if (!joint_model_group_)
 
  121     plan_solution.error_code_ = moveit::core::MoveItErrorCode::INVALID_GROUP_NAME;
 
  124       last_plan_solution_ = plan_solution;
 
  126     return plan_solution;
 
  130   auto psm = moveit_cpp_->getPlanningSceneMonitorNonConst();
 
  131   psm->updateFrameTransforms();
 
  136   req.group_name = group_name_;
 
  142   if (workspace_parameters_set_)
 
  143     req.workspace_parameters = workspace_parameters_;
 
  146   moveit::core::RobotStatePtr start_state = considered_start_state_;
 
  148     start_state = moveit_cpp_->getCurrentState();
 
  149   start_state->update();
 
  154   if (current_goal_constraints_.empty())
 
  157     plan_solution.error_code_ = moveit::core::MoveItErrorCode::INVALID_GOAL_CONSTRAINTS;
 
  160       last_plan_solution_ = plan_solution;
 
  162     return plan_solution;
 
  164   req.goal_constraints = current_goal_constraints_;
 
  167   req.path_constraints = current_path_constraints_;
 
  170   req.trajectory_constraints = current_trajectory_constraints_;
 
  174   const auto& pipelines = moveit_cpp_->getPlanningPipelines();
 
  176   if (it == pipelines.end())
 
  179     plan_solution.error_code_ = moveit::core::MoveItErrorCode::FAILURE;
 
  182       last_plan_solution_ = plan_solution;
 
  184     return plan_solution;
 
  186   const planning_pipeline::PlanningPipelinePtr pipeline = it->second;
 
  191     ROS_ERROR(
"Could not compute plan successfully");
 
  194       last_plan_solution_ = plan_solution;
 
  196     return plan_solution;
 
  200   plan_solution.start_state_ = req.start_state;
 
  217     last_plan_solution_ = plan_solution;
 
  219   return plan_solution;
 
  223 PlanningComponent::plan(
const MultiPipelinePlanRequestParameters& parameters,
 
  224                         const SolutionCallbackFunction& solution_selection_callback,
 
  225                         const StoppingCriterionFunction& stopping_criterion_callback)
 
  228   PlanningComponent::PlanSolutions planning_solutions{ parameters.multi_plan_request_parameters.size() };
 
  229   std::vector<std::thread> planning_threads;
 
  230   planning_threads.reserve(parameters.multi_plan_request_parameters.size());
 
  234   auto const hardware_concurrency = std::thread::hardware_concurrency();
 
  235   if (parameters.multi_plan_request_parameters.size() > hardware_concurrency && hardware_concurrency != 0)
 
  239         "More parallel planning problems defined ('%ld') than possible to solve concurrently with the hardware ('%d')",
 
  240         parameters.multi_plan_request_parameters.size(), hardware_concurrency);
 
  244   for (
auto const& plan_request_parameter : parameters.multi_plan_request_parameters)
 
  246     auto planning_thread = std::thread([&]() {
 
  250         plan_solution = plan(plan_request_parameter, 
false);
 
  252       catch (
const std::exception& e)
 
  255                                                               << 
"' threw exception '" << e.what() << 
"'");
 
  256         plan_solution.error_code_ = moveit::core::MoveItErrorCode::FAILURE;
 
  258       plan_solution.planner_id_ = plan_request_parameter.planner_id;
 
  259       planning_solutions.pushBack(plan_solution);
 
  261       if (stopping_criterion_callback != 
nullptr)
 
  263         if (stopping_criterion_callback(planning_solutions, parameters))
 
  267                                 "Stopping criterion met: Terminating planning pipelines that are still active");
 
  268           for (
auto const& plan_request_parameter : parameters.multi_plan_request_parameters)
 
  270             moveit_cpp_->terminatePlanningPipeline(plan_request_parameter.planning_pipeline);
 
  275     planning_threads.push_back(std::move(planning_thread));
 
  279   for (
auto& planning_thread : planning_threads)
 
  281     if (planning_thread.joinable())
 
  283       planning_thread.join();
 
  288   last_plan_solution_ = solution_selection_callback(planning_solutions.getSolutions());
 
  289   return last_plan_solution_;
 
  294   return plan(plan_request_parameters_);
 
  299   considered_start_state_ = std::make_shared<moveit::core::RobotState>(start_state);
 
  303 moveit::core::RobotStatePtr PlanningComponent::getStartState()
 
  305   if (considered_start_state_)
 
  306     return considered_start_state_;
 
  309     moveit::core::RobotStatePtr 
s;
 
  310     moveit_cpp_->getCurrentState(s, 1.0);
 
  315 bool PlanningComponent::setStartState(
const std::string& start_state_name)
 
  317   const auto& named_targets = getNamedTargetStates();
 
  318   if (std::find(named_targets.begin(), named_targets.end(), start_state_name) == named_targets.end())
 
  320     ROS_ERROR_NAMED(
LOGNAME, 
"No predefined joint state found for target name '%s'", start_state_name.c_str());
 
  324   start_state.setToDefaultValues(joint_model_group_, start_state_name);
 
  325   return setStartState(start_state);
 
  328 void PlanningComponent::setStartStateToCurrentState()
 
  330   considered_start_state_.reset();
 
  333 std::map<std::string, double> PlanningComponent::getNamedTargetStateValues(
const std::string& name)
 
  336   std::map<std::string, double> positions;
 
  337   joint_model_group_->getVariableDefaultPositions(name, positions);
 
  341 void PlanningComponent::setWorkspace(
double minx, 
double miny, 
double minz, 
double maxx, 
double maxy, 
double maxz)
 
  343   workspace_parameters_.header.frame_id = moveit_cpp_->getRobotModel()->getModelFrame();
 
  345   workspace_parameters_.min_corner.x = minx;
 
  346   workspace_parameters_.min_corner.y = miny;
 
  347   workspace_parameters_.min_corner.z = minz;
 
  348   workspace_parameters_.max_corner.x = maxx;
 
  349   workspace_parameters_.max_corner.y = maxy;
 
  350   workspace_parameters_.max_corner.z = maxz;
 
  351   workspace_parameters_set_ = 
true;
 
  354 void PlanningComponent::unsetWorkspace()
 
  356   workspace_parameters_set_ = 
false;
 
  359 bool PlanningComponent::setGoal(
const std::vector<moveit_msgs::Constraints>& goal_constraints)
 
  361   current_goal_constraints_ = goal_constraints;
 
  371 bool PlanningComponent::setGoal(
const geometry_msgs::PoseStamped& goal_pose, 
const std::string& link_name)
 
  377 bool PlanningComponent::setGoal(
const std::string& goal_state_name)
 
  379   const auto& named_targets = getNamedTargetStates();
 
  380   if (std::find(named_targets.begin(), named_targets.end(), goal_state_name) == named_targets.end())
 
  382     ROS_ERROR_NAMED(
LOGNAME, 
"No predefined joint state found for target name '%s'", goal_state_name.c_str());
 
  386   goal_state.setToDefaultValues(joint_model_group_, goal_state_name);
 
  387   return setGoal(goal_state);
 
  390 bool PlanningComponent::execute(
bool blocking)
 
  392   if (!last_plan_solution_)
 
  406   return moveit_cpp_->execute(group_name_, last_plan_solution_.trajectory_, blocking);
 
  411   return last_plan_solution_;
 
  418   auto const shortest_trajectory = std::min_element(solutions.begin(), solutions.end(),
 
  422                                                       if (solution_a && solution_b)
 
  424                                                         return robot_trajectory::path_length(*solution_a.trajectory_) <
 
  425                                                                robot_trajectory::path_length(*solution_b.trajectory_);
 
  435   if (shortest_trajectory->trajectory_ != 
nullptr)
 
  444   return *shortest_trajectory;
 
  447 void PlanningComponent::clearContents()
 
  449   considered_start_state_.reset();
 
  451   current_goal_constraints_.clear();