moveit2
The MoveIt Motion Planning Framework for ROS 2.
|
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 | |
PlanningPipeline (const moveit::core::RobotModelConstPtr &model, const std::shared_ptr< rclcpp::Node > &node, const std::string ¶meter_namespace, 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... | |
PlanningPipeline (const moveit::core::RobotModelConstPtr &model, const std::shared_ptr< rclcpp::Node > &node, const std::string ¶meter_namespace, 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... | |
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... | |
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 | 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... | |
bool | getDisplayComputedMotionPlans () const |
Get the flag set by displayComputedMotionPlans() More... | |
bool | getPublishReceivedRequests () const |
Get the flag set by publishReceivedRequests() More... | |
bool | getCheckSolutionPaths () const |
Get the flag set by checkSolutionPaths() 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... | |
void | terminate () const |
Request termination, if a generatePlan() function is currently computing plans. More... | |
const std::string & | getPlannerPluginName () const |
Get the name of the planning plugin used. More... | |
const std::vector< std::string > & | getAdapterPluginNames () const |
Get the names of the planning request adapter plugins used. More... | |
const planning_interface::PlannerManagerPtr & | getPlannerManager () |
Get the planner manager for the loaded planning plugin. More... | |
const moveit::core::RobotModelConstPtr & | getRobotModel () const |
Get the robot model that this pipeline is using. 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::msg::DisplauTrajectory) 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::msg::MotionPlanRequest) 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... | |
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 59 of file planning_pipeline.h.
planning_pipeline::PlanningPipeline::PlanningPipeline | ( | const moveit::core::RobotModelConstPtr & | model, |
const std::shared_ptr< rclcpp::Node > & | node, | ||
const std::string & | parameter_namespace, | ||
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.
model | The robot model for which this pipeline is initialized. |
node | The ROS node that should be used for reading parameters needed for configuration |
the | parameter namespace where the planner configurations are stored |
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 moveit::core::RobotModelConstPtr & | model, |
const std::shared_ptr< rclcpp::Node > & | node, | ||
const std::string & | parameter_namespace, | ||
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.
model | The robot model for which this pipeline is initialized. |
node | The ROS node that should be used for reading parameters needed for configuration |
the | parameter namespace where the planner configurations are stored |
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 83 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 221 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 198 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 232 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 240 of file planning_pipeline.cpp.
|
inline |
Get the names of the planning request adapter plugins used.
Definition at line 159 of file planning_pipeline.h.
|
inline |
Get the flag set by checkSolutionPaths()
Definition at line 124 of file planning_pipeline.h.
|
inline |
Get the flag set by displayComputedMotionPlans()
Definition at line 112 of file planning_pipeline.h.
|
inline |
Get the planner manager for the loaded planning plugin.
Definition at line 165 of file planning_pipeline.h.
|
inline |
Get the name of the planning plugin used.
Definition at line 153 of file planning_pipeline.h.
|
inline |
Get the flag set by publishReceivedRequests()
Definition at line 118 of file planning_pipeline.h.
|
inline |
Get the robot model that this pipeline is using.
Definition at line 171 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 209 of file planning_pipeline.cpp.
void planning_pipeline::PlanningPipeline::terminate | ( | ) | const |
Request termination, if a generatePlan() function is currently computing plans.
Definition at line 406 of file planning_pipeline.cpp.
|
static |
When motion plans are computed and they are supposed to be automatically displayed, they are sent to this topic (moveit_msgs::msg::DisplauTrajectory)
Definition at line 64 of file planning_pipeline.h.
|
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 72 of file planning_pipeline.h.
|
static |
When motion planning requests are received and they are supposed to be automatically published, they are sent to this topic (moveit_msgs::msg::MotionPlanRequest)
Definition at line 68 of file planning_pipeline.h.