43#include <rclcpp/node.hpp>
46#include <rclcpp/rclcpp.hpp>
68 std::map<std::string, std::string>
config;
164 virtual bool initialize(
const moveit::core::RobotModelConstPtr& model,
const rclcpp::Node::SharedPtr& node,
165 const std::string& parameter_namespace);
183 moveit_msgs::msg::MoveItErrorCodes& error_code)
const = 0;
#define MOVEIT_CLASS_FORWARD(C)
Base class for a MoveIt planner.
virtual bool canServiceRequest(const MotionPlanRequest &req) const =0
Determine whether this plugin instance is able to represent this planning request.
void terminate() const
Request termination, if a solve() function is currently computing plans.
virtual std::string getDescription() const =0
Get a short string that identifies the planning interface.
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 void setPlannerConfigurations(const PlannerConfigurationMap &pcs)
Specify the settings to be used for specific algorithms.
const PlannerConfigurationMap & getPlannerConfigurations() const
Get the settings for a specific algorithm.
virtual bool initialize(const moveit::core::RobotModelConstPtr &model, const rclcpp::Node::SharedPtr &node, const std::string ¶meter_namespace)
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 encounte...
PlannerConfigurationMap config_settings_
All the existing planning configurations. The name of the configuration is the key of the map....
virtual ~PlannerManager()
Representation of a particular planning context – the planning scene and the request are known,...
void setPlanningScene(const planning_scene::PlanningSceneConstPtr &planning_scene)
Set the planning scene for this context.
planning_scene::PlanningSceneConstPtr planning_scene_
The planning scene for this context.
virtual void solve(MotionPlanDetailedResponse &res)=0
Solve the motion planning problem and store the detailed result in res. This function should not clea...
std::string name_
The name of this planning context.
MotionPlanRequest request_
The planning request for this context.
const MotionPlanRequest & getMotionPlanRequest() const
Get the motion plan request associated to this planning context.
const planning_scene::PlanningSceneConstPtr & getPlanningScene() const
Get the planning scene associated to this planning context.
virtual void solve(MotionPlanResponse &res)=0
Solve the motion planning problem and store the result in res. This function should not clear data st...
std::string group_
The group (as in the SRDF) this planning context is for.
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 ~PlanningContext()
const std::string & getGroupName() const
Get the name of the group this planning context is for.
void setMotionPlanRequest(const MotionPlanRequest &request)
Set the planning request for this context.
const std::string & getName() const
Get the name of this planning context.
This namespace includes the base class for MoveIt planners.
std::map< std::string, PlannerConfigurationSettings > PlannerConfigurationMap
Map from PlannerConfigurationSettings.name to PlannerConfigurationSettings.
moveit_msgs::msg::MotionPlanRequest MotionPlanRequest
This namespace includes the central class for representing planning contexts.
Response to a planning query.
Specify the settings for a particular planning algorithm, for a particular group. The Planner plugin ...
std::map< std::string, std::string > config
Key-value pairs of settings that get passed to the planning algorithm.
std::string group
The group (as defined in the SRDF) this configuration is meant for.