moveit2
The MoveIt Motion Planning Framework for ROS 2.
Public Member Functions | Protected Attributes | List of all members
chomp_interface::CHOMPPlannerManager Class Reference
Inheritance diagram for chomp_interface::CHOMPPlannerManager:
Inheritance graph
[legend]
Collaboration diagram for chomp_interface::CHOMPPlannerManager:
Collaboration graph
[legend]

Public Member Functions

 CHOMPPlannerManager ()
 
bool initialize (const moveit::core::RobotModelConstPtr &model, const rclcpp::Node::SharedPtr &node, const std::string &) override
 
planning_interface::PlanningContextPtr getPlanningContext (const planning_scene::PlanningSceneConstPtr &planning_scene, const planning_interface::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. More...
 
bool canServiceRequest (const planning_interface::MotionPlanRequest &) const override
 Determine whether this plugin instance is able to represent this planning request. More...
 
std::string getDescription () const override
 Get a short string that identifies the planning interface. More...
 
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) More...
 
- 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. More...
 
virtual void setPlannerConfigurations (const PlannerConfigurationMap &pcs)
 Specify the settings to be used for specific algorithms. More...
 
const PlannerConfigurationMapgetPlannerConfigurations () const
 Get the settings for a specific algorithm. More...
 
void terminate () const
 Request termination, if a solve() function is currently computing plans. More...
 

Protected Attributes

std::map< std::string, CHOMPPlanningContextPtr > planning_contexts_
 
- 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. More...
 

Detailed Description

Definition at line 55 of file chomp_plugin.cpp.

Constructor & Destructor Documentation

◆ CHOMPPlannerManager()

chomp_interface::CHOMPPlannerManager::CHOMPPlannerManager ( )
inline

Definition at line 58 of file chomp_plugin.cpp.

Member Function Documentation

◆ canServiceRequest()

bool chomp_interface::CHOMPPlannerManager::canServiceRequest ( const planning_interface::MotionPlanRequest req) const
inlineoverridevirtual

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

Implements planning_interface::PlannerManager.

Definition at line 105 of file chomp_plugin.cpp.

◆ getDescription()

std::string chomp_interface::CHOMPPlannerManager::getDescription ( ) const
inlineoverridevirtual

Get a short string that identifies the planning interface.

Implements planning_interface::PlannerManager.

Definition at line 112 of file chomp_plugin.cpp.

◆ getPlanningAlgorithms()

void chomp_interface::CHOMPPlannerManager::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 117 of file chomp_plugin.cpp.

◆ getPlanningContext()

planning_interface::PlanningContextPtr chomp_interface::CHOMPPlannerManager::getPlanningContext ( const planning_scene::PlanningSceneConstPtr &  planning_scene,
const planning_interface::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 73 of file chomp_plugin.cpp.

Here is the call graph for this function:

◆ initialize()

bool chomp_interface::CHOMPPlannerManager::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 62 of file chomp_plugin.cpp.

Member Data Documentation

◆ planning_contexts_

std::map<std::string, CHOMPPlanningContextPtr> chomp_interface::CHOMPPlannerManager::planning_contexts_
protected

Definition at line 124 of file chomp_plugin.cpp.


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