Probabilistic RoadMap planner. More...
#include <BasicPRM.h>
Classes | |
class | Milestone |
Representation of a milestone. More... | |
Public Member Functions | |
BasicPRM (const base::SpaceInformationPtr &si) | |
Constructor. | |
virtual void | clear (void) |
Clear all internal datastructures. Planner settings are not affected. Subsequent calls to solve() will ignore all previous work. | |
unsigned int | getMaxNearestNeighbors (void) const |
Get the maximum number of neighbors for which a connection will be attempted when a new milestone is added. | |
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). | |
virtual void | growRoadmap (double growTime) |
If the user desires, the roadmap can be improved for a specified amount of time. The solve() method will also improve the roadmap, as needed. | |
virtual void | reconstructLastSolution (void) |
If the user desires to recompute the previously obtained solution, this function allows this functionality. | |
void | setMaxNearestNeighbors (unsigned int maxNearestNeighbors) |
Set the maximum number of neighbors for which a connection to will be attempted when a new milestone is added. | |
template<template< typename T > class NN> | |
void | setNearestNeighbors (void) |
Set a different nearest neighbors datastructure. | |
virtual void | setProblemDefinition (const base::ProblemDefinitionPtr &pdef) |
Set the problem definition for the planner. The problem needs to be set before calling solve(). Note: If this problem definition replaces a previous one, it may also be necessary to call clear(). | |
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 | ~BasicPRM (void) |
Protected Member Functions | |
Milestone * | addMilestone (base::State *state) |
Construct a milestone for a given state (state) and store it in the nearest neighbors data structure. | |
void | constructSolution (const Milestone *start, const Milestone *goal) |
Given two milestones from the same connected component, construct a path connecting them and set it as the solution. | |
double | distanceFunction (const Milestone *a, const Milestone *b) const |
Compute distance between two milestones (this is simply distance between the states of the milestones). | |
void | freeMemory (void) |
Free all the memory allocated by the planner. | |
void | growRoadmap (const std::vector< Milestone * > &start, const std::vector< Milestone * > &goal, const base::PlannerTerminationCondition &ptc, base::State *workState) |
Randomly sample the state space, add and connect milestones in the roadmap. Stop this process when the termination condition ptc returns true or when any of the start milestones are in the same connected component as any of the goal milestones. Use workState as temporary memory. | |
bool | haveSolution (const std::vector< Milestone * > &start, const std::vector< Milestone * > &goal, std::pair< Milestone *, Milestone * > *endpoints=NULL) |
Check if there exists a solution, i.e., there exists a pair of milestones such that the first is in start and the second is in goal, and the two milestones are in the same connected component. If endpoints is not null, that pair is recorded. | |
virtual void | nearestNeighbors (Milestone *milestone, std::vector< Milestone * > &nbh) |
Get the list of nearest neighbors (nbh) for a given milestone (milestone). | |
void | uniteComponents (Milestone *m1, Milestone *m2) |
Make two milestones (m1 and m2) be part of the same connected component. The component with fewer elements will get the id of the component with more elements. | |
Protected Attributes | |
unsigned long | componentCount_ |
The number of components that have been used at a point in time. There is no component with id larger than this value, but it is not necessary for all components with smaller id to exist (they could have been merged). | |
std::map< unsigned long, unsigned long > | componentSizes_ |
Number of elements in each component. | |
std::vector< Milestone * > | goalM_ |
Array of goal milestones. | |
const Milestone * | lastGoal_ |
constructSolution() will set this variable to be the milestone used as the goal. This is useful if multiple solution paths are to be generated. | |
const Milestone * | lastStart_ |
constructSolution() will set this variable to be the milestone used as the start. This is useful if multiple solution paths are to be generated. | |
unsigned int | maxNearestNeighbors_ |
Maximum number of nearest neighbors to attempt to connect new milestones to. | |
std::vector< Milestone * > | milestones_ |
Array of available milestones. | |
boost::shared_ptr < NearestNeighbors< Milestone * > > | nn_ |
Nearest neighbors data structure. | |
RNG | rng_ |
Random number generator. | |
base::ValidStateSamplerPtr | sampler_ |
Sampler user for generating valid samples in the state space. | |
std::vector< Milestone * > | startM_ |
Array of start milestones. |
Probabilistic RoadMap planner.
Definition at line 78 of file BasicPRM.h.
ompl::geometric::BasicPRM::BasicPRM | ( | const base::SpaceInformationPtr & | si | ) | [inline] |
Constructor.
Definition at line 83 of file BasicPRM.h.
virtual ompl::geometric::BasicPRM::~BasicPRM | ( | void | ) | [inline, virtual] |
Definition at line 93 of file BasicPRM.h.
Milestone* ompl::geometric::BasicPRM::addMilestone | ( | base::State * | state | ) | [protected] |
Construct a milestone for a given state (state) and store it in the nearest neighbors data structure.
virtual void ompl::geometric::BasicPRM::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.
void ompl::geometric::BasicPRM::constructSolution | ( | const Milestone * | start, | |
const Milestone * | goal | |||
) | [protected] |
Given two milestones from the same connected component, construct a path connecting them and set it as the solution.
double ompl::geometric::BasicPRM::distanceFunction | ( | const Milestone * | a, | |
const Milestone * | b | |||
) | const [inline, protected] |
Compute distance between two milestones (this is simply distance between the states of the milestones).
Definition at line 200 of file BasicPRM.h.
void ompl::geometric::BasicPRM::freeMemory | ( | void | ) | [protected] |
Free all the memory allocated by the planner.
unsigned int ompl::geometric::BasicPRM::getMaxNearestNeighbors | ( | void | ) | const [inline] |
Get the maximum number of neighbors for which a connection will be attempted when a new milestone is added.
Definition at line 111 of file BasicPRM.h.
virtual void ompl::geometric::BasicPRM::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.
void ompl::geometric::BasicPRM::growRoadmap | ( | const std::vector< Milestone * > & | start, | |
const std::vector< Milestone * > & | goal, | |||
const base::PlannerTerminationCondition & | ptc, | |||
base::State * | workState | |||
) | [protected] |
Randomly sample the state space, add and connect milestones in the roadmap. Stop this process when the termination condition ptc returns true or when any of the start milestones are in the same connected component as any of the goal milestones. Use workState as temporary memory.
virtual void ompl::geometric::BasicPRM::growRoadmap | ( | double | growTime | ) | [virtual] |
If the user desires, the roadmap can be improved for a specified amount of time. The solve() method will also improve the roadmap, as needed.
bool ompl::geometric::BasicPRM::haveSolution | ( | const std::vector< Milestone * > & | start, | |
const std::vector< Milestone * > & | goal, | |||
std::pair< Milestone *, Milestone * > * | endpoints = NULL | |||
) | [protected] |
Check if there exists a solution, i.e., there exists a pair of milestones such that the first is in start and the second is in goal, and the two milestones are in the same connected component. If endpoints is not null, that pair is recorded.
virtual void ompl::geometric::BasicPRM::nearestNeighbors | ( | Milestone * | milestone, | |
std::vector< Milestone * > & | nbh | |||
) | [protected, virtual] |
Get the list of nearest neighbors (nbh) for a given milestone (milestone).
virtual void ompl::geometric::BasicPRM::reconstructLastSolution | ( | void | ) | [virtual] |
If the user desires to recompute the previously obtained solution, this function allows this functionality.
void ompl::geometric::BasicPRM::setMaxNearestNeighbors | ( | unsigned int | maxNearestNeighbors | ) | [inline] |
Set the maximum number of neighbors for which a connection to will be attempted when a new milestone is added.
Definition at line 103 of file BasicPRM.h.
void ompl::geometric::BasicPRM::setNearestNeighbors | ( | void | ) | [inline] |
Set a different nearest neighbors datastructure.
Definition at line 134 of file BasicPRM.h.
virtual void ompl::geometric::BasicPRM::setProblemDefinition | ( | const base::ProblemDefinitionPtr & | pdef | ) | [virtual] |
Set the problem definition for the planner. The problem needs to be set before calling solve(). Note: If this problem definition replaces a previous one, it may also be necessary to call clear().
Reimplemented from ompl::base::Planner.
virtual void ompl::geometric::BasicPRM::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::BasicPRM::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.
Make two milestones (m1 and m2) be part of the same connected component. The component with fewer elements will get the id of the component with more elements.
unsigned long ompl::geometric::BasicPRM::componentCount_ [protected] |
The number of components that have been used at a point in time. There is no component with id larger than this value, but it is not necessary for all components with smaller id to exist (they could have been merged).
Definition at line 233 of file BasicPRM.h.
std::map<unsigned long, unsigned long> ompl::geometric::BasicPRM::componentSizes_ [protected] |
Number of elements in each component.
Definition at line 230 of file BasicPRM.h.
std::vector<Milestone*> ompl::geometric::BasicPRM::goalM_ [protected] |
Array of goal milestones.
Definition at line 218 of file BasicPRM.h.
const Milestone* ompl::geometric::BasicPRM::lastGoal_ [protected] |
constructSolution() will set this variable to be the milestone used as the goal. This is useful if multiple solution paths are to be generated.
Definition at line 224 of file BasicPRM.h.
const Milestone* ompl::geometric::BasicPRM::lastStart_ [protected] |
constructSolution() will set this variable to be the milestone used as the start. This is useful if multiple solution paths are to be generated.
Definition at line 221 of file BasicPRM.h.
unsigned int ompl::geometric::BasicPRM::maxNearestNeighbors_ [protected] |
Maximum number of nearest neighbors to attempt to connect new milestones to.
Definition at line 227 of file BasicPRM.h.
std::vector<Milestone*> ompl::geometric::BasicPRM::milestones_ [protected] |
Array of available milestones.
Definition at line 212 of file BasicPRM.h.
boost::shared_ptr< NearestNeighbors<Milestone*> > ompl::geometric::BasicPRM::nn_ [protected] |
Nearest neighbors data structure.
Definition at line 209 of file BasicPRM.h.
RNG ompl::geometric::BasicPRM::rng_ [protected] |
Random number generator.
Definition at line 236 of file BasicPRM.h.
Sampler user for generating valid samples in the state space.
Definition at line 206 of file BasicPRM.h.
std::vector<Milestone*> ompl::geometric::BasicPRM::startM_ [protected] |
Array of start milestones.
Definition at line 215 of file BasicPRM.h.