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. | |
| 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. | |
| 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). | |
| 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). | |
| const std::vector< std::string > & | getAdapterPluginNames () const | 
| Get the names of the planning request adapter plugins used. | |
| bool | getCheckSolutionPaths () const | 
| Get the flag set by checkSolutionPaths() | |
| bool | getDisplayComputedMotionPlans () const | 
| Get the flag set by displayComputedMotionPlans() | |
| const planning_interface::PlannerManagerPtr & | getPlannerManager () | 
| Get the planner manager for the loaded planning plugin. | |
| const std::string & | getPlannerPluginName () const | 
| Get the name of the planning plugin used. | |
| bool | getPublishReceivedRequests () const | 
| Get the flag set by publishReceivedRequests() | |
| const robot_model::RobotModelConstPtr & | getRobotModel () const | 
| Get the robot model that this pipeline is using. | |
| PlanningPipeline (const robot_model::RobotModelConstPtr &model, const ros::NodeHandle &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 (nh), initialize the planning pipeline. | |
| PlanningPipeline (const robot_model::RobotModelConstPtr &model, const ros::NodeHandle &nh, const std::string &planning_plugin_name, const std::vector< std::string > &adapter_plugin_names) | |
| Given a robot model (model), a node handle (nh), initialize the planning pipeline. | |
| 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. | |
| void | terminate () const | 
| Request termination, if a generatePlan() function is currently computing plans. | |
| 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) | |
| 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) | |
| 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) | |
| Private Member Functions | |
| void | configure () | 
| Private Attributes | |
| boost::scoped_ptr < planning_request_adapter::PlanningRequestAdapterChain > | adapter_chain_ | 
| boost::scoped_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. | |
| ros::Publisher | contacts_publisher_ | 
| bool | display_computed_motion_plans_ | 
| Flag indicating whether motion plans should be published as a moveit_msgs::DisplayTrajectory. | |
| ros::Publisher | display_path_publisher_ | 
| robot_model::RobotModelConstPtr | kmodel_ | 
| ros::NodeHandle | nh_ | 
| planning_interface::PlannerManagerPtr | planner_instance_ | 
| boost::scoped_ptr < pluginlib::ClassLoader < planning_interface::PlannerManager > > | planner_plugin_loader_ | 
| std::string | planner_plugin_name_ | 
| bool | publish_received_requests_ | 
| Flag indicating whether received requests should be published just before beginning processing (useful for debugging) | |
| ros::Publisher | received_request_publisher_ | 
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 56 of file planning_pipeline.h.
| planning_pipeline::PlanningPipeline::PlanningPipeline | ( | const robot_model::RobotModelConstPtr & | model, | 
| const ros::NodeHandle & | 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 (nh), initialize the planning pipeline.
| model | The robot model for which this pipeline is initialized. | 
| nh | The ROS node handle that should be used for reading parameters needed for configuration | 
| planning_plugin_param_name | The name of the ROS parameter under which the name of the planning plugin is specified | 
| adapter_plugins_param_name | The 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.
| planning_pipeline::PlanningPipeline::PlanningPipeline | ( | const robot_model::RobotModelConstPtr & | model, | 
| const ros::NodeHandle & | nh, | ||
| const std::string & | planning_plugin_name, | ||
| const std::vector< std::string > & | adapter_plugin_names | ||
| ) | 
Given a robot model (model), a node handle (nh), initialize the planning pipeline.
| model | The robot model for which this pipeline is initialized. | 
| nh | The ROS node handle that should be used for reading parameters needed for configuration | 
| planning_plugin_name | The name of the planning plugin to load | 
| adapter_plugins_names | The names of the planning request adapter plugins to load | 
Definition at line 74 of file planning_pipeline.cpp.
| 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 190 of file planning_pipeline.cpp.
| void planning_pipeline::PlanningPipeline::configure | ( | ) |  [private] | 
Definition at line 86 of file planning_pipeline.cpp.
| 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 170 of file planning_pipeline.cpp.
| 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).
| planning_scene | The planning scene where motion planning is to be done | 
| req | The request for motion planning | 
| res | The motion planning response | 
Definition at line 200 of file planning_pipeline.cpp.
| 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).
| planning_scene | The planning scene where motion planning is to be done | 
| req | The request for motion planning | 
| res | The motion planning response | 
| adapter_added_state_index | Sometimes 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 208 of file planning_pipeline.cpp.
| const std::vector<std::string>& planning_pipeline::PlanningPipeline::getAdapterPluginNames | ( | ) | const  [inline] | 
Get the names of the planning request adapter plugins used.
Definition at line 147 of file planning_pipeline.h.
| bool planning_pipeline::PlanningPipeline::getCheckSolutionPaths | ( | ) | const  [inline] | 
Get the flag set by checkSolutionPaths()
Definition at line 114 of file planning_pipeline.h.
| bool planning_pipeline::PlanningPipeline::getDisplayComputedMotionPlans | ( | ) | const  [inline] | 
Get the flag set by displayComputedMotionPlans()
Definition at line 102 of file planning_pipeline.h.
| const planning_interface::PlannerManagerPtr& planning_pipeline::PlanningPipeline::getPlannerManager | ( | ) |  [inline] | 
Get the planner manager for the loaded planning plugin.
Definition at line 153 of file planning_pipeline.h.
| const std::string& planning_pipeline::PlanningPipeline::getPlannerPluginName | ( | ) | const  [inline] | 
Get the name of the planning plugin used.
Definition at line 141 of file planning_pipeline.h.
| bool planning_pipeline::PlanningPipeline::getPublishReceivedRequests | ( | ) | const  [inline] | 
Get the flag set by publishReceivedRequests()
Definition at line 108 of file planning_pipeline.h.
| const robot_model::RobotModelConstPtr& planning_pipeline::PlanningPipeline::getRobotModel | ( | ) | const  [inline] | 
Get the robot model that this pipeline is using.
Definition at line 159 of file planning_pipeline.h.
| 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 180 of file planning_pipeline.cpp.
| void planning_pipeline::PlanningPipeline::terminate | ( | ) | const | 
Request termination, if a generatePlan() function is currently computing plans.
Definition at line 346 of file planning_pipeline.cpp.
| boost::scoped_ptr<planning_request_adapter::PlanningRequestAdapterChain> planning_pipeline::PlanningPipeline::adapter_chain_  [private] | 
Definition at line 183 of file planning_pipeline.h.
| boost::scoped_ptr<pluginlib::ClassLoader<planning_request_adapter::PlanningRequestAdapter> > planning_pipeline::PlanningPipeline::adapter_plugin_loader_  [private] | 
Definition at line 182 of file planning_pipeline.h.
| std::vector<std::string> planning_pipeline::PlanningPipeline::adapter_plugin_names_  [private] | 
Definition at line 184 of file planning_pipeline.h.
| 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 189 of file planning_pipeline.h.
Definition at line 190 of file planning_pipeline.h.
Flag indicating whether motion plans should be published as a moveit_msgs::DisplayTrajectory.
Definition at line 171 of file planning_pipeline.h.
Definition at line 172 of file planning_pipeline.h.
| 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 62 of file planning_pipeline.h.
| robot_model::RobotModelConstPtr planning_pipeline::PlanningPipeline::kmodel_  [private] | 
Definition at line 186 of file planning_pipeline.h.
| 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 68 of file planning_pipeline.h.
| 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 65 of file planning_pipeline.h.
Definition at line 168 of file planning_pipeline.h.
| planning_interface::PlannerManagerPtr planning_pipeline::PlanningPipeline::planner_instance_  [private] | 
Definition at line 179 of file planning_pipeline.h.
| boost::scoped_ptr<pluginlib::ClassLoader<planning_interface::PlannerManager> > planning_pipeline::PlanningPipeline::planner_plugin_loader_  [private] | 
Definition at line 178 of file planning_pipeline.h.
| std::string planning_pipeline::PlanningPipeline::planner_plugin_name_  [private] | 
Definition at line 180 of file planning_pipeline.h.
Flag indicating whether received requests should be published just before beginning processing (useful for debugging)
Definition at line 175 of file planning_pipeline.h.
Definition at line 176 of file planning_pipeline.h.