Go to the documentation of this file.
   81                    const std::string& planning_plugin_param_name = 
"planning_plugin",
 
   82                    const std::string& adapter_plugins_param_name = 
"request_adapters");
 
   91                    const std::string& planning_plugin_name, 
const std::vector<std::string>& adapter_plugin_names);
 
  141                     std::vector<std::size_t>& adapter_added_state_index) 
const;
 
  165   const moveit::core::RobotModelConstPtr& 
getRobotModel()
 const 
  180   mutable std::atomic<bool> 
active_;
 
  201   std::unique_ptr<pluginlib::ClassLoader<planning_request_adapter::PlanningRequestAdapter> > 
adapter_plugin_loader_;
 
  202   std::unique_ptr<planning_request_adapter::PlanningRequestAdapterChain> 
adapter_chain_;
 
  
std::string planner_plugin_name_
 
static const std::string DISPLAY_PATH_TOPIC
When motion plans are computed and they are supposed to be automatically displayed,...
 
moveit::core::RobotModelConstPtr robot_model_
 
void terminate() const
Request termination, if a generatePlan() function is currently computing plans.
 
std::unique_ptr< pluginlib::ClassLoader< planning_interface::PlannerManager > > planner_plugin_loader_
 
planning_interface::PlannerManagerPtr planner_instance_
 
const std::vector< std::string > & getAdapterPluginNames() const
Get the names of the planning request adapter plugins used.
 
const moveit::core::RobotModelConstPtr & getRobotModel() const
Get the robot model that this pipeline is using.
 
static const std::string MOTION_CONTACTS_TOPIC
When contacts are found in the solution path reported by a planner, they can be published as markers ...
 
bool check_solution_paths_
Flag indicating whether the reported plans should be checked once again, by the planning pipeline its...
 
static const std::string MOTION_PLAN_REQUEST_TOPIC
When motion planning requests are received and they are supposed to be automatically published,...
 
std::unique_ptr< pluginlib::ClassLoader< planning_request_adapter::PlanningRequestAdapter > > adapter_plugin_loader_
 
bool getPublishReceivedRequests() const
Get the flag set by publishReceivedRequests()
 
bool generatePlan(const planning_scene::PlanningSceneConstPtr &planning_scene, const planning_interface::MotionPlanRequest &req, planning_interface::MotionPlanResponse &res) const
Call the motion planner plugin and the sequence of planning request adapters (if any).
 
void checkSolutionPaths(bool flag)
Pass a flag telling the pipeline whether or not to re-check the solution paths reported by the planne...
 
PlanningPipeline(const moveit::core::RobotModelConstPtr &model, const ros::NodeHandle &pipeline_nh=ros::NodeHandle("~"), const std::string &planning_plugin_param_name="planning_plugin", const std::string &adapter_plugins_param_name="request_adapters")
Given a robot model (model), a node handle (pipeline_nh), initialize the planning pipeline.
 
void displayComputedMotionPlans(bool flag)
Pass a flag telling the pipeline whether or not to publish the computed motion plans on DISPLAY_PATH_...
 
void publishReceivedRequests(bool flag)
Pass a flag telling the pipeline whether or not to publish the received motion planning requests on M...
 
ros::NodeHandle pipeline_nh_
 
const planning_interface::PlannerManagerPtr & getPlannerManager()
Get the planner manager for the loaded planning plugin.
 
MOVEIT_CLASS_FORWARD(PlanningPipeline)
 
moveit_msgs::MotionPlanRequest MotionPlanRequest
 
bool publish_received_requests_
 
bool getCheckSolutionPaths() const
Get the flag set by checkSolutionPaths()
 
std::atomic< bool > active_
 
std::vector< std::string > adapter_plugin_names_
 
ros::Publisher display_path_publisher_
 
bool isActive() const
Get current status of the planning pipeline.
 
bool getDisplayComputedMotionPlans() const
Get the flag set by displayComputedMotionPlans()
 
std::unique_ptr< planning_request_adapter::PlanningRequestAdapterChain > adapter_chain_
 
ros::NodeHandle private_nh_
 
ros::Publisher received_request_publisher_
 
bool display_computed_motion_plans_
Flag indicating whether motion plans should be published as a moveit_msgs::DisplayTrajectory.
 
This class facilitates loading planning plugins and planning request adapted plugins....
 
ros::Publisher contacts_publisher_
 
const std::string & getPlannerPluginName() const
Get the name of the planning plugin used.
 
planning
Author(s): Ioan Sucan 
, Sachin Chitta 
autogenerated on Sat May 3 2025 02:26:19