Public Member Functions | Protected Member Functions | Protected Attributes | Private Attributes | List of all members
ompl_interface::OMPLInterface Class Reference

#include <ompl_interface.h>

Public Member Functions

constraint_samplers::ConstraintSamplerManagergetConstraintSamplerManager ()
 
const constraint_samplers::ConstraintSamplerManagergetConstraintSamplerManager () const
 
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::MoveItErrorCodes &error_code) const
 
PlanningContextManagergetPlanningContextManager ()
 
const PlanningContextManagergetPlanningContextManager () const
 
bool isUsingConstraintsApproximations () const
 
 OMPLInterface (const moveit::core::RobotModelConstPtr &robot_model, const planning_interface::PlannerConfigurationMap &pconfig, const ros::NodeHandle &nh=ros::NodeHandle("~"))
 Initialize OMPL-based planning for a particular robot model. ROS configuration is read from the specified NodeHandle. However, planner configurations are used as specified in pconfig instead of reading them from the ROS parameter server. More...
 
 OMPLInterface (const moveit::core::RobotModelConstPtr &robot_model, const ros::NodeHandle &nh=ros::NodeHandle("~"))
 Initialize OMPL-based planning for a particular robot model. ROS configuration is read from the specified NodeHandle. More...
 
void printStatus ()
 Print the status of this node. More...
 
void setPlannerConfigurations (const planning_interface::PlannerConfigurationMap &pconfig)
 Specify configurations for the planners. More...
 
bool simplifySolutions () const
 
void simplifySolutions (bool flag)
 
void useConstraintsApproximations (bool flag)
 
virtual ~OMPLInterface ()
 

Protected Member Functions

void configureContext (const ModelBasedPlanningContextPtr &context) const
 
void loadConstraintSamplers ()
 Load the additional plugins for sampling constraints. More...
 
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...
 
ModelBasedPlanningContextPtr prepareForSolve (const planning_interface::MotionPlanRequest &req, const planning_scene::PlanningSceneConstPtr &planning_scene, moveit_msgs::MoveItErrorCodes *error_code, unsigned int *attempts, double *timeout) const
 Configure the OMPL planning context for a new planning request. More...
 

Protected Attributes

constraint_samplers::ConstraintSamplerManagerPtr constraint_sampler_manager_
 
PlanningContextManager context_manager_
 
ros::NodeHandle nh_
 
moveit::core::RobotModelConstPtr robot_model_
 The ROS node handle. More...
 
bool simplify_solutions_
 
bool use_constraints_approximations_
 

Private Attributes

constraint_sampler_manager_loader::ConstraintSamplerManagerLoaderPtr constraint_sampler_manager_loader_
 

Detailed Description

This class defines the interface to the motion planners in OMPL

Definition at line 85 of file ompl_interface.h.

Constructor & Destructor Documentation

◆ OMPLInterface() [1/2]

ompl_interface::OMPLInterface::OMPLInterface ( const moveit::core::RobotModelConstPtr &  robot_model,
const ros::NodeHandle nh = ros::NodeHandle("~") 
)

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

Definition at line 49 of file ompl_interface.cpp.

◆ OMPLInterface() [2/2]

ompl_interface::OMPLInterface::OMPLInterface ( const moveit::core::RobotModelConstPtr &  robot_model,
const planning_interface::PlannerConfigurationMap pconfig,
const ros::NodeHandle nh = ros::NodeHandle("~") 
)

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

Definition at line 63 of file ompl_interface.cpp.

◆ ~OMPLInterface()

ompl_interface::OMPLInterface::~OMPLInterface ( )
virtualdefault

Member Function Documentation

◆ configureContext()

void ompl_interface::OMPLInterface::configureContext ( const ModelBasedPlanningContextPtr &  context) const
protected

Definition at line 118 of file ompl_interface.cpp.

◆ getConstraintSamplerManager() [1/2]

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

Definition at line 161 of file ompl_interface.h.

◆ getConstraintSamplerManager() [2/2]

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

Definition at line 166 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 140 of file ompl_interface.h.

◆ getPlanningContext() [1/2]

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

Definition at line 99 of file ompl_interface.cpp.

◆ getPlanningContext() [2/2]

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

Definition at line 107 of file ompl_interface.cpp.

◆ getPlanningContextManager() [1/2]

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

Definition at line 156 of file ompl_interface.h.

◆ getPlanningContextManager() [2/2]

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

Definition at line 151 of file ompl_interface.h.

◆ isUsingConstraintsApproximations()

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

Definition at line 176 of file ompl_interface.h.

◆ loadConstraintSamplers()

void ompl_interface::OMPLInterface::loadConstraintSamplers ( )
protected

Load the additional plugins for sampling constraints.

Definition at line 123 of file ompl_interface.cpp.

◆ 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 129 of file ompl_interface.cpp.

◆ loadPlannerConfigurations()

void ompl_interface::OMPLInterface::loadPlannerConfigurations ( )
protected

Configure the planners.

Definition at line 170 of file ompl_interface.cpp.

◆ prepareForSolve()

ModelBasedPlanningContextPtr ompl_interface::OMPLInterface::prepareForSolve ( const planning_interface::MotionPlanRequest req,
const planning_scene::PlanningSceneConstPtr &  planning_scene,
moveit_msgs::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 285 of file ompl_interface.cpp.

◆ 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 80 of file ompl_interface.cpp.

◆ simplifySolutions() [1/2]

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

Definition at line 180 of file ompl_interface.h.

◆ simplifySolutions() [2/2]

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

Definition at line 185 of file ompl_interface.h.

◆ useConstraintsApproximations()

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

Definition at line 171 of file ompl_interface.h.

Member Data Documentation

◆ constraint_sampler_manager_

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

Definition at line 218 of file ompl_interface.h.

◆ constraint_sampler_manager_loader_

constraint_sampler_manager_loader::ConstraintSamplerManagerLoaderPtr ompl_interface::OMPLInterface::constraint_sampler_manager_loader_
private

Definition at line 227 of file ompl_interface.h.

◆ context_manager_

PlanningContextManager ompl_interface::OMPLInterface::context_manager_
protected

Definition at line 220 of file ompl_interface.h.

◆ nh_

ros::NodeHandle ompl_interface::OMPLInterface::nh_
protected

Definition at line 213 of file ompl_interface.h.

◆ robot_model_

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

The ROS node handle.

The kinematic model for which motion plans are computed

Definition at line 216 of file ompl_interface.h.

◆ simplify_solutions_

bool ompl_interface::OMPLInterface::simplify_solutions_
protected

Definition at line 224 of file ompl_interface.h.

◆ use_constraints_approximations_

bool ompl_interface::OMPLInterface::use_constraints_approximations_
protected

Definition at line 222 of file ompl_interface.h.


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


ompl
Author(s): Ioan Sucan
autogenerated on Sat Apr 27 2024 02:26:21