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
 
ConstraintsLibrarygetConstraintsLibrary ()
 
const ConstraintsLibrarygetConstraintsLibrary () const
 
ModelBasedPlanningContextPtr getLastPlanningContext () 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
 
ModelBasedPlanningContextPtr getPlanningContext (const std::string &config, const std::string &factory_type="") const
 
const PlanningContextManagergetPlanningContextManager () const
 
PlanningContextManagergetPlanningContextManager ()
 
bool isUsingConstraintsApproximations () const
 
void loadConstraintApproximations (const std::string &path)
 
bool loadConstraintApproximations ()
 Look up param server 'constraint_approximations' and use its value as the path to load constraint approximations to. More...
 
 OMPLInterface (const robot_model::RobotModelConstPtr &kmodel, const ros::NodeHandle &nh=ros::NodeHandle("~"))
 Initialize OMPL-based planning for a particular robot model. ROS configuration is read from the specified NodeHandle. More...
 
 OMPLInterface (const robot_model::RobotModelConstPtr &kmodel, 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...
 
void printStatus ()
 Print the status of this node. More...
 
void saveConstraintApproximations (const std::string &path)
 
bool saveConstraintApproximations ()
 Look up param server 'constraint_approximations' and use its value as the path to save constraint approximations to. 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_
 
ConstraintsLibraryPtr constraints_library_
 
PlanningContextManager context_manager_
 
robot_model::RobotModelConstPtr kmodel_
 The ROS node handle. More...
 
ros::NodeHandle nh_
 
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 56 of file ompl_interface.h.

Constructor & Destructor Documentation

ompl_interface::OMPLInterface::OMPLInterface ( const robot_model::RobotModelConstPtr &  kmodel,
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 46 of file ompl_interface.cpp.

ompl_interface::OMPLInterface::OMPLInterface ( const robot_model::RobotModelConstPtr &  kmodel,
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 61 of file ompl_interface.cpp.

ompl_interface::OMPLInterface::~OMPLInterface ( )
virtual

Definition at line 78 of file ompl_interface.cpp.

Member Function Documentation

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

Definition at line 128 of file ompl_interface.cpp.

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

Definition at line 118 of file ompl_interface.h.

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

Definition at line 123 of file ompl_interface.h.

ConstraintsLibrary& ompl_interface::OMPLInterface::getConstraintsLibrary ( )
inline

Definition at line 108 of file ompl_interface.h.

const ConstraintsLibrary& ompl_interface::OMPLInterface::getConstraintsLibrary ( ) const
inline

Definition at line 113 of file ompl_interface.h.

ModelBasedPlanningContextPtr ompl_interface::OMPLInterface::getLastPlanningContext ( ) const
inline

Definition at line 93 of file ompl_interface.h.

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 79 of file ompl_interface.h.

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

Definition at line 101 of file ompl_interface.cpp.

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

ompl_interface::ModelBasedPlanningContextPtr ompl_interface::OMPLInterface::getPlanningContext ( const std::string &  config,
const std::string &  factory_type = "" 
) const

Definition at line 120 of file ompl_interface.cpp.

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

Definition at line 98 of file ompl_interface.h.

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

Definition at line 103 of file ompl_interface.h.

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

Definition at line 133 of file ompl_interface.h.

void ompl_interface::OMPLInterface::loadConstraintApproximations ( const std::string &  path)

Definition at line 137 of file ompl_interface.cpp.

bool ompl_interface::OMPLInterface::loadConstraintApproximations ( )

Look up param server 'constraint_approximations' and use its value as the path to load constraint approximations to.

Definition at line 162 of file ompl_interface.cpp.

void ompl_interface::OMPLInterface::loadConstraintSamplers ( )
protected

Load the additional plugins for sampling constraints.

Definition at line 173 of file ompl_interface.cpp.

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

void ompl_interface::OMPLInterface::loadPlannerConfigurations ( )
protected

Configure the planners.

Definition at line 220 of file ompl_interface.cpp.

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.

void ompl_interface::OMPLInterface::printStatus ( )

Print the status of this node.

Definition at line 326 of file ompl_interface.cpp.

void ompl_interface::OMPLInterface::saveConstraintApproximations ( const std::string &  path)

Definition at line 145 of file ompl_interface.cpp.

bool ompl_interface::OMPLInterface::saveConstraintApproximations ( )

Look up param server 'constraint_approximations' and use its value as the path to save constraint approximations to.

Definition at line 150 of file ompl_interface.cpp.

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

Specify configurations for the planners.

Parameters
pconfigConfigurations for the different planners

Definition at line 82 of file ompl_interface.cpp.

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

Definition at line 142 of file ompl_interface.h.

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

Definition at line 147 of file ompl_interface.h.

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

Definition at line 128 of file ompl_interface.h.

Member Data Documentation

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

Definition at line 188 of file ompl_interface.h.

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

Definition at line 198 of file ompl_interface.h.

ConstraintsLibraryPtr ompl_interface::OMPLInterface::constraints_library_
protected

Definition at line 192 of file ompl_interface.h.

PlanningContextManager ompl_interface::OMPLInterface::context_manager_
protected

Definition at line 190 of file ompl_interface.h.

robot_model::RobotModelConstPtr ompl_interface::OMPLInterface::kmodel_
protected

The ROS node handle.

The kinematic model for which motion plans are computed

Definition at line 186 of file ompl_interface.h.

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

Definition at line 183 of file ompl_interface.h.

bool ompl_interface::OMPLInterface::simplify_solutions_
protected

Definition at line 195 of file ompl_interface.h.

bool ompl_interface::OMPLInterface::use_constraints_approximations_
protected

Definition at line 193 of file ompl_interface.h.


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


ompl
Author(s): Ioan Sucan
autogenerated on Wed Jul 10 2019 04:03:46