Base class for a MoveIt! planner. More...
#include <planning_interface.h>
Public Member Functions | |
virtual bool | canServiceRequest (const MotionPlanRequest &req) const =0 |
Determine whether this plugin instance is able to represent this planning request. More... | |
virtual std::string | getDescription () const |
Get. More... | |
const PlannerConfigurationMap & | getPlannerConfigurations () const |
Get the settings for a specific algorithm. 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::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 | initialize (const robot_model::RobotModelConstPtr &model, const std::string &ns) |
PlannerManager () | |
virtual void | setPlannerConfigurations (const PlannerConfigurationMap &pcs) |
Specify the settings to be used for specific algorithms. More... | |
void | terminate () const |
Request termination, if a solve() function is currently computing plans. More... | |
virtual | ~PlannerManager () |
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... | |
Base class for a MoveIt! planner.
Definition at line 151 of file planning_interface.h.
|
inline |
Definition at line 154 of file planning_interface.h.
|
inlinevirtual |
Definition at line 158 of file planning_interface.h.
|
pure virtual |
Determine whether this plugin instance is able to represent this planning request.
|
virtual |
Get.
a short string that identifies the planning interface
Definition at line 99 of file planning_interface.cpp.
|
inline |
Get the settings for a specific algorithm.
Definition at line 198 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)
Definition at line 111 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 |
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 104 of file planning_interface.cpp.
|
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 ns
Definition at line 94 of file planning_interface.cpp.
|
virtual |
Specify the settings to be used for specific algorithms.
Definition at line 117 of file planning_interface.cpp.
void planning_interface::PlannerManager::terminate | ( | ) | const |
Request termination, if a solve() function is currently computing plans.
Definition at line 122 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 212 of file planning_interface.h.