Public Member Functions | Protected Member Functions | Protected Attributes | Private Attributes
ompl_interface::OMPLInterface Class Reference

#include <ompl_interface.h>

List of all members.

Public Member Functions

constraint_samplers::ConstraintSamplerManagergetConstraintSamplerManager ()
const
constraint_samplers::ConstraintSamplerManager
getConstraintSamplerManager () const
ConstraintsLibrarygetConstraintsLibrary ()
const ConstraintsLibrarygetConstraintsLibrary () const
ModelBasedPlanningContextPtr getLastPlanningContext () const
const
planning_interface::PlannerConfigurationMap
getPlannerConfigurations () const
 Get the configurations for the planners that are already loaded.
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.
 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.
 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.
void printStatus ()
 Print the status of this node.
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.
void setPlannerConfigurations (const planning_interface::PlannerConfigurationMap &pconfig)
 Specify configurations for the planners.
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.
void loadPlannerConfigurations ()
 Configure the planners.
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.

Protected Attributes

constraint_samplers::ConstraintSamplerManagerPtr constraint_sampler_manager_
ConstraintsLibraryPtr constraints_library_
PlanningContextManager context_manager_
robot_model::RobotModelConstPtr kmodel_
 The ROS node handle.
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 44 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 59 of file ompl_interface.cpp.

Definition at line 76 of file ompl_interface.cpp.


Member Function Documentation

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

Definition at line 125 of file ompl_interface.cpp.

Definition at line 118 of file ompl_interface.h.

Definition at line 123 of file ompl_interface.h.

Definition at line 108 of file ompl_interface.h.

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.

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 99 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 106 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 117 of file ompl_interface.cpp.

Definition at line 98 of file ompl_interface.h.

Definition at line 103 of file ompl_interface.h.

Definition at line 133 of file ompl_interface.h.

Definition at line 134 of file ompl_interface.cpp.

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

Definition at line 159 of file ompl_interface.cpp.

Load the additional plugins for sampling constraints.

Definition at line 170 of file ompl_interface.cpp.

Configure the planners.

Definition at line 176 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.

Print the status of this node.

Definition at line 292 of file ompl_interface.cpp.

Definition at line 142 of file ompl_interface.cpp.

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

Definition at line 147 of file ompl_interface.cpp.

Specify configurations for the planners.

Parameters:
pconfigConfigurations for the different planners

Definition at line 80 of file ompl_interface.cpp.

Definition at line 142 of file ompl_interface.h.

Definition at line 147 of file ompl_interface.h.

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

constraint_sampler_manager_loader::ConstraintSamplerManagerLoaderPtr ompl_interface::OMPLInterface::constraint_sampler_manager_loader_ [private]

Definition at line 193 of file ompl_interface.h.

ConstraintsLibraryPtr ompl_interface::OMPLInterface::constraints_library_ [protected]

Definition at line 187 of file ompl_interface.h.

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

Definition at line 178 of file ompl_interface.h.

Definition at line 190 of file ompl_interface.h.

Definition at line 188 of file ompl_interface.h.


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


ompl
Author(s): Ioan Sucan
autogenerated on Wed Jun 19 2019 19:24:27