Public Member Functions | Protected Attributes
planning_interface::PlannerManager Class Reference

Base class for a MoveIt planner. More...

#include <planning_interface.h>

List of all members.

Public Member Functions

virtual bool canServiceRequest (const MotionPlanRequest &req) const =0
 Determine whether this plugin instance is able to represent this planning request.
virtual std::string getDescription () const
 Get.
const PlannerConfigurationMapgetPlannerConfigurations () const
 Get the settings for a specific algorithm.
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::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 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.
void terminate () const
 Request termination, if a solve() function is currently computing plans.
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.

Detailed Description

Base class for a MoveIt planner.

Definition at line 143 of file planning_interface.h.


Constructor & Destructor Documentation

Definition at line 147 of file planning_interface.h.

Definition at line 151 of file planning_interface.h.


Member Function Documentation

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

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

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

Get.

a short string that identifies the planning interface

Definition at line 96 of file planning_interface.cpp.

Get the settings for a specific algorithm.

Definition at line 186 of file planning_interface.h.

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)

Definition at line 108 of file planning_interface.cpp.

virtual PlanningContextPtr planning_interface::PlannerManager::getPlanningContext ( const planning_scene::PlanningSceneConstPtr planning_scene,
const MotionPlanRequest req,
moveit_msgs::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
planning_interface::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 101 of file planning_interface.cpp.

bool planning_interface::PlannerManager::initialize ( const robot_model::RobotModelConstPtr model,
const std::string &  ns 
) [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 91 of file planning_interface.cpp.

Specify the settings to be used for specific algorithms.

Definition at line 114 of file planning_interface.cpp.

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

Definition at line 119 of file planning_interface.cpp.


Member Data Documentation

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 201 of file planning_interface.h.


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


moveit_core
Author(s): Ioan Sucan , Sachin Chitta , Acorn Pooley
autogenerated on Mon Oct 6 2014 02:24:48