48 static const rclcpp::Logger LOGGER =
 
   49     rclcpp::get_logger(
"moveit.pilz_industrial_motion_planner.move_group_sequence_service");
 
   60   command_list_manager_ = std::make_unique<pilz_industrial_motion_planner::CommandListManager>(
 
   61       context_->moveit_cpp_->getNode(), 
context_->planning_scene_monitor_->getRobotModel());
 
   63   sequence_service_ = 
context_->moveit_cpp_->getNode()->create_service<moveit_msgs::srv::GetMotionSequence>(
 
   64       SEQUENCE_SERVICE_NAME,
 
   65       [
this](
const moveit_msgs::srv::GetMotionSequence::Request::SharedPtr& req,
 
   66              const moveit_msgs::srv::GetMotionSequence::Response::SharedPtr& res) { 
return plan(req, res); });
 
   69 bool MoveGroupSequenceService::plan(
const moveit_msgs::srv::GetMotionSequence::Request::SharedPtr& req,
 
   70                                     const moveit_msgs::srv::GetMotionSequence::Response::SharedPtr& res)
 
   73   if (req->request.items.empty())
 
   75     RCLCPP_WARN(LOGGER, 
"Received empty request. That's ok but maybe not what you intended.");
 
   76     res->response.error_code.val = moveit_msgs::msg::MoveItErrorCodes::SUCCESS;
 
   80   rclcpp::Time planning_start = 
context_->moveit_cpp_->getNode()->now();
 
   90       RCLCPP_ERROR_STREAM(LOGGER, 
"Could not load planning pipeline " << req->request.items[0].req.pipeline_id);
 
   91       res->response.error_code.val = moveit_msgs::msg::MoveItErrorCodes::FAILURE;
 
   95     auto scene = 
context_->planning_scene_monitor_->copyPlanningScene();
 
   96     traj_vec = command_list_manager_->solve(
scene, 
context_->planning_pipeline_, req->request);
 
   98   catch (
const MoveItErrorCodeException& ex)
 
  100     RCLCPP_ERROR_STREAM(LOGGER, 
"Planner threw an exception (error code: " << ex.getErrorCode() << 
"): " << ex.what());
 
  101     res->response.error_code.val = ex.getErrorCode();
 
  105   catch (
const std::exception& ex)
 
  107     RCLCPP_ERROR_STREAM(LOGGER, 
"Planner threw an exception: " << ex.what());
 
  113   res->response.planned_trajectories.resize(traj_vec.size());
 
  114   for (RobotTrajCont::size_type i = 0; i < traj_vec.size(); ++i)
 
  117                                                   res->response.planned_trajectories.at(i));
 
  119   res->response.error_code.val = moveit_msgs::msg::MoveItErrorCodes::SUCCESS;
 
  120   res->response.planning_time = (
context_->moveit_cpp_->getNode()->now() - planning_start).seconds();
 
  126 #include <pluginlib/class_list_macros.hpp> 
PLUGINLIB_EXPORT_CLASS(cached_ik_kinematics_plugin::CachedIKKinematicsPlugin< kdl_kinematics_plugin::KDLKinematicsPlugin >, kinematics::KinematicsBase)
 
void convertToMsg(const std::vector< plan_execution::ExecutableTrajectory > &trajectory, moveit_msgs::msg::RobotState &first_state_msg, std::vector< moveit_msgs::msg::RobotTrajectory > &trajectory_msg) const
 
MoveGroupContextPtr context_
 
planning_pipeline::PlanningPipelinePtr resolvePlanningPipeline(const std::string &pipeline_id) const
 
Provide service to blend multiple trajectories in the form of a MoveGroup capability (plugin).
 
void initialize() override
 
MoveGroupSequenceService()
 
~MoveGroupSequenceService() override
 
std::vector< robot_trajectory::RobotTrajectoryPtr > RobotTrajCont