Class SBL

Nested Relationships

Nested Types

Inheritance Relationships

Base Type

Class Documentation

class SBL : public ompl::base::Planner

Single-Query Bi-Directional Probabilistic Roadmap Planner with Lazy Collision Checking.

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

SBL(const base::SpaceInformationPtr &si)

The constructor needs the instance of the space information.

~SBL() 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.

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

inline void freeMemory()

Free the memory allocated by the planner.

void freeGridMotions(Grid<MotionInfo> &grid)

Free the memory used by the motions contained in a grid.

void addMotion(TreeData &tree, Motion *motion)

Add a motion to a tree.

Motion *selectMotion(TreeData &tree)

Select a motion from a tree.

void removeMotion(TreeData &tree, Motion *motion)

Remove a motion from a tree.

bool isPathValid(TreeData &tree, Motion *motion)

Since solutions are computed in a lazy fashion, once trees are connected, the solution found needs to be checked for validity. This function checks whether the reverse path from a given motion to a root is valid. If this is not the case, invalid motions are removed

bool checkSolution(bool start, TreeData &tree, TreeData &otherTree, Motion *motion, std::vector<Motion*> &solution)

Check if a solution can be obtained by connecting two trees using a specified motion.

Protected Attributes

base::ValidStateSamplerPtr sampler_

The employed state sampler.

base::ProjectionEvaluatorPtr projectionEvaluator_

The employed projection evaluator.

TreeData tStart_

The start tree.

TreeData tGoal_

The goal tree.

double maxDistance_ = {0.}

The maximum length of a motion to be added in the tree.

RNG rng_

The random number generator to be used.

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

Representation of a motion.

Public Functions

Motion() = default

Default constructor. Allocates no memory.

inline Motion(const base::SpaceInformationPtr &si)

Constructor that allocates storage for a state.

Public Members

const base::State *root = {nullptr}

The root of the tree this motion would get to, if we were to follow parent pointers.

base::State *state = {nullptr}

The state this motion leads to.

Motion *parent = {nullptr}

The parent motion &#8212; it contains the state this motion originates at.

bool valid = {false}

Flag indicating whether this motion has been checked for validity.

std::vector<Motion*> children

The set of motions descending from the current motion.

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 TreeData

Representation of a search tree. Two instances will be used. One for start and one for goal.

Public Functions

TreeData() = default

Public Members

Grid<MotionInfo> grid = {0}

The grid of motions corresponding to this tree.

unsigned int size = {0}

The number of motions (in total) from the tree.

CellPDF pdf

The PDF used for selecting a cell from which to sample a motion.