moveit2
The MoveIt Motion Planning Framework for ROS 2.
Public Member Functions | Protected Attributes | List of all members
planning_interface::PlannerManager Class Referenceabstract

Base class for a MoveIt planner. More...

#include <planning_interface.h>

Inheritance diagram for planning_interface::PlannerManager:
Inheritance graph
[legend]

Public Member Functions

 PlannerManager ()
 
virtual ~PlannerManager ()
 
virtual bool initialize (const moveit::core::RobotModelConstPtr &model, const rclcpp::Node::SharedPtr &node, const std::string &parameter_namespace)
 
virtual std::string getDescription () const
 Get. More...
 
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) More...
 
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. More...
 
PlanningContextPtr getPlanningContext (const planning_scene::PlanningSceneConstPtr &planning_scene, const MotionPlanRequest &req) const
 Calls the function above but ignores the error_code. More...
 
virtual bool canServiceRequest (const MotionPlanRequest &req) const =0
 Determine whether this plugin instance is able to represent this planning request. More...
 
virtual void setPlannerConfigurations (const PlannerConfigurationMap &pcs)=0
 Specify the settings to be used for specific algorithms. More...
 
const PlannerConfigurationMapgetPlannerConfigurations () const
 Get the settings for a specific algorithm. More...
 
void terminate () const
 Request termination, if a solve() function is currently computing plans. More...
 

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. More...
 

Detailed Description

Base class for a MoveIt planner.

Definition at line 152 of file planning_interface.h.

Constructor & Destructor Documentation

◆ PlannerManager()

planning_interface::PlannerManager::PlannerManager ( )
inline

Definition at line 155 of file planning_interface.h.

◆ ~PlannerManager()

virtual planning_interface::PlannerManager::~PlannerManager ( )
inlinevirtual

Definition at line 159 of file planning_interface.h.

Member Function Documentation

◆ canServiceRequest()

virtual bool planning_interface::PlannerManager::canServiceRequest ( const MotionPlanRequest req) const
pure virtual

Determine whether this plugin instance is able to represent this planning request.

Implemented in pilz_industrial_motion_planner::CommandPlanner, chomp_interface::CHOMPPlannerManager, and ompl_interface::OMPLPlannerManager.

◆ getDescription()

std::string planning_interface::PlannerManager::getDescription ( ) const
virtual

◆ getPlannerConfigurations()

const PlannerConfigurationMap& planning_interface::PlannerManager::getPlannerConfigurations ( ) const
inline

Get the settings for a specific algorithm.

Definition at line 200 of file planning_interface.h.

◆ getPlanningAlgorithms()

void planning_interface::PlannerManager::getPlanningAlgorithms ( std::vector< std::string > &  algs) const
virtual

Get the names of the known planning algorithms (values that can be filled as planner_id in the planning request)

Reimplemented in trajopt_interface::TrajOptPlannerManager, pilz_industrial_motion_planner::CommandPlanner, ompl_interface::OMPLPlannerManager, and chomp_interface::CHOMPPlannerManager.

Definition at line 115 of file planning_interface.cpp.

◆ getPlanningContext() [1/2]

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 108 of file planning_interface.cpp.

Here is the call graph for this function:

◆ getPlanningContext() [2/2]

virtual PlanningContextPtr planning_interface::PlannerManager::getPlanningContext ( const planning_scene::PlanningSceneConstPtr &  planning_scene,
const MotionPlanRequest req,
moveit_msgs::msg::MoveItErrorCodes &  error_code 
) const
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.

Parameters
planning_sceneA const planning scene to use for planning
reqThe representation of the planning request
error_codeThis is where the error is set if constructing the planning context fails

Implemented in pilz_industrial_motion_planner::CommandPlanner, ompl_interface::OMPLPlannerManager, and chomp_interface::CHOMPPlannerManager.

Here is the caller graph for this function:

◆ initialize()

bool planning_interface::PlannerManager::initialize ( const moveit::core::RobotModelConstPtr &  model,
const rclcpp::Node::SharedPtr &  node,
const std::string &  parameter_namespace 
)
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 ompl_interface::OMPLPlannerManager, pilz_industrial_motion_planner::CommandPlanner, and chomp_interface::CHOMPPlannerManager.

Definition at line 97 of file planning_interface.cpp.

Here is the caller graph for this function:

◆ setPlannerConfigurations()

void planning_interface::PlannerManager::setPlannerConfigurations ( const PlannerConfigurationMap pcs)
pure virtual

Specify the settings to be used for specific algorithms.

Implemented in pilz_industrial_motion_planner::CommandPlanner, chomp_interface::CHOMPPlannerManager, and ompl_interface::OMPLPlannerManager.

Definition at line 121 of file planning_interface.cpp.

◆ terminate()

void planning_interface::PlannerManager::terminate ( ) const

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

Definition at line 126 of file planning_interface.cpp.

Here is the call graph for this function:

Member Data Documentation

◆ config_settings_

PlannerConfigurationMap planning_interface::PlannerManager::config_settings_
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 214 of file planning_interface.h.


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