37 #ifndef MOVEIT_PLANNING_INTERFACE_PLANNING_INTERFACE_ 38 #define MOVEIT_PLANNING_INTERFACE_PLANNING_INTERFACE_ 78 std::map<std::string, std::string>
config;
111 return planning_scene_;
121 void setPlanningScene(
const planning_scene::PlanningSceneConstPtr&
planning_scene);
136 virtual bool terminate() = 0;
139 virtual void clear() = 0;
174 virtual bool initialize(
const robot_model::RobotModelConstPtr& model,
const std::string& ns);
177 virtual std::string getDescription()
const;
181 virtual void getPlanningAlgorithms(std::vector<std::string>& algs)
const;
190 virtual PlanningContextPtr getPlanningContext(
const planning_scene::PlanningSceneConstPtr&
planning_scene,
192 moveit_msgs::MoveItErrorCodes& error_code)
const = 0;
195 PlanningContextPtr getPlanningContext(
const planning_scene::PlanningSceneConstPtr& planning_scene,
202 virtual void setPlannerConfigurations(
const PlannerConfigurationMap& pcs);
207 return config_settings_;
211 void terminate()
const;
MOVEIT_CLASS_FORWARD(PlanningScene)
ros::NodeHandle getConfigNodeHandle(const ros::NodeHandle &nh=ros::NodeHandle("~"))
Retrieve NodeHandle/namespace defining the PlanningPipeline parameters Traditionally, these were directly defined in the private namespace of the move_group node. Since MoveIt 1.1.2 multiple pipeline configs are supported in parallel. In Melodic we support this new scheme by allowing to choose the default pipeline, specified via the parameter ~default_planning_pipeline.
ROSCONSOLE_DECL void initialize()
virtual ~PlannerManager()
Specify the settings for a particular planning algorithm, for a particular group. The Planner plugin ...
std::map< std::string, PlannerConfigurationSettings > PlannerConfigurationMap
Map from PlannerConfigurationSettings.name to PlannerConfigurationSettings.
std::map< std::string, std::string > config
Key-value pairs of settings that get passed to the planning algorithm.
Representation of a particular planning context – the planning scene and the request are known...
const std::string & getGroupName() const
Get the name of the group this planning context is for.
std::string group_
The group (as in the SRDF) this planning context is for.
const PlannerConfigurationMap & getPlannerConfigurations() const
Get the settings for a specific algorithm.
planning_scene::PlanningSceneConstPtr planning_scene_
The planning scene for this context.
const std::string & getName() const
Get the name of this planning context.
This class maintains the representation of the environment as seen by a planning instance. The environment geometry, the robot geometry and state are maintained.
This namespace includes the central class for representing planning contexts.
moveit_msgs::MotionPlanRequest MotionPlanRequest
std::string group
The group (as defined in the SRDF) this configuration is meant for.
std::string name_
The name of this planning context.
This namespace includes the base class for MoveIt! planners.
const planning_scene::PlanningSceneConstPtr & getPlanningScene() const
Get the planning scene associated to this planning context.
MotionPlanRequest request_
The planning request for this context.
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...
const MotionPlanRequest & getMotionPlanRequest() const
Get the motion plan request associated to this planning context.