Public Member Functions | Static Public Attributes | Private Member Functions | Private Attributes | List of all members
planning_pipeline::PlanningPipeline Class Reference

This class facilitates loading planning plugins and planning request adapted plugins. and allows calling planning_interface::PlanningContext::solve() from a loaded planning plugin and the planning_request_adapter::PlanningRequestAdapter plugins, in the specified order. More...

#include <planning_pipeline.h>

Public Member Functions

void checkSolutionPaths (bool flag)
 Pass a flag telling the pipeline whether or not to re-check the solution paths reported by the planner. This is true by default.
More...
 
void displayComputedMotionPlans (bool flag)
 Pass a flag telling the pipeline whether or not to publish the computed motion plans on DISPLAY_PATH_TOPIC. Default is true. More...
 
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). More...
 
bool generatePlan (const planning_scene::PlanningSceneConstPtr &planning_scene, const planning_interface::MotionPlanRequest &req, planning_interface::MotionPlanResponse &res, std::vector< std::size_t > &adapter_added_state_index) const
 Call the motion planner plugin and the sequence of planning request adapters (if any). More...
 
const std::vector< std::string > & getAdapterPluginNames () const
 Get the names of the planning request adapter plugins used. More...
 
bool getCheckSolutionPaths () const
 Get the flag set by checkSolutionPaths() More...
 
bool getDisplayComputedMotionPlans () const
 Get the flag set by displayComputedMotionPlans() More...
 
const planning_interface::PlannerManagerPtr & getPlannerManager ()
 Get the planner manager for the loaded planning plugin. More...
 
const std::string & getPlannerPluginName () const
 Get the name of the planning plugin used. More...
 
bool getPublishReceivedRequests () const
 Get the flag set by publishReceivedRequests() 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...
 
 PlanningPipeline (const moveit::core::RobotModelConstPtr &model, const ros::NodeHandle &pipeline_nh, const std::string &planning_plugin_name, const std::vector< std::string > &adapter_plugin_names)
 Given a robot model (model), a node handle (pipeline_nh), initialize the planning pipeline. More...
 
 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. More...
 
void publishReceivedRequests (bool flag)
 Pass a flag telling the pipeline whether or not to publish the received motion planning requests on MOTION_PLAN_REQUEST_TOPIC. Default is false. More...
 
void terminate () const
 Request termination, if a generatePlan() function is currently computing plans. More...
 

Static Public Attributes

static const std::string DISPLAY_PATH_TOPIC = "display_planned_path"
 When motion plans are computed and they are supposed to be automatically displayed, they are sent to this topic (moveit_msgs::DisplauTrajectory) More...
 
static const std::string MOTION_CONTACTS_TOPIC = "display_contacts"
 When contacts are found in the solution path reported by a planner, they can be published as markers on this topic (visualization_msgs::MarkerArray) More...
 
static const std::string MOTION_PLAN_REQUEST_TOPIC = "motion_plan_request"
 When motion planning requests are received and they are supposed to be automatically published, they are sent to this topic (moveit_msgs::MotionPlanRequest) More...
 

Private Member Functions

void configure ()
 

Private Attributes

std::atomic< bool > active_
 
std::unique_ptr< planning_request_adapter::PlanningRequestAdapterChainadapter_chain_
 
std::unique_ptr< pluginlib::ClassLoader< planning_request_adapter::PlanningRequestAdapter > > adapter_plugin_loader_
 
std::vector< std::string > adapter_plugin_names_
 
bool check_solution_paths_
 Flag indicating whether the reported plans should be checked once again, by the planning pipeline itself. More...
 
ros::Publisher contacts_publisher_
 
bool display_computed_motion_plans_
 Flag indicating whether motion plans should be published as a moveit_msgs::DisplayTrajectory. More...
 
ros::Publisher display_path_publisher_
 
ros::NodeHandle pipeline_nh_
 
planning_interface::PlannerManagerPtr planner_instance_
 
std::unique_ptr< pluginlib::ClassLoader< planning_interface::PlannerManager > > planner_plugin_loader_
 
std::string planner_plugin_name_
 
ros::NodeHandle private_nh_
 
bool publish_received_requests_
 
ros::Publisher received_request_publisher_
 
moveit::core::RobotModelConstPtr robot_model_
 

Detailed Description

This class facilitates loading planning plugins and planning request adapted plugins. and allows calling planning_interface::PlanningContext::solve() from a loaded planning plugin and the planning_request_adapter::PlanningRequestAdapter plugins, in the specified order.

Definition at line 88 of file planning_pipeline.h.

Constructor & Destructor Documentation

◆ PlanningPipeline() [1/2]

planning_pipeline::PlanningPipeline::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.

Parameters
modelThe robot model for which this pipeline is initialized.
pipeline_nhThe ROS node handle that should be used for reading parameters needed for configuration
planning_plugin_param_nameThe name of the ROS parameter under which the name of the planning plugin is specified
adapter_plugins_param_nameThe name of the ROS parameter under which the names of the request adapter plugins are specified (plugin names separated by space; order matters)

Definition at line 51 of file planning_pipeline.cpp.

◆ PlanningPipeline() [2/2]

planning_pipeline::PlanningPipeline::PlanningPipeline ( const moveit::core::RobotModelConstPtr &  model,
const ros::NodeHandle pipeline_nh,
const std::string &  planning_plugin_name,
const std::vector< std::string > &  adapter_plugin_names 
)

Given a robot model (model), a node handle (pipeline_nh), initialize the planning pipeline.

Parameters
modelThe robot model for which this pipeline is initialized.
pipeline_nhThe ROS node handle that should be used for reading parameters needed for configuration
planning_plugin_nameThe name of the planning plugin to load
adapter_plugins_namesThe names of the planning request adapter plugins to load

Definition at line 73 of file planning_pipeline.cpp.

Member Function Documentation

◆ checkSolutionPaths()

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

Pass a flag telling the pipeline whether or not to re-check the solution paths reported by the planner. This is true by default.

Definition at line 201 of file planning_pipeline.cpp.

◆ configure()

void planning_pipeline::PlanningPipeline::configure ( )
private

Definition at line 87 of file planning_pipeline.cpp.

◆ displayComputedMotionPlans()

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

Pass a flag telling the pipeline whether or not to publish the computed motion plans on DISPLAY_PATH_TOPIC. Default is true.

Definition at line 182 of file planning_pipeline.cpp.

◆ generatePlan() [1/2]

bool planning_pipeline::PlanningPipeline::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).

Parameters
planning_sceneThe planning scene where motion planning is to be done
reqThe request for motion planning
resThe motion planning response

Definition at line 210 of file planning_pipeline.cpp.

◆ generatePlan() [2/2]

bool planning_pipeline::PlanningPipeline::generatePlan ( const planning_scene::PlanningSceneConstPtr &  planning_scene,
const planning_interface::MotionPlanRequest req,
planning_interface::MotionPlanResponse res,
std::vector< std::size_t > &  adapter_added_state_index 
) const

Call the motion planner plugin and the sequence of planning request adapters (if any).

Parameters
planning_sceneThe planning scene where motion planning is to be done
reqThe request for motion planning
resThe motion planning response
adapter_added_state_indexSometimes planning request adapters may add states on the solution path (e.g., add the current state of the robot as prefix, when the robot started to plan only from near that state, as the current state itself appears to touch obstacles). This is helpful because the added states should not be considered invalid in all situations.

Definition at line 218 of file planning_pipeline.cpp.

◆ getAdapterPluginNames()

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

Get the names of the planning request adapter plugins used.

Definition at line 217 of file planning_pipeline.h.

◆ getCheckSolutionPaths()

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

Get the flag set by checkSolutionPaths()

Definition at line 182 of file planning_pipeline.h.

◆ getDisplayComputedMotionPlans()

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

Get the flag set by displayComputedMotionPlans()

Definition at line 170 of file planning_pipeline.h.

◆ getPlannerManager()

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

Get the planner manager for the loaded planning plugin.

Definition at line 223 of file planning_pipeline.h.

◆ getPlannerPluginName()

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

Get the name of the planning plugin used.

Definition at line 211 of file planning_pipeline.h.

◆ getPublishReceivedRequests()

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

Get the flag set by publishReceivedRequests()

Definition at line 176 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 229 of file planning_pipeline.h.

◆ isActive()

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

Get current status of the planning pipeline.

Definition at line 235 of file planning_pipeline.h.

◆ publishReceivedRequests()

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

Pass a flag telling the pipeline whether or not to publish the received motion planning requests on MOTION_PLAN_REQUEST_TOPIC. Default is false.

Definition at line 191 of file planning_pipeline.cpp.

◆ terminate()

void planning_pipeline::PlanningPipeline::terminate ( ) const

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

Definition at line 385 of file planning_pipeline.cpp.

Member Data Documentation

◆ active_

std::atomic<bool> planning_pipeline::PlanningPipeline::active_
mutableprivate

Definition at line 244 of file planning_pipeline.h.

◆ adapter_chain_

std::unique_ptr<planning_request_adapter::PlanningRequestAdapterChain> planning_pipeline::PlanningPipeline::adapter_chain_
private

Definition at line 266 of file planning_pipeline.h.

◆ adapter_plugin_loader_

std::unique_ptr<pluginlib::ClassLoader<planning_request_adapter::PlanningRequestAdapter> > planning_pipeline::PlanningPipeline::adapter_plugin_loader_
private

Definition at line 265 of file planning_pipeline.h.

◆ adapter_plugin_names_

std::vector<std::string> planning_pipeline::PlanningPipeline::adapter_plugin_names_
private

Definition at line 267 of file planning_pipeline.h.

◆ check_solution_paths_

bool planning_pipeline::PlanningPipeline::check_solution_paths_
private

Flag indicating whether the reported plans should be checked once again, by the planning pipeline itself.

Definition at line 272 of file planning_pipeline.h.

◆ contacts_publisher_

ros::Publisher planning_pipeline::PlanningPipeline::contacts_publisher_
private

Definition at line 273 of file planning_pipeline.h.

◆ display_computed_motion_plans_

bool planning_pipeline::PlanningPipeline::display_computed_motion_plans_
private

Flag indicating whether motion plans should be published as a moveit_msgs::DisplayTrajectory.

Definition at line 253 of file planning_pipeline.h.

◆ display_path_publisher_

ros::Publisher planning_pipeline::PlanningPipeline::display_path_publisher_
private

Definition at line 254 of file planning_pipeline.h.

◆ DISPLAY_PATH_TOPIC

const std::string planning_pipeline::PlanningPipeline::DISPLAY_PATH_TOPIC = "display_planned_path"
static

When motion plans are computed and they are supposed to be automatically displayed, they are sent to this topic (moveit_msgs::DisplauTrajectory)

Definition at line 125 of file planning_pipeline.h.

◆ MOTION_CONTACTS_TOPIC

const std::string planning_pipeline::PlanningPipeline::MOTION_CONTACTS_TOPIC = "display_contacts"
static

When contacts are found in the solution path reported by a planner, they can be published as markers on this topic (visualization_msgs::MarkerArray)

Definition at line 133 of file planning_pipeline.h.

◆ MOTION_PLAN_REQUEST_TOPIC

const std::string planning_pipeline::PlanningPipeline::MOTION_PLAN_REQUEST_TOPIC = "motion_plan_request"
static

When motion planning requests are received and they are supposed to be automatically published, they are sent to this topic (moveit_msgs::MotionPlanRequest)

Definition at line 129 of file planning_pipeline.h.

◆ pipeline_nh_

ros::NodeHandle planning_pipeline::PlanningPipeline::pipeline_nh_
private

Definition at line 247 of file planning_pipeline.h.

◆ planner_instance_

planning_interface::PlannerManagerPtr planning_pipeline::PlanningPipeline::planner_instance_
private

Definition at line 262 of file planning_pipeline.h.

◆ planner_plugin_loader_

std::unique_ptr<pluginlib::ClassLoader<planning_interface::PlannerManager> > planning_pipeline::PlanningPipeline::planner_plugin_loader_
private

Definition at line 261 of file planning_pipeline.h.

◆ planner_plugin_name_

std::string planning_pipeline::PlanningPipeline::planner_plugin_name_
private

Definition at line 263 of file planning_pipeline.h.

◆ private_nh_

ros::NodeHandle planning_pipeline::PlanningPipeline::private_nh_
private

Definition at line 250 of file planning_pipeline.h.

◆ publish_received_requests_

bool planning_pipeline::PlanningPipeline::publish_received_requests_
private

Flag indicating whether received requests should be published just before beginning processing (useful for debugging)

Definition at line 258 of file planning_pipeline.h.

◆ received_request_publisher_

ros::Publisher planning_pipeline::PlanningPipeline::received_request_publisher_
private

Definition at line 259 of file planning_pipeline.h.

◆ robot_model_

moveit::core::RobotModelConstPtr planning_pipeline::PlanningPipeline::robot_model_
private

Definition at line 269 of file planning_pipeline.h.


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


planning
Author(s): Ioan Sucan , Sachin Chitta
autogenerated on Thu Apr 18 2024 02:24:19