moveit2
The MoveIt Motion Planning Framework for ROS 2.
Loading...
Searching...
No Matches
Public Member Functions | List of all members
stomp_moveit::StompPlannerManager Class Reference
Inheritance diagram for stomp_moveit::StompPlannerManager:
Inheritance graph
[legend]
Collaboration diagram for stomp_moveit::StompPlannerManager:
Collaboration graph
[legend]

Public Member Functions

 StompPlannerManager ()=default
 
 ~StompPlannerManager () override=default
 
bool initialize (const moveit::core::RobotModelConstPtr &model, const rclcpp::Node::SharedPtr &node, const std::string &parameter_namespace) override
 
std::string getDescription () const override
 Get a short string that identifies the planning interface.
 
void getPlanningAlgorithms (std::vector< std::string > &algs) const override
 Get the names of the known planning algorithms (values that can be filled as planner_id in the planning request)
 
PlanningContextPtr getPlanningContext (const planning_scene::PlanningSceneConstPtr &planning_scene, const MotionPlanRequest &req, moveit_msgs::msg::MoveItErrorCodes &error_code) const override
 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.
 
bool canServiceRequest (const MotionPlanRequest &req) const override
 Determine whether this plugin instance is able to represent this planning request.
 
void setPlannerConfigurations (const PlannerConfigurationMap &) override
 Specify the settings to be used for specific algorithms.
 
- Public Member Functions inherited from planning_interface::PlannerManager
 PlannerManager ()
 
virtual ~PlannerManager ()
 
PlanningContextPtr getPlanningContext (const planning_scene::PlanningSceneConstPtr &planning_scene, const MotionPlanRequest &req) const
 Calls the function above but ignores the error_code.
 
const PlannerConfigurationMapgetPlannerConfigurations () const
 Get the settings for a specific algorithm.
 
void terminate () const
 Request termination, if a solve() function is currently computing plans.
 

Additional Inherited Members

- Protected Attributes inherited from planning_interface::PlannerManager
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

Definition at line 60 of file stomp_moveit_planner_plugin.cpp.

Constructor & Destructor Documentation

◆ StompPlannerManager()

stomp_moveit::StompPlannerManager::StompPlannerManager ( )
default

◆ ~StompPlannerManager()

stomp_moveit::StompPlannerManager::~StompPlannerManager ( )
overridedefault

Member Function Documentation

◆ canServiceRequest()

bool stomp_moveit::StompPlannerManager::canServiceRequest ( const MotionPlanRequest req) const
inlineoverridevirtual

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

Implements planning_interface::PlannerManager.

Definition at line 115 of file stomp_moveit_planner_plugin.cpp.

Here is the caller graph for this function:

◆ getDescription()

std::string stomp_moveit::StompPlannerManager::getDescription ( ) const
inlineoverridevirtual

Get a short string that identifies the planning interface.

Implements planning_interface::PlannerManager.

Definition at line 77 of file stomp_moveit_planner_plugin.cpp.

◆ getPlanningAlgorithms()

void stomp_moveit::StompPlannerManager::getPlanningAlgorithms ( std::vector< std::string > &  algs) const
inlineoverridevirtual

Get the names of the known planning algorithms (values that can be filled as planner_id in the planning request)

Reimplemented from planning_interface::PlannerManager.

Definition at line 82 of file stomp_moveit_planner_plugin.cpp.

◆ getPlanningContext()

PlanningContextPtr stomp_moveit::StompPlannerManager::getPlanningContext ( const planning_scene::PlanningSceneConstPtr &  planning_scene,
const MotionPlanRequest req,
moveit_msgs::msg::MoveItErrorCodes &  error_code 
) const
inlineoverridevirtual

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

Implements planning_interface::PlannerManager.

Definition at line 87 of file stomp_moveit_planner_plugin.cpp.

Here is the call graph for this function:

◆ initialize()

bool stomp_moveit::StompPlannerManager::initialize ( const moveit::core::RobotModelConstPtr &  model,
const rclcpp::Node::SharedPtr &  node,
const std::string &  parameter_namespace 
)
inlineoverridevirtual

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 parameter_namespace

Reimplemented from planning_interface::PlannerManager.

Definition at line 66 of file stomp_moveit_planner_plugin.cpp.

◆ setPlannerConfigurations()

void stomp_moveit::StompPlannerManager::setPlannerConfigurations ( const PlannerConfigurationMap pcs)
inlineoverridevirtual

Specify the settings to be used for specific algorithms.

Reimplemented from planning_interface::PlannerManager.

Definition at line 131 of file stomp_moveit_planner_plugin.cpp.


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