Class pSBL

Nested Relationships

Nested Types

Inheritance Relationships

Base Type

Class Documentation

class pSBL : public ompl::base::Planner

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[PDF]

Public Functions

pSBL(const base::SpaceInformationPtr &si)
~pSBL() override
inline void setProjectionEvaluator(const base::ProjectionEvaluatorPtr &projectionEvaluator)

Set the projection evaluator. This class is able to compute the projection of a given state.

inline void setProjectionEvaluator(const std::string &name)

Set the projection evaluator (select one from the ones registered with the state space).

inline const base::ProjectionEvaluatorPtr &getProjectionEvaluator() const

Get the projection evaluator.

inline void setRange(double distance)

Set the range the planner is supposed to use.

This parameter greatly influences the runtime of the algorithm. It represents the maximum length of a motion to be added in the tree of motions.

inline 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.

inline unsigned int getThreadCount() const

Get the thread count.

virtual void setup() override

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) override

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). If clearQuery() is called, the planner may retain prior datastructures generated from a previous query on a new problem definition. The function terminates if the call to ptc returns true.

virtual void clear() override

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 override

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

using GridCell = Grid<MotionInfo>::Cell

A grid cell.

using CellPDF = PDF<GridCell*>

A PDF of grid cells.

Protected Functions

void threadSolve(unsigned int tid, const base::PlannerTerminationCondition &ptc, SolutionInfo *sol)
inline 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_
std::mutex loopLock_
std::mutex loopLockCounter_
unsigned int loopCounter_
double maxDistance_ = {0.}
unsigned int threadCount_
std::pair<base::State*, base::State*> connectionPoint_ = {nullptr, nullptr}

The pair of states in each tree connected during planning. Used for PlannerData computation.

class Motion

Public Functions

Motion() = default
inline Motion(const base::SpaceInformationPtr &si)
~Motion() = default

Public Members

const base::State *root = {nullptr}
base::State *state = {nullptr}
Motion *parent = {nullptr}
bool valid = {false}
std::vector<Motion*> children
std::mutex lock
struct MotionInfo

A struct containing an array of motions and a corresponding PDF element.

Public Functions

inline Motion *operator[](unsigned int i)
inline std::vector<Motion*>::iterator begin()
inline void erase(std::vector<Motion*>::iterator iter)
inline void push_back(Motion *m)
inline unsigned int size() const
inline bool empty() const

Public Members

std::vector<Motion*> motions_
CellPDF::Element *elem_
struct MotionsToBeRemoved

Public Members

std::vector<PendingRemoveMotion> motions
std::mutex lock
struct PendingRemoveMotion

Public Members

TreeData *tree
Motion *motion
struct SolutionInfo

Public Members

std::vector<Motion*> solution
bool found
std::mutex lock
struct TreeData

Public Functions

TreeData() = default

Public Members

Grid<MotionInfo> grid = {0}
unsigned int size = {0}
CellPDF pdf
std::mutex lock