Classes | Typedefs | Functions
planning_interface Namespace Reference

This namespace includes the base class for MoveIt! planners. More...

Classes

struct  MotionPlanDetailedResponse
 
struct  MotionPlanResponse
 
struct  PlannerConfigurationSettings
 Specify the settings for a particular planning algorithm, for a particular group. The Planner plugin uses these settings to configure the algorithm. More...
 
class  PlannerManager
 Base class for a MoveIt! planner. More...
 
class  PlanningContext
 Representation of a particular planning context – the planning scene and the request are known, solution is not yet computed. More...
 

Typedefs

typedef moveit_msgs::MotionPlanRequest MotionPlanRequest
 
typedef std::map< std::string, PlannerConfigurationSettingsPlannerConfigurationMap
 Map from PlannerConfigurationSettings.name to PlannerConfigurationSettings. More...
 

Functions

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. More...
 
 MOVEIT_CLASS_FORWARD (PlanningContext)
 
 MOVEIT_CLASS_FORWARD (PlannerManager)
 

Detailed Description

This namespace includes the base class for MoveIt! planners.

Typedef Documentation

◆ MotionPlanRequest

typedef moveit_msgs::MotionPlanRequest planning_interface::MotionPlanRequest

Definition at line 46 of file planning_request.h.

◆ PlannerConfigurationMap

Function Documentation

◆ getConfigNodeHandle()

ros::NodeHandle planning_interface::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.

Definition at line 59 of file planning_interface.cpp.

◆ MOVEIT_CLASS_FORWARD() [1/2]

planning_interface::MOVEIT_CLASS_FORWARD ( PlanningContext  )

◆ MOVEIT_CLASS_FORWARD() [2/2]

planning_interface::MOVEIT_CLASS_FORWARD ( PlannerManager  )


moveit_core
Author(s): Ioan Sucan , Sachin Chitta , Acorn Pooley
autogenerated on Thu Mar 17 2022 02:51:05