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

Public Member Functions

 TrajOptPlannerManager ()
 
bool initialize (const moveit::core::RobotModelConstPtr &model, const std::string &ns) override
 
bool canServiceRequest (const moveit_msgs::MotionPlanRequest &req) const override
 
std::string getDescription () const override
 Get. 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...
 
planning_interface::PlanningContextPtr getPlanningContext (const planning_scene::PlanningSceneConstPtr &planning_scene, const planning_interface::MotionPlanRequest &req, moveit_msgs::MoveItErrorCodes &error_code) const override
 
- Public Member Functions inherited from planning_interface::PlannerManager
 PlannerManager ()
 
virtual ~PlannerManager ()
 
virtual bool initialize (const moveit::core::RobotModelConstPtr &model, const rclcpp::Node::SharedPtr &node, const std::string &parameter_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 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...
 
PlanningContextPtr getPlanningContext (const planning_scene::PlanningSceneConstPtr &planning_scene, const MotionPlanRequest &req) const
 Calls the function above but ignores the error_code. More...
 
virtual bool canServiceRequest (const MotionPlanRequest &req) const =0
 Determine whether this plugin instance is able to represent this planning request. More...
 
virtual void setPlannerConfigurations (const PlannerConfigurationMap &pcs)=0
 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, TrajOptPlanningContextPtr > 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 49 of file trajopt_planner_manager.cpp.

Constructor & Destructor Documentation

◆ TrajOptPlannerManager()

trajopt_interface::TrajOptPlannerManager::TrajOptPlannerManager ( )
inline

Definition at line 52 of file trajopt_planner_manager.cpp.

Member Function Documentation

◆ canServiceRequest()

bool trajopt_interface::TrajOptPlannerManager::canServiceRequest ( const moveit_msgs::MotionPlanRequest &  req) const
inlineoverride

Definition at line 74 of file trajopt_planner_manager.cpp.

◆ getDescription()

std::string trajopt_interface::TrajOptPlannerManager::getDescription ( ) const
inlineoverridevirtual

Get.

a short string that identifies the planning interface

Reimplemented from planning_interface::PlannerManager.

Definition at line 79 of file trajopt_planner_manager.cpp.

◆ getPlanningAlgorithms()

void trajopt_interface::TrajOptPlannerManager::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 84 of file trajopt_planner_manager.cpp.

◆ getPlanningContext()

planning_interface::PlanningContextPtr trajopt_interface::TrajOptPlannerManager::getPlanningContext ( const planning_scene::PlanningSceneConstPtr &  planning_scene,
const planning_interface::MotionPlanRequest req,
moveit_msgs::MoveItErrorCodes &  error_code 
) const
inlineoverride

Definition at line 90 of file trajopt_planner_manager.cpp.

Here is the call graph for this function:

◆ initialize()

bool trajopt_interface::TrajOptPlannerManager::initialize ( const moveit::core::RobotModelConstPtr &  model,
const std::string &  ns 
)
inlineoverride

Definition at line 56 of file trajopt_planner_manager.cpp.

Member Data Documentation

◆ planning_contexts_

std::map<std::string, TrajOptPlanningContextPtr> trajopt_interface::TrajOptPlannerManager::planning_contexts_
protected

Definition at line 134 of file trajopt_planner_manager.cpp.


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