moveit2
The MoveIt Motion Planning Framework for ROS 2.
Public Member Functions | List of all members
planning_pipeline::PlanningPipeline Class Reference

This class facilitates loading planning plugins and planning adapter plugins. It implements functionality to use the loaded plugins in a motion planning pipeline consisting of PlanningRequestAdapters (Pre-processing), a Planner plugin and PlanningResponseAdapters (Post-processing). More...

#include <planning_pipeline.h>

Public Member Functions

 PlanningPipeline (const moveit::core::RobotModelConstPtr &model, const std::shared_ptr< rclcpp::Node > &node, const std::string &parameter_namespace)
 Given a robot model, a ROS node, and a parameter namespace, initialize the planning pipeline. The planner plugin and adapters are provided in form of ROS parameters. The order of the elements in the adapter vectors corresponds to the order in the motion planning pipeline. More...
 
 PlanningPipeline (const moveit::core::RobotModelConstPtr &model, const std::shared_ptr< rclcpp::Node > &node, const std::string &parameter_namespace, const std::vector< std::string > &planner_plugin_names, const std::vector< std::string > &request_adapter_plugin_names=std::vector< std::string >(), const std::vector< std::string > &response_adapter_plugin_names=std::vector< std::string >())
 Given a robot model, a ROS node, and a parameter namespace, initialize the planning pipeline with the given planner plugin and adapters. The order of the elements in the adapter vectors corresponds to the order in the motion planning pipeline. More...
 
void displayComputedMotionPlans (bool)
 
void publishReceivedRequests (bool)
 
void checkSolutionPaths (bool)
 
bool getDisplayComputedMotionPlans () const
 
bool getPublishReceivedRequests () const
 
bool getCheckSolutionPaths () const
 
const std::vector< std::string > & getAdapterPluginNames () const
 
bool generatePlan (const planning_scene::PlanningSceneConstPtr &, const planning_interface::MotionPlanRequest &, planning_interface::MotionPlanResponse &, const bool, const bool, const bool) const
 
const std::string & getPlannerPluginName () const
 
const planning_interface::PlannerManagerPtr & getPlannerManager ()
 
bool generatePlan (const planning_scene::PlanningSceneConstPtr &planning_scene, const planning_interface::MotionPlanRequest &req, planning_interface::MotionPlanResponse &res, const bool publish_received_requests=false) const
 Call the chain of planning request adapters, motion planner plugin, and planning response adapters in sequence. More...
 
void terminate () const
 Request termination, if a generatePlan() function is currently computing plans. More...
 
const std::vector< std::string > & getPlannerPluginNames () const
 Get the names of the planning plugins used. More...
 
const std::vector< std::string > & getRequestAdapterPluginNames () const
 Get the names of the planning request adapter plugins used. More...
 
const std::vector< std::string > & getResponseAdapterPluginNames () const
 Get the names of the planning response adapter plugins in the order they are processed. More...
 
const moveit::core::RobotModelConstPtr & getRobotModel () const
 Get the robot model that this pipeline is using. More...
 
bool isActive () const
 Get current status of the planning pipeline. More...
 
std::string getName () const
 Return the parameter namespace as name of the planning pipeline. More...
 
const planning_interface::PlannerManagerPtr getPlannerManager (const std::string &planner_name)
 Get access to planner plugin. More...
 

Detailed Description

This class facilitates loading planning plugins and planning adapter plugins. It implements functionality to use the loaded plugins in a motion planning pipeline consisting of PlanningRequestAdapters (Pre-processing), a Planner plugin and PlanningResponseAdapters (Post-processing).

Definition at line 103 of file planning_pipeline.h.

Constructor & Destructor Documentation

◆ PlanningPipeline() [1/2]

planning_pipeline::PlanningPipeline::PlanningPipeline ( const moveit::core::RobotModelConstPtr &  model,
const std::shared_ptr< rclcpp::Node > &  node,
const std::string &  parameter_namespace 
)

Given a robot model, a ROS node, and a parameter namespace, initialize the planning pipeline. The planner plugin and adapters are provided in form of ROS parameters. The order of the elements in the adapter vectors corresponds to the order in the motion planning pipeline.

Parameters
modelThe robot model for which this pipeline is initialized.
nodeThe ROS node that should be used for reading parameters needed for configuration
parameter_namespaceparameter namespace where the planner configurations are stored

Definition at line 84 of file planning_pipeline.cpp.

◆ PlanningPipeline() [2/2]

planning_pipeline::PlanningPipeline::PlanningPipeline ( const moveit::core::RobotModelConstPtr &  model,
const std::shared_ptr< rclcpp::Node > &  node,
const std::string &  parameter_namespace,
const std::vector< std::string > &  planner_plugin_names,
const std::vector< std::string > &  request_adapter_plugin_names = std::vector<std::string>(),
const std::vector< std::string > &  response_adapter_plugin_names = std::vector<std::string>() 
)

Given a robot model, a ROS node, and a parameter namespace, initialize the planning pipeline with the given planner plugin and adapters. The order of the elements in the adapter vectors corresponds to the order in the motion planning pipeline.

Parameters
modelThe robot model for which this pipeline is initialized.
nodeThe ROS node that should be used for reading parameters needed for configuration
parameter_namespaceParameter namespace where the planner configurations are stored
planner_plugin_namesNames of the planner plugins to use
request_adapter_plugin_namesOptional vector of RequestAdapter plugin names
response_adapter_plugin_namesOptional vector of ResponseAdapter plugin names

Definition at line 98 of file planning_pipeline.cpp.

Member Function Documentation

◆ checkSolutionPaths()

void planning_pipeline::PlanningPipeline::checkSolutionPaths ( bool  )
inline

Definition at line 136 of file planning_pipeline.h.

◆ displayComputedMotionPlans()

void planning_pipeline::PlanningPipeline::displayComputedMotionPlans ( bool  )
inline

Definition at line 134 of file planning_pipeline.h.

◆ generatePlan() [1/2]

bool planning_pipeline::PlanningPipeline::generatePlan ( const planning_scene::PlanningSceneConstPtr &  ,
const planning_interface::MotionPlanRequest ,
planning_interface::MotionPlanResponse ,
const bool  ,
const bool  ,
const bool   
) const
inline

Definition at line 158 of file planning_pipeline.h.

◆ generatePlan() [2/2]

bool planning_pipeline::PlanningPipeline::generatePlan ( const planning_scene::PlanningSceneConstPtr &  planning_scene,
const planning_interface::MotionPlanRequest req,
planning_interface::MotionPlanResponse res,
const bool  publish_received_requests = false 
) const

Call the chain of planning request adapters, motion planner plugin, and planning response adapters in sequence.

Parameters
planning_sceneThe planning scene where motion planning is to be done
reqThe request for motion planning
resThe motion planning response
publish_received_requestsFlag indicating whether received requests should be published just before beginning processing (useful for debugging)

Definition at line 251 of file planning_pipeline.cpp.

◆ getAdapterPluginNames()

const std::vector<std::string>& planning_pipeline::PlanningPipeline::getAdapterPluginNames ( ) const
inline

Definition at line 151 of file planning_pipeline.h.

◆ getCheckSolutionPaths()

bool planning_pipeline::PlanningPipeline::getCheckSolutionPaths ( ) const
inline

Definition at line 145 of file planning_pipeline.h.

◆ getDisplayComputedMotionPlans()

bool planning_pipeline::PlanningPipeline::getDisplayComputedMotionPlans ( ) const
inline

Definition at line 137 of file planning_pipeline.h.

◆ getName()

std::string planning_pipeline::PlanningPipeline::getName ( ) const
inline

Return the parameter namespace as name of the planning pipeline.

Definition at line 223 of file planning_pipeline.h.

◆ getPlannerManager() [1/2]

const planning_interface::PlannerManagerPtr& planning_pipeline::PlanningPipeline::getPlannerManager ( )
inline

Definition at line 171 of file planning_pipeline.h.

◆ getPlannerManager() [2/2]

const planning_interface::PlannerManagerPtr planning_pipeline::PlanningPipeline::getPlannerManager ( const std::string &  planner_name)
inline

Get access to planner plugin.

Definition at line 229 of file planning_pipeline.h.

◆ getPlannerPluginName()

const std::string& planning_pipeline::PlanningPipeline::getPlannerPluginName ( ) const
inline

Definition at line 165 of file planning_pipeline.h.

◆ getPlannerPluginNames()

const std::vector<std::string>& planning_pipeline::PlanningPipeline::getPlannerPluginNames ( ) const
inline

Get the names of the planning plugins used.

Definition at line 193 of file planning_pipeline.h.

◆ getPublishReceivedRequests()

bool planning_pipeline::PlanningPipeline::getPublishReceivedRequests ( ) const
inline

Definition at line 141 of file planning_pipeline.h.

◆ getRequestAdapterPluginNames()

const std::vector<std::string>& planning_pipeline::PlanningPipeline::getRequestAdapterPluginNames ( ) const
inline

Get the names of the planning request adapter plugins used.

Definition at line 199 of file planning_pipeline.h.

◆ getResponseAdapterPluginNames()

const std::vector<std::string>& planning_pipeline::PlanningPipeline::getResponseAdapterPluginNames ( ) const
inline

Get the names of the planning response adapter plugins in the order they are processed.

Definition at line 205 of file planning_pipeline.h.

◆ getRobotModel()

const moveit::core::RobotModelConstPtr& planning_pipeline::PlanningPipeline::getRobotModel ( ) const
inline

Get the robot model that this pipeline is using.

Definition at line 211 of file planning_pipeline.h.

◆ isActive()

bool planning_pipeline::PlanningPipeline::isActive ( ) const
inline

Get current status of the planning pipeline.

Definition at line 217 of file planning_pipeline.h.

◆ publishReceivedRequests()

void planning_pipeline::PlanningPipeline::publishReceivedRequests ( bool  )
inline

Definition at line 135 of file planning_pipeline.h.

◆ terminate()

void planning_pipeline::PlanningPipeline::terminate ( ) const

Request termination, if a generatePlan() function is currently computing plans.

Definition at line 371 of file planning_pipeline.cpp.


The documentation for this class was generated from the following files: