43 static const rclcpp::Logger
LOGGER = rclcpp::get_logger(
"moveit_move_group_capabilities_base.move_group_context");
46 const std::string& default_planning_pipeline,
47 bool allow_trajectory_execution,
bool debug)
49 , planning_scene_monitor_(
moveit_cpp->getPlanningSceneMonitor())
50 , allow_trajectory_execution_(allow_trajectory_execution)
54 const auto& pipelines =
moveit_cpp->getPlanningPipelines();
55 const auto default_pipeline_it = pipelines.find(default_planning_pipeline);
56 if (default_pipeline_it != pipelines.end())
71 "Failed to find default PlanningPipeline '%s' - please check MoveGroup's planning pipeline configuration.",
72 default_planning_pipeline.c_str());
85 plan_execution_.reset();
86 trajectory_execution_manager_.reset();
87 planning_pipeline_.reset();
88 planning_scene_monitor_.reset();
93 const planning_interface::PlannerManagerPtr& planner_interface = planning_pipeline_->getPlannerManager();
94 if (planner_interface)
96 RCLCPP_INFO_STREAM(LOGGER,
"MoveGroup context using planning plugin " << planning_pipeline_->getPlannerPluginName());
97 RCLCPP_INFO_STREAM(LOGGER,
"MoveGroup context initialization complete");
102 RCLCPP_WARN_STREAM(LOGGER,
"MoveGroup running was unable to load " << planning_pipeline_->getPlannerPluginName());
const rclcpp::Logger LOGGER
moveit_cpp::MoveItCppPtr moveit_cpp_
plan_execution::PlanExecutionPtr plan_execution_
bool allow_trajectory_execution_
trajectory_execution_manager::TrajectoryExecutionManagerPtr trajectory_execution_manager_
MoveGroupContext(const moveit_cpp::MoveItCppPtr &moveit_cpp, const std::string &default_planning_pipeline, bool allow_trajectory_execution=false, bool debug=false)
planning_pipeline::PlanningPipelinePtr planning_pipeline_
planning_scene_monitor::PlanningSceneMonitorPtr planning_scene_monitor_