Single-Query Bi-Directional Probabilistic Roadmap Planner with Lazy Collision Checking. More...
#include <SBL.h>
Classes | |
class | Motion |
Representation of a motion. More... | |
struct | TreeData |
Representation of a search tree. Two instances will be used. One for start and one for goal. More... | |
Public Member Functions | |
virtual void | clear (void) |
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). | |
const base::ProjectionEvaluatorPtr & | getProjectionEvaluator (void) const |
Get the projection evaluator. | |
double | getRange (void) const |
Get the range the planner is using. | |
SBL (const base::SpaceInformationPtr &si) | |
The constructor needs the instance of the space information. | |
void | setProjectionEvaluator (const std::string &name) |
Set the projection evaluator (select one from the ones registered with the state space). | |
void | setProjectionEvaluator (const base::ProjectionEvaluatorPtr &projectionEvaluator) |
Set the projection evaluator. This class is able to compute the projection of a given state. | |
void | setRange (double distance) |
Set the range the planner is supposed to use. | |
virtual void | setup (void) |
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 bool | 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 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 | ~SBL (void) |
Protected Types | |
typedef std::vector< Motion * > | MotionSet |
An array of motions. | |
Protected Member Functions | |
void | addMotion (TreeData &tree, Motion *motion) |
Add a motion to a tree. | |
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. | |
void | freeGridMotions (Grid< MotionSet > &grid) |
Free the memory used by the motions contained in a grid. | |
void | freeMemory (void) |
Free the memory allocated by the planner. | |
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. | |
void | removeMotion (TreeData &tree, Motion *motion) |
Remove a motion from a tree. | |
Motion * | selectMotion (TreeData &tree) |
Select a motion from a tree. | |
Protected Attributes | |
double | maxDistance_ |
The maximum length of a motion to be added in the tree. | |
base::ProjectionEvaluatorPtr | projectionEvaluator_ |
The employed projection evaluator. | |
RNG | rng_ |
The random number generator to be used. | |
base::ValidStateSamplerPtr | sampler_ |
The employed state sampler. | |
TreeData | tGoal_ |
The goal tree. | |
TreeData | tStart_ |
The start tree. |
Single-Query Bi-Directional Probabilistic Roadmap Planner with Lazy Collision Checking.
Definition at line 86 of file SBL.h.
typedef std::vector<Motion*> ompl::geometric::SBL::MotionSet [protected] |
ompl::geometric::SBL::SBL | ( | const base::SpaceInformationPtr & | si | ) | [inline] |
Add a motion to a tree.
bool ompl::geometric::SBL::checkSolution | ( | bool | start, | |
TreeData & | tree, | |||
TreeData & | otherTree, | |||
Motion * | motion, | |||
std::vector< Motion * > & | solution | |||
) | [protected] |
Check if a solution can be obtained by connecting two trees using a specified motion.
virtual void ompl::geometric::SBL::clear | ( | void | ) | [virtual] |
Clear all internal datastructures. Planner settings are not affected. Subsequent calls to solve() will ignore all previous work.
Reimplemented from ompl::base::Planner.
Free the memory used by the motions contained in a grid.
void ompl::geometric::SBL::freeMemory | ( | void | ) | [inline, protected] |
virtual void ompl::geometric::SBL::getPlannerData | ( | base::PlannerData & | data | ) | const [virtual] |
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).
Reimplemented from ompl::base::Planner.
const base::ProjectionEvaluatorPtr& ompl::geometric::SBL::getProjectionEvaluator | ( | void | ) | const [inline] |
double ompl::geometric::SBL::getRange | ( | void | ) | const [inline] |
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.
Remove a motion from a tree.
Select a motion from a tree.
void ompl::geometric::SBL::setProjectionEvaluator | ( | const std::string & | name | ) | [inline] |
void ompl::geometric::SBL::setProjectionEvaluator | ( | const base::ProjectionEvaluatorPtr & | projectionEvaluator | ) | [inline] |
void ompl::geometric::SBL::setRange | ( | double | distance | ) | [inline] |
virtual void ompl::geometric::SBL::setup | ( | void | ) | [virtual] |
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.
Reimplemented from ompl::base::Planner.
virtual bool ompl::geometric::SBL::solve | ( | const base::PlannerTerminationCondition & | ptc | ) | [virtual] |
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 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.
Implements ompl::base::Planner.
double ompl::geometric::SBL::maxDistance_ [protected] |
RNG ompl::geometric::SBL::rng_ [protected] |
TreeData ompl::geometric::SBL::tGoal_ [protected] |
TreeData ompl::geometric::SBL::tStart_ [protected] |