Classes |
Public Member Functions |
Protected Types |
Protected Member Functions |
Protected Attributes
ompl::geometric::pSBL Class Reference
Parallel Single-query Bi-directional Lazy collision checking planner. More...
#include <ompl/geometric/planners/sbl/pSBL.h>
Inheritance diagram for ompl::geometric::pSBL:

Classes | |
class | Motion |
struct | MotionInfo |
A struct containing an array of motions and a corresponding PDF element. More... | |
struct | MotionsToBeRemoved |
struct | PendingRemoveMotion |
struct | SolutionInfo |
struct | TreeData |
Public Member Functions | |
pSBL (const base::SpaceInformationPtr &si) | |
void | setProjectionEvaluator (const base::ProjectionEvaluatorPtr &projectionEvaluator) |
Set the projection evaluator. This class is able to compute the projection of a given state. | |
void | setProjectionEvaluator (const std::string &name) |
Set the projection evaluator (select one from the ones registered with the state space). | |
const base::ProjectionEvaluatorPtr & | getProjectionEvaluator () const |
Get the projection evaluator. | |
void | setRange (double distance) |
Set the range the planner is supposed to use. | |
double | getRange () const |
Get the range the planner is using. | |
void | setThreadCount (unsigned int nthreads) |
Set the number of threads the planner should use. Default is 2. | |
unsigned int | getThreadCount () const |
Get the thread count. | |
virtual void | setup () |
Perform extra configuration steps, if needed. This call will also issue a call to ompl::base::SpaceInformation::setup() if needed. This must be called before solving. | |
virtual base::PlannerStatus | solve (const base::PlannerTerminationCondition &ptc) |
Function that can solve the motion planning problem. This function can be called multiple times on the same problem, without calling clear() in between. This allows the planner to continue work for more time on an unsolved problem, for example. If this option is used, it is assumed the problem definition is not changed (unpredictable results otherwise). The only change in the problem definition that is accounted for is the addition of starting or goal states (but not changing previously added start/goal states). The function terminates if the call to ptc returns true. | |
virtual void | clear () |
Clear all internal datastructures. Planner settings are not affected. Subsequent calls to solve() will ignore all previous work. | |
virtual void | getPlannerData (base::PlannerData &data) const |
Get information about the current run of the motion planner. Repeated calls to this function will update data (only additions are made). This is useful to see what changed in the exploration datastructure, between calls to solve(), for example (without calling clear() in between). | |
Protected Types | |
typedef Grid< MotionInfo >::Cell | GridCell |
A grid cell. | |
typedef PDF< GridCell * > | CellPDF |
A PDF of grid cells. | |
Protected Member Functions | |
void | threadSolve (unsigned int tid, const base::PlannerTerminationCondition &ptc, SolutionInfo *sol) |
void | freeMemory () |
void | freeGridMotions (Grid< MotionInfo > &grid) |
void | addMotion (TreeData &tree, Motion *motion) |
Motion * | selectMotion (RNG &rng, TreeData &tree) |
void | removeMotion (TreeData &tree, Motion *motion, std::map< Motion *, bool > &seen) |
bool | isPathValid (TreeData &tree, Motion *motion) |
bool | checkSolution (RNG &rng, bool start, TreeData &tree, TreeData &otherTree, Motion *motion, std::vector< Motion * > &solution) |
Protected Attributes | |
base::StateSamplerArray < base::ValidStateSampler > | samplerArray_ |
base::ProjectionEvaluatorPtr | projectionEvaluator_ |
TreeData | tStart_ |
TreeData | tGoal_ |
MotionsToBeRemoved | removeList_ |
boost::mutex | loopLock_ |
boost::mutex | loopLockCounter_ |
unsigned int | loopCounter_ |
double | maxDistance_ |
unsigned int | threadCount_ |
std::pair< base::State *, base::State * > | connectionPoint_ |
The pair of states in each tree connected during planning. Used for PlannerData computation. |
Detailed Description
Parallel Single-query Bi-directional Lazy collision checking planner.
- Short description
- SBL is a tree-based motion planner that attempts to grow two trees at once: one grows from the starting state and the other from the goal state. The tree expansion strategy is the same as for EST. Attempts are made to connect these trees at every step of the expansion. If they are connected, a solution path is obtained. However, this solution path is not certain to be valid (the lazy part of the algorithm) so it is checked for validity. If invalid parts are found, they are removed from the tree and exploration of the state space continues until a solution is found. To guide the exploration, an additional grid data structure is maintained. Grid cells contain states that have been previously visited. When deciding which state to use for further expansion, this grid is used; least-filled grid cells have most chances of being selected. The grid is usually imposed on a projection of the state space. This projection needs to be set before using the planner (setProjectionEvaluator() function). Connection of states in different trees is attempted if they fall in the same grid cell. If no projection is set, the planner will attempt to use the default projection associated to the state space. An exception is thrown if no default projection is available either.
- External documentation
- G. Sánchez and J.-C. Latombe, A single-query bi-directional probabilistic roadmap planner with lazy collision checking, in The Tenth International Symposium on Robotics Research, pp. 403–417, 2001. DOI: [10.1007/3-540-36460-9_27](http://dx.doi.org/10.1007/3-540-36460-9_27)
[[PDF]](http://www.springerlink.com/content/9843341054386hh6/fulltext.pdf)
Member Function Documentation
void ompl::geometric::pSBL::setRange | ( | double | distance | ) | [inline] |
The documentation for this class was generated from the following files: