moveit2
The MoveIt Motion Planning Framework for ROS 2.
|
Base class for a MoveIt planner. More...
#include <planning_interface.h>
Public Member Functions | |
PlannerManager () | |
virtual | ~PlannerManager () |
virtual bool | initialize (const moveit::core::RobotModelConstPtr &model, const rclcpp::Node::SharedPtr &node, const std::string ¶meter_namespace) |
virtual std::string | getDescription () const =0 |
Get a short string that identifies the planning interface. | |
virtual void | getPlanningAlgorithms (std::vector< std::string > &algs) const |
Get the names of the known planning algorithms (values that can be filled as planner_id in the planning request) | |
virtual PlanningContextPtr | getPlanningContext (const planning_scene::PlanningSceneConstPtr &planning_scene, const MotionPlanRequest &req, moveit_msgs::msg::MoveItErrorCodes &error_code) const =0 |
Construct a planning context given the current scene and a planning request. If a problem is encountered, error code is set and empty ptr is returned. The returned motion planner context is clean – the motion planner will start from scratch every time a context is constructed. | |
PlanningContextPtr | getPlanningContext (const planning_scene::PlanningSceneConstPtr &planning_scene, const MotionPlanRequest &req) const |
Calls the function above but ignores the error_code. | |
virtual bool | canServiceRequest (const MotionPlanRequest &req) const =0 |
Determine whether this plugin instance is able to represent this planning request. | |
virtual void | setPlannerConfigurations (const PlannerConfigurationMap &pcs) |
Specify the settings to be used for specific algorithms. | |
const PlannerConfigurationMap & | getPlannerConfigurations () const |
Get the settings for a specific algorithm. | |
void | terminate () const |
Request termination, if a solve() function is currently computing plans. | |
Protected Attributes | |
PlannerConfigurationMap | config_settings_ |
All the existing planning configurations. The name of the configuration is the key of the map. This name can be of the form "group_name[config_name]" if there are particular configurations specified for a group, or of the form "group_name" if default settings are to be used. | |
Base class for a MoveIt planner.
Definition at line 148 of file planning_interface.h.
|
inline |
Definition at line 151 of file planning_interface.h.
|
inlinevirtual |
Definition at line 155 of file planning_interface.h.
|
pure virtual |
Determine whether this plugin instance is able to represent this planning request.
Implemented in stomp_moveit::StompPlannerManager, ompl_interface::OMPLPlannerManager, chomp_interface::CHOMPPlannerManager, planning_pipeline_test::DummyPlannerManager, and pilz_industrial_motion_planner::CommandPlanner.
|
pure virtual |
Get a short string that identifies the planning interface.
Implemented in chomp_interface::CHOMPPlannerManager, ompl_interface::OMPLPlannerManager, pilz_industrial_motion_planner::CommandPlanner, stomp_moveit::StompPlannerManager, and planning_pipeline_test::DummyPlannerManager.
Definition at line 112 of file planning_interface.cpp.
|
inline |
Get the settings for a specific algorithm.
Definition at line 196 of file planning_interface.h.
|
virtual |
Get the names of the known planning algorithms (values that can be filled as planner_id in the planning request)
Reimplemented in chomp_interface::CHOMPPlannerManager, ompl_interface::OMPLPlannerManager, pilz_industrial_motion_planner::CommandPlanner, and stomp_moveit::StompPlannerManager.
Definition at line 124 of file planning_interface.cpp.
PlanningContextPtr planning_interface::PlannerManager::getPlanningContext | ( | const planning_scene::PlanningSceneConstPtr & | planning_scene, |
const MotionPlanRequest & | req | ||
) | const |
Calls the function above but ignores the error_code.
Definition at line 117 of file planning_interface.cpp.
|
pure virtual |
Construct a planning context given the current scene and a planning request. If a problem is encountered, error code is set and empty ptr is returned. The returned motion planner context is clean – the motion planner will start from scratch every time a context is constructed.
planning_scene | A const planning scene to use for planning |
req | The representation of the planning request |
error_code | This is where the error is set if constructing the planning context fails |
Implemented in planning_pipeline_test::DummyPlannerManager, stomp_moveit::StompPlannerManager, chomp_interface::CHOMPPlannerManager, ompl_interface::OMPLPlannerManager, and pilz_industrial_motion_planner::CommandPlanner.
|
virtual |
Initialize a planner. This function will be called after the construction of the plugin, before any other call is made. It is assumed that motion plans will be computed for the robot described by model and that any exposed ROS functionality or required ROS parameters are namespaced by parameter_namespace
Reimplemented in chomp_interface::CHOMPPlannerManager, pilz_industrial_motion_planner::CommandPlanner, ompl_interface::OMPLPlannerManager, and stomp_moveit::StompPlannerManager.
Definition at line 106 of file planning_interface.cpp.
|
virtual |
Specify the settings to be used for specific algorithms.
Reimplemented in stomp_moveit::StompPlannerManager, and ompl_interface::OMPLPlannerManager.
Definition at line 130 of file planning_interface.cpp.
void planning_interface::PlannerManager::terminate | ( | ) | const |
Request termination, if a solve() function is currently computing plans.
Definition at line 135 of file planning_interface.cpp.
|
protected |
All the existing planning configurations. The name of the configuration is the key of the map. This name can be of the form "group_name[config_name]" if there are particular configurations specified for a group, or of the form "group_name" if default settings are to be used.
Definition at line 210 of file planning_interface.h.