moveit2
The MoveIt Motion Planning Framework for ROS 2.
Public Member Functions | Protected Member Functions | Protected Attributes | List of all members
ompl_interface::OMPLInterface Class Reference

#include <ompl_interface.h>

Collaboration diagram for ompl_interface::OMPLInterface:
Collaboration graph
[legend]

Public Member Functions

 OMPLInterface (const moveit::core::RobotModelConstPtr &robot_model, const rclcpp::Node::SharedPtr &node, const std::string &parameter_namespace)
 Initialize OMPL-based planning for a particular robot model. ROS configuration is read from the specified Node. More...
 
 OMPLInterface (const moveit::core::RobotModelConstPtr &robot_model, const planning_interface::PlannerConfigurationMap &pconfig, const rclcpp::Node::SharedPtr &node, const std::string &parameter_namespace)
 Initialize OMPL-based planning for a particular robot model. ROS configuration is read from the specified Node. However, planner configurations are used as specified in pconfig instead of reading them from ROS parameters. More...
 
virtual ~OMPLInterface ()
 
void setPlannerConfigurations (const planning_interface::PlannerConfigurationMap &pconfig)
 Specify configurations for the planners. More...
 
const planning_interface::PlannerConfigurationMapgetPlannerConfigurations () const
 Get the configurations for the planners that are already loaded. More...
 
ModelBasedPlanningContextPtr getPlanningContext (const planning_scene::PlanningSceneConstPtr &planning_scene, const planning_interface::MotionPlanRequest &req) const
 
ModelBasedPlanningContextPtr getPlanningContext (const planning_scene::PlanningSceneConstPtr &planning_scene, const planning_interface::MotionPlanRequest &req, moveit_msgs::msg::MoveItErrorCodes &error_code) const
 
const PlanningContextManagergetPlanningContextManager () const
 
PlanningContextManagergetPlanningContextManager ()
 
constraint_samplers::ConstraintSamplerManagergetConstraintSamplerManager ()
 
const constraint_samplers::ConstraintSamplerManagergetConstraintSamplerManager () const
 
void useConstraintsApproximations (bool flag)
 
bool isUsingConstraintsApproximations () const
 
void printStatus ()
 Print the status of this node. More...
 

Protected Member Functions

bool loadPlannerConfiguration (const std::string &group_name, const std::string &planner_id, const std::map< std::string, std::string > &group_params, planning_interface::PlannerConfigurationSettings &planner_config)
 Load planner configurations for specified group into planner_config. More...
 
void loadPlannerConfigurations ()
 Configure the planners. More...
 
void loadConstraintSamplers ()
 Load the additional plugins for sampling constraints. More...
 
ModelBasedPlanningContextPtr prepareForSolve (const planning_interface::MotionPlanRequest &req, const planning_scene::PlanningSceneConstPtr &planning_scene, moveit_msgs::msg::MoveItErrorCodes *error_code, unsigned int *attempts, double *timeout) const
 Configure the OMPL planning context for a new planning request. More...
 

Protected Attributes

rclcpp::Node::SharedPtr node_
 
const std::string parameter_namespace_
 The ROS node. More...
 
moveit::core::RobotModelConstPtr robot_model_
 The kinematic model for which motion plans are computed. More...
 
constraint_samplers::ConstraintSamplerManagerPtr constraint_sampler_manager_
 
PlanningContextManager context_manager_
 
bool use_constraints_approximations_
 

Detailed Description

This class defines the interface to the motion planners in OMPL

Definition at line 54 of file ompl_interface.h.

Constructor & Destructor Documentation

◆ OMPLInterface() [1/2]

ompl_interface::OMPLInterface::OMPLInterface ( const moveit::core::RobotModelConstPtr &  robot_model,
const rclcpp::Node::SharedPtr &  node,
const std::string &  parameter_namespace 
)

Initialize OMPL-based planning for a particular robot model. ROS configuration is read from the specified Node.

Definition at line 54 of file ompl_interface.cpp.

Here is the call graph for this function:

◆ OMPLInterface() [2/2]

ompl_interface::OMPLInterface::OMPLInterface ( const moveit::core::RobotModelConstPtr &  robot_model,
const planning_interface::PlannerConfigurationMap pconfig,
const rclcpp::Node::SharedPtr &  node,
const std::string &  parameter_namespace 
)

Initialize OMPL-based planning for a particular robot model. ROS configuration is read from the specified Node. However, planner configurations are used as specified in pconfig instead of reading them from ROS parameters.

Definition at line 68 of file ompl_interface.cpp.

Here is the call graph for this function:

◆ ~OMPLInterface()

ompl_interface::OMPLInterface::~OMPLInterface ( )
virtualdefault

Member Function Documentation

◆ getConstraintSamplerManager() [1/2]

constraint_samplers::ConstraintSamplerManager& ompl_interface::OMPLInterface::getConstraintSamplerManager ( )
inline

Definition at line 99 of file ompl_interface.h.

◆ getConstraintSamplerManager() [2/2]

const constraint_samplers::ConstraintSamplerManager& ompl_interface::OMPLInterface::getConstraintSamplerManager ( ) const
inline

Definition at line 104 of file ompl_interface.h.

◆ getPlannerConfigurations()

const planning_interface::PlannerConfigurationMap& ompl_interface::OMPLInterface::getPlannerConfigurations ( ) const
inline

Get the configurations for the planners that are already loaded.

Parameters
pconfigConfigurations for the different planners

Definition at line 78 of file ompl_interface.h.

Here is the call graph for this function:

◆ getPlanningContext() [1/2]

ModelBasedPlanningContextPtr ompl_interface::OMPLInterface::getPlanningContext ( const planning_scene::PlanningSceneConstPtr &  planning_scene,
const planning_interface::MotionPlanRequest req 
) const

Definition at line 104 of file ompl_interface.cpp.

◆ getPlanningContext() [2/2]

ModelBasedPlanningContextPtr ompl_interface::OMPLInterface::getPlanningContext ( const planning_scene::PlanningSceneConstPtr &  planning_scene,
const planning_interface::MotionPlanRequest req,
moveit_msgs::msg::MoveItErrorCodes &  error_code 
) const

Definition at line 112 of file ompl_interface.cpp.

Here is the call graph for this function:

◆ getPlanningContextManager() [1/2]

PlanningContextManager& ompl_interface::OMPLInterface::getPlanningContextManager ( )
inline

Definition at line 94 of file ompl_interface.h.

◆ getPlanningContextManager() [2/2]

const PlanningContextManager& ompl_interface::OMPLInterface::getPlanningContextManager ( ) const
inline

Definition at line 89 of file ompl_interface.h.

◆ isUsingConstraintsApproximations()

bool ompl_interface::OMPLInterface::isUsingConstraintsApproximations ( ) const
inline

Definition at line 114 of file ompl_interface.h.

◆ loadConstraintSamplers()

void ompl_interface::OMPLInterface::loadConstraintSamplers ( )
protected

Load the additional plugins for sampling constraints.

Definition at line 121 of file ompl_interface.cpp.

Here is the caller graph for this function:

◆ loadPlannerConfiguration()

bool ompl_interface::OMPLInterface::loadPlannerConfiguration ( const std::string &  group_name,
const std::string &  planner_id,
const std::map< std::string, std::string > &  group_params,
planning_interface::PlannerConfigurationSettings planner_config 
)
protected

Load planner configurations for specified group into planner_config.

Definition at line 128 of file ompl_interface.cpp.

Here is the call graph for this function:
Here is the caller graph for this function:

◆ loadPlannerConfigurations()

void ompl_interface::OMPLInterface::loadPlannerConfigurations ( )
protected

Configure the planners.

Definition at line 158 of file ompl_interface.cpp.

Here is the call graph for this function:
Here is the caller graph for this function:

◆ prepareForSolve()

ModelBasedPlanningContextPtr ompl_interface::OMPLInterface::prepareForSolve ( const planning_interface::MotionPlanRequest req,
const planning_scene::PlanningSceneConstPtr &  planning_scene,
moveit_msgs::msg::MoveItErrorCodes *  error_code,
unsigned int *  attempts,
double *  timeout 
) const
protected

Configure the OMPL planning context for a new planning request.

◆ printStatus()

void ompl_interface::OMPLInterface::printStatus ( )

Print the status of this node.

Definition at line 262 of file ompl_interface.cpp.

Here is the call graph for this function:

◆ setPlannerConfigurations()

void ompl_interface::OMPLInterface::setPlannerConfigurations ( const planning_interface::PlannerConfigurationMap pconfig)

Specify configurations for the planners.

Parameters
pconfigConfigurations for the different planners

Definition at line 85 of file ompl_interface.cpp.

Here is the call graph for this function:
Here is the caller graph for this function:

◆ useConstraintsApproximations()

void ompl_interface::OMPLInterface::useConstraintsApproximations ( bool  flag)
inline

Definition at line 109 of file ompl_interface.h.

Member Data Documentation

◆ constraint_sampler_manager_

constraint_samplers::ConstraintSamplerManagerPtr ompl_interface::OMPLInterface::constraint_sampler_manager_
protected

Definition at line 146 of file ompl_interface.h.

◆ context_manager_

PlanningContextManager ompl_interface::OMPLInterface::context_manager_
protected

Definition at line 148 of file ompl_interface.h.

◆ node_

rclcpp::Node::SharedPtr ompl_interface::OMPLInterface::node_
protected

Definition at line 140 of file ompl_interface.h.

◆ parameter_namespace_

const std::string ompl_interface::OMPLInterface::parameter_namespace_
protected

The ROS node.

Definition at line 141 of file ompl_interface.h.

◆ robot_model_

moveit::core::RobotModelConstPtr ompl_interface::OMPLInterface::robot_model_
protected

The kinematic model for which motion plans are computed.

Definition at line 144 of file ompl_interface.h.

◆ use_constraints_approximations_

bool ompl_interface::OMPLInterface::use_constraints_approximations_
protected

Definition at line 150 of file ompl_interface.h.


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