SPArse Roadmap Spanner Version 2.0 More...
#include <SPARStwo.h>
Classes | |
struct | InterfaceData |
Interface information storage class, which does bookkeeping for criterion four. More... | |
struct | InterfaceHashStruct |
struct | vertex_color_t |
struct | vertex_interface_data_t |
struct | vertex_state_t |
Public Types | |
enum | GuardType { START, GOAL, COVERAGE, CONNECTIVITY, INTERFACE, QUALITY } |
Enumeration which specifies the reason a guard is added to the spanner. | |
typedef unsigned long int | VertexIndexType |
The type used internally for representing vertex IDs. | |
typedef std::pair < VertexIndexType, VertexIndexType > | VertexPair |
Pair of vertices which support an interface. | |
typedef boost::unordered_map < VertexPair, InterfaceData, boost::hash< VertexPair > > | InterfaceHash |
the hash which maps pairs of neighbor points to pairs of states | |
typedef boost::adjacency_list < boost::vecS, boost::vecS, boost::undirectedS, boost::property < vertex_state_t, base::State *, boost::property < boost::vertex_predecessor_t, VertexIndexType, boost::property < boost::vertex_rank_t, VertexIndexType, boost::property < vertex_color_t, GuardType, boost::property < vertex_interface_data_t, InterfaceHashStruct > > > > >, boost::property < boost::edge_weight_t, double > > | Graph |
The underlying roadmap graph. More... | |
typedef boost::graph_traits < Graph >::vertex_descriptor | Vertex |
Vertex in Graph. | |
typedef boost::graph_traits < Graph >::edge_descriptor | Edge |
Edge in Graph. | |
![]() | |
typedef boost::function < std::string()> | PlannerProgressProperty |
Definition of a function which returns a property about the planner's progress that can be queried by a benchmarking routine. | |
typedef std::map< std::string, PlannerProgressProperty > | PlannerProgressProperties |
A dictionary which maps the name of a progress property to the function to be used for querying that property. | |
Public Member Functions | |
SPARStwo (const base::SpaceInformationPtr &si) | |
Constructor. | |
virtual | ~SPARStwo (void) |
Destructor. | |
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(). | |
void | setStretchFactor (double t) |
Sets the stretch factor. | |
void | setSparseDeltaFraction (double D) |
Sets vertex visibility range as a fraction of max. extent. | |
void | setDenseDeltaFraction (double d) |
Sets interface support tolerance as a fraction of max. extent. | |
void | setMaxFailures (unsigned int m) |
Sets the maximum failures until termination. | |
unsigned int | getMaxFailures () const |
Retrieve the maximum consecutive failure limit. | |
double | getDenseDeltaFraction () const |
Retrieve the dense graph interface support delta. | |
double | getSparseDeltaFraction () const |
Retrieve the sparse graph visibility range delta. | |
double | getStretchFactor () const |
Retrieve the spanner's set stretch factor. | |
void | constructRoadmap (const base::PlannerTerminationCondition &ptc) |
While the termination condition permits, construct the spanner graph. | |
void | constructRoadmap (const base::PlannerTerminationCondition &ptc, bool stopOnMaxFail) |
While the termination condition permits, construct the spanner graph. If stopOnMaxFail is true, the function also terminates when the failure limit set by setMaxFailures() is reached. | |
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. Start and goal states from the currently specified ProblemDefinition are cached. This means that between calls to solve(), input states are only added, not removed. When using PRM as a multi-query planner, the input states should be however cleared, without clearing the roadmap itself. This can be done using the clearQuery() function. | |
void | clearQuery (void) |
Clear the query previously loaded from the ProblemDefinition. Subsequent calls to solve() will reuse the previously computed roadmap, but will clear the set of input states constructed by the previous call to solve(). This enables multi-query functionality for PRM. | |
virtual void | clear (void) |
Clear all internal datastructures. Planner settings are not affected. Subsequent calls to solve() will ignore all previous work. | |
template<template< typename T > class NN> | |
void | setNearestNeighbors (void) |
Set a different nearest neighbors datastructure. | |
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. | |
const Graph & | getRoadmap (void) const |
Retrieve the computed roadmap. | |
unsigned int | milestoneCount (void) const |
Get the number of vertices in the sparse roadmap. | |
long unsigned int | getIterations (void) const |
Get the number of iterations the algorithm performed. | |
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). | |
![]() | |
Planner (const SpaceInformationPtr &si, const std::string &name) | |
Constructor. | |
virtual | ~Planner (void) |
Destructor. | |
template<class T > | |
T * | as (void) |
Cast this instance to a desired type. More... | |
template<class T > | |
const T * | as (void) const |
Cast this instance to a desired type. More... | |
const SpaceInformationPtr & | getSpaceInformation (void) const |
Get the space information this planner is using. | |
const ProblemDefinitionPtr & | getProblemDefinition (void) const |
Get the problem definition the planner is trying to solve. | |
const PlannerInputStates & | getPlannerInputStates (void) const |
Get the planner input states. | |
PlannerStatus | solve (const PlannerTerminationConditionFn &ptc, double checkInterval) |
Same as above except the termination condition is only evaluated at a specified interval. | |
PlannerStatus | solve (double solveTime) |
Same as above except the termination condition is solely a time limit: the number of seconds the algorithm is allowed to spend planning. | |
const std::string & | getName (void) const |
Get the name of the planner. | |
void | setName (const std::string &name) |
Set the name of the planner. | |
const PlannerSpecs & | getSpecs (void) const |
Return the specifications (capabilities of this planner) | |
virtual void | checkValidity (void) |
Check to see if the planner is in a working state (setup has been called, a goal was set, the input states seem to be in order). In case of error, this function throws an exception. | |
bool | isSetup (void) const |
Check if setup() was called for this planner. | |
ParamSet & | params (void) |
Get the parameters for this planner. | |
const ParamSet & | params (void) const |
Get the parameters for this planner. | |
const PlannerProgressProperties & | getPlannerProgressProperties () const |
Retrieve a planner's planner progress property map. | |
virtual void | printProperties (std::ostream &out) const |
Print properties of the motion planner. | |
virtual void | printSettings (std::ostream &out) const |
Print information about the motion planner's settings. | |
Protected Member Functions | |
void | freeMemory (void) |
Free all the memory allocated by the planner. | |
void | checkQueryStateInitialization (void) |
Check that the query vertex is initialized (used for internal nearest neighbor searches) | |
bool | checkAddCoverage (const base::State *qNew, std::vector< Vertex > &visibleNeighborhood) |
Checks to see if the sample needs to be added to ensure coverage of the space. | |
bool | checkAddConnectivity (const base::State *qNew, std::vector< Vertex > &visibleNeighborhood) |
Checks to see if the sample needs to be added to ensure connectivity. | |
bool | checkAddInterface (const base::State *qNew, std::vector< Vertex > &graphNeighborhood, std::vector< Vertex > &visibleNeighborhood) |
Checks to see if the current sample reveals the existence of an interface, and if so, tries to bridge it. | |
bool | checkAddPath (Vertex v) |
Checks vertex v for short paths through its region and adds when appropriate. | |
void | resetFailures (void) |
A reset function for resetting the failures count. | |
void | findGraphNeighbors (base::State *st, std::vector< Vertex > &graphNeighborhood, std::vector< Vertex > &visibleNeighborhood) |
Finds visible nodes in the graph near st. | |
void | approachGraph (Vertex v) |
Approaches the graph from a given vertex. | |
Vertex | findGraphRepresentative (base::State *st) |
Finds the representative of the input state, st. | |
void | findCloseRepresentatives (base::State *workArea, const base::State *qNew, Vertex qRep, std::map< Vertex, base::State * > &closeRepresentatives, const base::PlannerTerminationCondition &ptc) |
Finds representatives of samples near qNew_ which are not his representative. | |
void | updatePairPoints (Vertex rep, const base::State *q, Vertex r, const base::State *s) |
High-level method which updates pair point information for repV_ with neighbor r. | |
void | computeVPP (Vertex v, Vertex vp, std::vector< Vertex > &VPPs) |
Computes all nodes which qualify as a candidate v" for v and vp. | |
void | computeX (Vertex v, Vertex vp, Vertex vpp, std::vector< Vertex > &Xs) |
Computes all nodes which qualify as a candidate x for v, v', and v". | |
VertexPair | index (Vertex vp, Vertex vpp) |
Rectifies indexing order for accessing the vertex data. | |
InterfaceData & | getData (Vertex v, Vertex vp, Vertex vpp) |
Retrieves the Vertex data associated with v,vp,vpp. | |
void | distanceCheck (Vertex rep, const base::State *q, Vertex r, const base::State *s, Vertex rp) |
Performs distance checking for the candidate new state, q against the current information. | |
void | abandonLists (base::State *st) |
When a new guard is added at state st, finds all guards who must abandon their interface information and deletes that information. | |
Vertex | addGuard (base::State *state, GuardType type) |
Construct a guard for a given state (state) and store it in the nearest neighbors data structure. | |
void | connectGuards (Vertex v, Vertex vp) |
Connect two guards in the roadmap. | |
bool | haveSolution (const std::vector< Vertex > &start, const std::vector< Vertex > &goal, base::PathPtr &solution) |
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 a solution is found, the path is saved. | |
void | checkForSolution (const base::PlannerTerminationCondition &ptc, base::PathPtr &solution) |
bool | reachedTerminationCriterion (void) const |
Returns true if we have reached the iteration failures limit, maxFailures_ or if a solution was added. | |
bool | reachedFailureLimit (void) const |
Returns whether we have reached the iteration failures limit, maxFailures_. | |
base::PathPtr | constructSolution (const Vertex start, const Vertex goal) const |
Given two milestones from the same connected component, construct a path connecting them and set it as the solution. | |
bool | sameComponent (Vertex m1, Vertex m2) |
Check if two milestones (m1 and m2) are part of the same connected component. This is not a const function since we use incremental connected components from boost. | |
double | distanceFunction (const Vertex a, const Vertex b) const |
Compute distance between two milestones (this is simply distance between the states of the milestones) | |
![]() | |
template<typename T , typename PlannerType , typename SetterType , typename GetterType > | |
void | declareParam (const std::string &name, const PlannerType &planner, const SetterType &setter, const GetterType &getter, const std::string &rangeSuggestion="") |
This function declares a parameter for this planner instance, and specifies the setter and getter functions. | |
template<typename T , typename PlannerType , typename SetterType > | |
void | declareParam (const std::string &name, const PlannerType &planner, const SetterType &setter, const std::string &rangeSuggestion="") |
This function declares a parameter for this planner instance, and specifies the setter function. | |
void | addPlannerProgressProperty (const std::string &progressPropertyName, const PlannerProgressProperty &prop) |
Add a planner progress property called progressPropertyName with a property querying function prop to this planner's progress property map. | |
Protected Attributes | |
base::ValidStateSamplerPtr | sampler_ |
Sampler user for generating valid samples in the state space. | |
base::StateSamplerPtr | simpleSampler_ |
Sampler user for generating random in the state space. | |
boost::shared_ptr < NearestNeighbors< Vertex > > | nn_ |
Nearest neighbors data structure. | |
Graph | g_ |
Connectivity graph. | |
std::vector< Vertex > | startM_ |
Array of start milestones. | |
std::vector< Vertex > | goalM_ |
Array of goal milestones. | |
Vertex | queryVertex_ |
Vertex for performing nearest neighbor queries. | |
double | stretchFactor_ |
Stretch Factor as per graph spanner literature (multiplicative bound on path quality) | |
double | sparseDeltaFraction_ |
Maximum visibility range for nodes in the graph as a fraction of maximum extent. | |
double | denseDeltaFraction_ |
Maximum range for allowing two samples to support an interface as a fraction of maximum extent. | |
unsigned int | maxFailures_ |
The number of consecutive failures to add to the graph before termination. | |
unsigned int | nearSamplePoints_ |
Number of sample points to use when trying to detect interfaces. | |
boost::property_map< Graph, vertex_state_t >::type | stateProperty_ |
Access to the internal base::state at each Vertex. | |
PathSimplifierPtr | psimp_ |
A path simplifier used to simplify dense paths added to the graph. | |
boost::property_map< Graph, boost::edge_weight_t >::type | weightProperty_ |
Access to the weights of each Edge. | |
boost::property_map< Graph, vertex_color_t >::type | colorProperty_ |
Access to the colors for the vertices. | |
boost::property_map< Graph, vertex_interface_data_t > ::type | interfaceDataProperty_ |
Access to the interface pair information for the vertices. | |
boost::disjoint_sets < boost::property_map< Graph, boost::vertex_rank_t >::type, boost::property_map< Graph, boost::vertex_predecessor_t > ::type > | disjointSets_ |
Data structure that maintains the connected components. | |
RNG | rng_ |
Random number generator. | |
bool | addedSolution_ |
A flag indicating that a solution has been added during solve() | |
unsigned int | consecutiveFailures_ |
A counter for the number of consecutive failed iterations of the algorithm. | |
long unsigned int | iterations_ |
A counter for the number of iterations of the algorithm. | |
double | sparseDelta_ |
Maximum visibility range for nodes in the graph. | |
double | denseDelta_ |
Maximum range for allowing two samples to support an interface. | |
boost::mutex | graphMutex_ |
Mutex to guard access to the Graph member (g_) | |
![]() | |
SpaceInformationPtr | si_ |
The space information for which planning is done. | |
ProblemDefinitionPtr | pdef_ |
The user set problem definition. | |
PlannerInputStates | pis_ |
Utility class to extract valid input states. | |
std::string | name_ |
The name of this planner. | |
PlannerSpecs | specs_ |
The specifications of the planner (its capabilities) | |
ParamSet | params_ |
A map from parameter names to parameter instances for this planner. This field is populated by the declareParam() function. | |
PlannerProgressProperties | plannerProgressProperties_ |
A mapping between this planner's progress property names and the functions used for querying those progress properties. | |
bool | setup_ |
Flag indicating whether setup() has been called. | |
SPArse Roadmap Spanner Version 2.0
Definition at line 79 of file SPARStwo.h.
typedef boost::adjacency_list< boost::vecS, boost::vecS, boost::undirectedS, boost::property < vertex_state_t, base::State*, boost::property < boost::vertex_predecessor_t, VertexIndexType, boost::property < boost::vertex_rank_t, VertexIndexType, boost::property < vertex_color_t, GuardType, boost::property < vertex_interface_data_t, InterfaceHashStruct > > > > >, boost::property < boost::edge_weight_t, double > > ompl::geometric::SPARStwo::Graph |
The underlying roadmap graph.
Definition at line 229 of file SPARStwo.h.
|
protected |
Thread that checks for solution
Definition at line 320 of file SPARStwo.cpp.