Go to the documentation of this file.
70 std::map<std::string, std::string>
config;
131 virtual void clear() = 0;
166 virtual bool initialize(
const moveit::core::RobotModelConstPtr& model,
const std::string& ns);
184 moveit_msgs::MoveItErrorCodes& error_code)
const = 0;
void terminate() const
Request termination, if a solve() function is currently computing plans.
virtual bool solve(MotionPlanResponse &res)=0
Solve the motion planning problem and store the result in res. This function should not clear data st...
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 encounte...
virtual bool terminate()=0
If solve() is running, terminate the computation. Return false if termination not possible....
virtual void clear()=0
Clear the data structures used by the planner.
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 planni...
virtual bool canServiceRequest(const MotionPlanRequest &req) const =0
Determine whether this plugin instance is able to represent this planning request.
virtual ~PlannerManager()
std::map< std::string, PlannerConfigurationSettings > PlannerConfigurationMap
Map from PlannerConfigurationSettings.name to PlannerConfigurationSettings.
virtual bool initialize(const moveit::core::RobotModelConstPtr &model, const std::string &ns)
virtual void setPlannerConfigurations(const PlannerConfigurationMap &pcs)
Specify the settings to be used for specific algorithms.
const std::string & getGroupName() const
Get the name of the group this planning context is for.
planning_scene::PlanningSceneConstPtr planning_scene_
The planning scene for this context.
std::string group_
The group (as in the SRDF) this planning context is for.
This class maintains the representation of the environment as seen by a planning instance....
MOVEIT_CLASS_FORWARD(PlanningScene)
MOVEIT_CLASS_FORWARD(PlanningContext)
std::map< std::string, std::string > config
Key-value pairs of settings that get passed to the planning algorithm.
const std::string & getName() const
Get the name of this planning context.
void setPlanningScene(const planning_scene::PlanningSceneConstPtr &planning_scene)
Set the planning scene for this context.
moveit_msgs::MotionPlanRequest MotionPlanRequest
virtual std::string getDescription() const
Get.
const PlannerConfigurationMap & getPlannerConfigurations() const
Get the settings for a specific algorithm.
const planning_scene::PlanningSceneConstPtr & getPlanningScene() const
Get the planning scene associated to this planning context.
virtual ~PlanningContext()
This namespace includes the base class for MoveIt planners.
std::string name_
The name of this planning context.
PlanningContext(const std::string &name, const std::string &group)
Construct a planning context named name for the group group.
MotionPlanRequest request_
The planning request for this context.
Representation of a particular planning context – the planning scene and the request are known,...
Specify the settings for a particular planning algorithm, for a particular group. The Planner plugin ...
const MotionPlanRequest & getMotionPlanRequest() const
Get the motion plan request associated to this planning context.
std::string group
The group (as defined in the SRDF) this configuration is meant for.
This namespace includes the central class for representing planning scenes.
Base class for a MoveIt planner.
PlannerConfigurationMap config_settings_
All the existing planning configurations. The name of the configuration is the key of the map....
void setMotionPlanRequest(const MotionPlanRequest &request)
Set the planning request for this context.
moveit_core
Author(s): Ioan Sucan
, Sachin Chitta , Acorn Pooley
autogenerated on Sun Nov 3 2024 03:26:14