OMPL Plannification
Path planning with OMPL
OMPL_Planner Class Reference

Class for planner for 2D and 3D planning. More...

#include <OMPL_Planner.hpp>

Public Member Functions

 OMPL_Planner (int dim)
 Constructor. More...
 
void setPlanningBounds (const std::vector< double > planning_bounds_x, const std::vector< double > planning_bounds_y, const std::vector< double > planning_bounds_z=std::vector< double >())
 Set the bounds of the planner workspace. More...
 
void setPlanningDepth (double depth_limit=1)
 Set the planning depth. More...
 
void setPlanner (const std::string plannerName="RRTstar")
 Set the planning algorithm used to solve the problem. More...
 
void setStateChecker (const ob::StateValidityCheckerPtr state_checker)
 Set the state checker. More...
 
void setStateChecker (const std::string mapFile, double collision_mask_x, double collision_mask_y, double collision_mask_z=0.2)
 
void setStateChecker (octomap::OcTree *octree, double collision_mask_x, double collision_mask_y, double collision_mask_z)
 
void updateStateChecker (octomap::OcTree *octree)
 Update the state checker. More...
 
void setStartGoal (const std::vector< double > start_state, const std::vector< double > goal_state)
 Set the planning objectives. More...
 
bool findPath (double solving_time)
 Solve the planning problem. More...
 
bool isValid (std::vector< double > position) const
 Check if position is collision-free. More...
 
bool checkPath () const
 Check if the path is valid.
 
bool updatePath (octomap::OcTree *octree, double solving_time, const std::vector< double > start_state, const std::vector< double > goal_state)
 Update the path. More...
 
og::PathGeometric getPath () const
 Return the path found by the planner.
 
og::SimpleSetup getSimpleSetup () const
 Return the OMPL object containing most of the information of the planning problem.
 
 ~OMPL_Planner ()
 Destructor. More...
 

Detailed Description

Class for planner for 2D and 3D planning.

Definition at line 35 of file OMPL_Planner.hpp.

Constructor & Destructor Documentation

OMPL_Planner::OMPL_Planner ( int  dim)

Constructor.

Create space and simple_setup instance for OMPL planning. Set planning dimension.

Definition at line 11 of file OMPL_Planner.cpp.

OMPL_Planner::~OMPL_Planner ( )

Destructor.

Free dynamicly allowed data.

Definition at line 20 of file OMPL_Planner.cpp.

Member Function Documentation

bool OMPL_Planner::findPath ( double  solving_time)

Solve the planning problem.

Find a path from the start state to the goal state in the map given to the state checker. The planner will run during solving_time and optimize the solution during this time.

Definition at line 139 of file OMPL_Planner.cpp.

bool OMPL_Planner::isValid ( std::vector< double >  position) const

Check if position is collision-free.

Checking is done on the last map given to the state checker.

Definition at line 158 of file OMPL_Planner.cpp.

void OMPL_Planner::setPlanner ( const std::string  plannerName = "RRTstar")

Set the planning algorithm used to solve the problem.

Planner avalaible : RRTstar, CForest. If no argument provided, RRTstar will be used (reliable planner for most of the situations). Implementation of other planners (except control-based planners) is quite simple.

Definition at line 56 of file OMPL_Planner.cpp.

void OMPL_Planner::setPlanningBounds ( const std::vector< double >  planning_bounds_x,
const std::vector< double >  planning_bounds_y,
const std::vector< double >  planning_bounds_z = std::vector<double>() 
)

Set the bounds of the planner workspace.

Workspace defined by a box with planning_bounds limits. Optional argument : Planning_bounds_z (used only for 3D planning).

Definition at line 31 of file OMPL_Planner.cpp.

void OMPL_Planner::setPlanningDepth ( double  depth_limit = 1)

Set the planning depth.

Set the lowest altitude for states. Represent the planning depth (constant) for 2D planning. Used to prevent unwanted invalid state (Issue with the ground in Octomap).

Definition at line 49 of file OMPL_Planner.cpp.

void OMPL_Planner::setStartGoal ( const std::vector< double >  start_state,
const std::vector< double >  goal_state 
)

Set the planning objectives.

If the state has an altitude lower than the planning depth, it's altitude will be set to the planning depth.

Definition at line 116 of file OMPL_Planner.cpp.

void OMPL_Planner::setStateChecker ( const ob::StateValidityCheckerPtr  state_checker)

Set the state checker.

Check if a given position is collision-free.

Definition at line 71 of file OMPL_Planner.cpp.

bool OMPL_Planner::updatePath ( octomap::OcTree *  octree,
double  solving_time,
const std::vector< double >  start_state,
const std::vector< double >  goal_state 
)

Update the path.

Search a new path from start_state to goal state if there's a collision with the path and an obstacle from the new map. Update the state checker. Return True if a new path is found or if the path is collision-free. Return False, if the planner found an obstacle but failed to found a new path.

Definition at line 194 of file OMPL_Planner.cpp.

void OMPL_Planner::updateStateChecker ( octomap::OcTree *  octree)

Update the state checker.

The new map will be used for state checking. If the state checker wasn't set before, there's no update and no warning message will be displayed.

Definition at line 109 of file OMPL_Planner.cpp.


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