moveit2
The MoveIt Motion Planning Framework for ROS 2.
|
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 ¶meter_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. | |
PlanningPipeline (const moveit::core::RobotModelConstPtr &model, const std::shared_ptr< rclcpp::Node > &node, const std::string ¶meter_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. | |
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. | |
void | terminate () const |
Request termination, if a generatePlan() function is currently computing plans. | |
const std::vector< std::string > & | getPlannerPluginNames () const |
Get the names of the planning plugins used. | |
const std::vector< std::string > & | getRequestAdapterPluginNames () const |
Get the names of the planning request adapter plugins used. | |
const std::vector< std::string > & | getResponseAdapterPluginNames () const |
Get the names of the planning response adapter plugins in the order they are processed. | |
const moveit::core::RobotModelConstPtr & | getRobotModel () const |
Get the robot model that this pipeline is using. | |
bool | isActive () const |
Get current status of the planning pipeline. | |
std::string | getName () const |
Return the parameter namespace as name of the planning pipeline. | |
const planning_interface::PlannerManagerPtr | getPlannerManager (const std::string &planner_name) |
Get access to planner plugin. | |
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.
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.
model | The robot model for which this pipeline is initialized. |
node | The ROS node that should be used for reading parameters needed for configuration |
parameter_namespace | parameter namespace where the planner configurations are stored |
Definition at line 84 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::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.
model | The robot model for which this pipeline is initialized. |
node | The ROS node that should be used for reading parameters needed for configuration |
parameter_namespace | Parameter namespace where the planner configurations are stored |
planner_plugin_names | Names of the planner plugins to use |
request_adapter_plugin_names | Optional vector of RequestAdapter plugin names |
response_adapter_plugin_names | Optional vector of ResponseAdapter plugin names |
Definition at line 98 of file planning_pipeline.cpp.
|
inline |
Definition at line 136 of file planning_pipeline.h.
|
inline |
Definition at line 134 of file planning_pipeline.h.
|
inline |
Definition at line 158 of file planning_pipeline.h.
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.
planning_scene | The planning scene where motion planning is to be done |
req | The request for motion planning |
res | The motion planning response |
publish_received_requests | Flag indicating whether received requests should be published just before beginning processing (useful for debugging) |
Definition at line 251 of file planning_pipeline.cpp.
|
inline |
Definition at line 151 of file planning_pipeline.h.
|
inline |
Definition at line 145 of file planning_pipeline.h.
|
inline |
Definition at line 137 of file planning_pipeline.h.
|
inline |
Return the parameter namespace as name of the planning pipeline.
Definition at line 223 of file planning_pipeline.h.
|
inline |
Definition at line 171 of file planning_pipeline.h.
|
inline |
Get access to planner plugin.
Definition at line 229 of file planning_pipeline.h.
|
inline |
Definition at line 165 of file planning_pipeline.h.
|
inline |
Get the names of the planning plugins used.
Definition at line 193 of file planning_pipeline.h.
|
inline |
Definition at line 141 of file planning_pipeline.h.
|
inline |
Get the names of the planning request adapter plugins used.
Definition at line 199 of file planning_pipeline.h.
|
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.
|
inline |
Get the robot model that this pipeline is using.
Definition at line 211 of file planning_pipeline.h.
|
inline |
Get current status of the planning pipeline.
Definition at line 217 of file planning_pipeline.h.
|
inline |
Definition at line 135 of file planning_pipeline.h.
void planning_pipeline::PlanningPipeline::terminate | ( | ) | const |
Request termination, if a generatePlan() function is currently computing plans.
Definition at line 376 of file planning_pipeline.cpp.