A conceptual representation of samples as an edge-implicit random geometric graph. More...
#include <ompl/geometric/planners/informedtrees/bitstar/ImplicitGraph.h>
Public Member Functions | |
| ImplicitGraph (NameFunc nameFunc) | |
| Construct an implicit graph. | |
| virtual | ~ImplicitGraph ()=default |
| Destruct the graph using default destruction. | |
| void | setup (const ompl::base::SpaceInformationPtr &spaceInformation, const ompl::base::ProblemDefinitionPtr &problemDefinition, CostHelper *costHelper, SearchQueue *searchQueue, const ompl::base::Planner *plannerPtr, ompl::base::PlannerInputStates &inputStates) |
| Setup the ImplicitGraph, must be called before use. Does not take a copy of the PlannerInputStates, but checks it for starts/goals. | |
| void | reset () |
| Reset the graph to the state of construction. | |
| bool | hasAStart () const |
| Gets whether the graph contains a start or not. | |
| bool | hasAGoal () const |
| Gets whether the graph contains a goal or not. | |
| VertexPtrVector::const_iterator | startVerticesBeginConst () const |
| Returns a const-iterator to the front of the start-vertex vector. | |
| VertexPtrVector::const_iterator | startVerticesEndConst () const |
| Returns a const-iterator to the end of the start-vertex vector. | |
| VertexPtrVector::const_iterator | goalVerticesBeginConst () const |
| Returns a const-iterator to the front of the goal-vertex vector. | |
| VertexPtrVector::const_iterator | goalVerticesEndConst () const |
| Returns a const-iterator to the end of the goal-vertex vector. | |
| ompl::base::Cost | minCost () const |
| Get the minimum cost solution possible for this problem. | |
| bool | hasInformedMeasure () const |
| Query whether the underlying state sampler can provide an informed measure. | |
| double | getInformedMeasure (const ompl::base::Cost &cost) const |
| Query the underlying state sampler for the informed measure of the problem. | |
| double | distance (const VertexConstPtr &a, const VertexConstPtr &b) const |
| Computes the distance between two states. | |
| double | distance (const VertexConstPtrPair &vertices) const |
| Computes the distance between two states. | |
| void | nearestSamples (const VertexPtr &vertex, VertexPtrVector *neighbourSamples) |
| Get the nearest unconnected samples using the appropriate "near" definition (i.e., k or r). | |
| void | getGraphAsPlannerData (ompl::base::PlannerData &data) const |
| Adds the graph to the given PlannerData struct. | |
| VertexConstPtr | closestVertexToGoal () const |
| IF BEING TRACKED, returns the closest vertex in the tree to the goal. | |
| double | smallestDistanceToGoal () const |
| IF BEING TRACKED, returns the how close vertices in the tree are to the goal. | |
| unsigned int | getConnectivityK () const |
| Get the k of this k-nearest RGG. | |
| double | getConnectivityR () const |
| Get the radius of this r-disc RGG. | |
| VertexPtrVector | getCopyOfSamples () const |
| Get a copy of all samples. | |
| void | registerSolutionCost (const ompl::base::Cost &solutionCost) |
| Mark that a solution has been found and that the graph should be limited to the given heuristic value. | |
| void | updateStartAndGoalStates (ompl::base::PlannerInputStates &inputStates, const base::PlannerTerminationCondition &terminationCondition) |
| Adds any new goals or starts that have appeared in the problem definition to the vector of vertices and the queue. Creates a new informed sampler if necessary. | |
| void | addNewSamples (const unsigned int &numSamples) |
| Increase the resolution of the graph-based approximation of the continuous search domain by adding a batch of new samples. | |
| std::pair< unsigned int, unsigned int > | prune (double prunedMeasure) |
| Prune the samples to the subproblem of the given measure. Returns the number of vertices disconnected and the number of samples removed. | |
| void | addToSamples (const VertexPtr &sample) |
| Add an unconnected sample. | |
| void | addToSamples (const VertexPtrVector &samples) |
| Add a vector of unconnected samples. | |
| void | removeFromSamples (const VertexPtr &sample) |
| Remove a sample from the sample set. | |
| void | pruneSample (const VertexPtr &sample) |
| Remove an unconnected sample. | |
| void | recycleSample (const VertexPtr &sample) |
| Insert a sample into the set for recycled samples. | |
| void | registerAsVertex (const VertexPtr &vertex) |
| Add a vertex to the tree, optionally moving it from the set of unconnected samples. | |
| unsigned int | removeFromVertices (const VertexPtr &sample, bool moveToFree) |
| Remove a vertex from the tree, can optionally be allowed to move it to the set of unconnected samples if may still be useful. | |
| std::pair< unsigned int, unsigned int > | pruneVertex (const VertexPtr &vertex) |
| Remove a vertex and mark as pruned. | |
| void | removeEdgeBetweenVertexAndParent (const VertexPtr &child, bool cascadeCostUpdates) |
| Disconnect a vertex from its parent by removing the edges stored in itself, and its parents. Cascades cost updates if requested. | |
| void | setRewireFactor (double rewireFactor) |
| Set the rewiring scale factor, s, such that r_rrg = s \times r_rrg*. | |
| double | getRewireFactor () const |
| Get the rewiring scale factor. | |
| void | setUseKNearest (bool useKNearest) |
| Enable a k-nearest search for instead of an r-disc search. | |
| bool | getUseKNearest () const |
| Get whether a k-nearest search is being used. | |
| void | setJustInTimeSampling (bool useJit) |
| bool | getJustInTimeSampling () const |
| Get whether we're using just-in-time sampling. | |
| void | setDropSamplesOnPrune (bool dropSamples) |
| Set whether unconnected samples are dropped on pruning. | |
| void | setPruning (bool usePruning) |
| Set whether samples that are provably not beneficial should be kept around. | |
| bool | getDropSamplesOnPrune () const |
| Get whether unconnected samples are dropped on pruning. | |
| void | setTrackApproximateSolutions (bool findApproximate) |
| Set whether to track approximate solutions during the search. | |
| bool | getTrackApproximateSolutions () const |
| Get whether approximate solutions are tracked during the search. | |
| void | setAverageNumOfAllowedFailedAttemptsWhenSampling (std::size_t number) |
| Set the average number of allowed failed attempts when sampling. | |
| std::size_t | getAverageNumOfAllowedFailedAttemptsWhenSampling () const |
| Get the average number of allowed failed attempts when sampling. | |
| template<template< typename T > class NN> | |
| void | setNearestNeighbors () |
| Set a different nearest neighbours datastructure. | |
| unsigned int | numSamples () const |
| The number of samples. | |
| unsigned int | numVertices () const |
| The number of vertices in the search tree. | |
| unsigned int | numStatesGenerated () const |
| The total number of states generated. | |
| unsigned int | numVerticesConnected () const |
| The total number of vertices added to the graph. | |
| unsigned int | numFreeStatesPruned () const |
| The number of states pruned. | |
| unsigned int | numVerticesDisconnected () const |
| The number of tree vertices disconnected. | |
| unsigned int | numNearestLookups () const |
| The number of nearest neighbour calls. | |
| unsigned int | numStateCollisionChecks () const |
| The number of state collision checks. | |
| bool | canVertexBeDisconnected (const VertexPtr &vertex) const |
| Returns whether the vertex can be pruned, i.e., whether it could provide a better solution given. the current graph. The check should always be g_t(v) + h^(v) >= g_t(x_g). | |
| bool | canSampleBePruned (const VertexPtr &sample) const |
| Returns whether the sample can be pruned, i.e., whether it could ever provide a better solution. The check should always be g^(v) + h^(v) >= g_t(x_g). | |
Detailed Description
A conceptual representation of samples as an edge-implicit random geometric graph.
- Short Description
- An edge-implicit representation of a random geometric graph. TODO(Marlin): Separating the search tree from the RGG seems conceptually cleaner. Think about its implications.
Definition at line 56 of file ImplicitGraph.h.
Constructor & Destructor Documentation
◆ ImplicitGraph()
| ompl::geometric::BITstar::ImplicitGraph::ImplicitGraph | ( | NameFunc | nameFunc | ) |
Construct an implicit graph.
Definition at line 86 of file ImplicitGraph.cpp.
Member Function Documentation
◆ addNewSamples()
| void ompl::geometric::BITstar::ImplicitGraph::addNewSamples | ( | const unsigned int & | numSamples | ) |
Increase the resolution of the graph-based approximation of the continuous search domain by adding a batch of new samples.
Definition at line 602 of file ImplicitGraph.cpp.
◆ addToSamples() [1/2]
| void ompl::geometric::BITstar::ImplicitGraph::addToSamples | ( | const VertexPtr & | sample | ) |
Add an unconnected sample.
Definition at line 654 of file ImplicitGraph.cpp.
◆ addToSamples() [2/2]
| void ompl::geometric::BITstar::ImplicitGraph::addToSamples | ( | const VertexPtrVector & | samples | ) |
Add a vector of unconnected samples.
Definition at line 667 of file ImplicitGraph.cpp.
◆ canSampleBePruned()
| bool ompl::geometric::BITstar::ImplicitGraph::canSampleBePruned | ( | const VertexPtr & | sample | ) | const |
Returns whether the sample can be pruned, i.e., whether it could ever provide a better solution. The check should always be g^(v) + h^(v) >= g_t(x_g).
Definition at line 1252 of file ImplicitGraph.cpp.
◆ canVertexBeDisconnected()
| bool ompl::geometric::BITstar::ImplicitGraph::canVertexBeDisconnected | ( | const VertexPtr & | vertex | ) | const |
Returns whether the vertex can be pruned, i.e., whether it could provide a better solution given. the current graph. The check should always be g_t(v) + h^(v) >= g_t(x_g).
Definition at line 1240 of file ImplicitGraph.cpp.
◆ closestVertexToGoal()
| BITstar::VertexConstPtr ompl::geometric::BITstar::ImplicitGraph::closestVertexToGoal | ( | ) | const |
IF BEING TRACKED, returns the closest vertex in the tree to the goal.
Definition at line 1483 of file ImplicitGraph.cpp.
◆ distance() [1/2]
| double ompl::geometric::BITstar::ImplicitGraph::distance | ( | const VertexConstPtr & | a, |
| const VertexConstPtr & | b ) const |
Computes the distance between two states.
Definition at line 259 of file ImplicitGraph.cpp.
◆ distance() [2/2]
| double ompl::geometric::BITstar::ImplicitGraph::distance | ( | const VertexConstPtrPair & | vertices | ) | const |
Computes the distance between two states.
Definition at line 280 of file ImplicitGraph.cpp.
◆ getAverageNumOfAllowedFailedAttemptsWhenSampling()
| std::size_t ompl::geometric::BITstar::ImplicitGraph::getAverageNumOfAllowedFailedAttemptsWhenSampling | ( | ) | const |
Get the average number of allowed failed attempts when sampling.
Definition at line 1675 of file ImplicitGraph.cpp.
◆ getConnectivityK()
| unsigned int ompl::geometric::BITstar::ImplicitGraph::getConnectivityK | ( | ) | const |
Get the k of this k-nearest RGG.
Definition at line 1505 of file ImplicitGraph.cpp.
◆ getConnectivityR()
| double ompl::geometric::BITstar::ImplicitGraph::getConnectivityR | ( | ) | const |
Get the radius of this r-disc RGG.
Definition at line 1516 of file ImplicitGraph.cpp.
◆ getCopyOfSamples()
| BITstar::VertexPtrVector ompl::geometric::BITstar::ImplicitGraph::getCopyOfSamples | ( | ) | const |
Get a copy of all samples.
Definition at line 1527 of file ImplicitGraph.cpp.
◆ getDropSamplesOnPrune()
| bool ompl::geometric::BITstar::ImplicitGraph::getDropSamplesOnPrune | ( | ) | const |
Get whether unconnected samples are dropped on pruning.
Definition at line 1631 of file ImplicitGraph.cpp.
◆ getGraphAsPlannerData()
| void ompl::geometric::BITstar::ImplicitGraph::getGraphAsPlannerData | ( | ompl::base::PlannerData & | data | ) | const |
Adds the graph to the given PlannerData struct.
Definition at line 305 of file ImplicitGraph.cpp.
◆ getInformedMeasure()
| double ompl::geometric::BITstar::ImplicitGraph::getInformedMeasure | ( | const ompl::base::Cost & | cost | ) | const |
Query the underlying state sampler for the informed measure of the problem.
Definition at line 1478 of file ImplicitGraph.cpp.
◆ getJustInTimeSampling()
| bool ompl::geometric::BITstar::ImplicitGraph::getJustInTimeSampling | ( | ) | const |
Get whether we're using just-in-time sampling.
Definition at line 1605 of file ImplicitGraph.cpp.
◆ getRewireFactor()
| double ompl::geometric::BITstar::ImplicitGraph::getRewireFactor | ( | ) | const |
Get the rewiring scale factor.
Definition at line 1547 of file ImplicitGraph.cpp.
◆ getTrackApproximateSolutions()
| bool ompl::geometric::BITstar::ImplicitGraph::getTrackApproximateSolutions | ( | ) | const |
Get whether approximate solutions are tracked during the search.
Definition at line 1665 of file ImplicitGraph.cpp.
◆ getUseKNearest()
| bool ompl::geometric::BITstar::ImplicitGraph::getUseKNearest | ( | ) | const |
Get whether a k-nearest search is being used.
Definition at line 1575 of file ImplicitGraph.cpp.
◆ goalVerticesBeginConst()
| BITstar::VertexPtrVector::const_iterator ompl::geometric::BITstar::ImplicitGraph::goalVerticesBeginConst | ( | ) | const |
Returns a const-iterator to the front of the goal-vertex vector.
Definition at line 1458 of file ImplicitGraph.cpp.
◆ goalVerticesEndConst()
| BITstar::VertexPtrVector::const_iterator ompl::geometric::BITstar::ImplicitGraph::goalVerticesEndConst | ( | ) | const |
Returns a const-iterator to the end of the goal-vertex vector.
Definition at line 1463 of file ImplicitGraph.cpp.
◆ hasAGoal()
| bool ompl::geometric::BITstar::ImplicitGraph::hasAGoal | ( | ) | const |
Gets whether the graph contains a goal or not.
Definition at line 1443 of file ImplicitGraph.cpp.
◆ hasAStart()
| bool ompl::geometric::BITstar::ImplicitGraph::hasAStart | ( | ) | const |
Gets whether the graph contains a start or not.
Definition at line 1438 of file ImplicitGraph.cpp.
◆ hasInformedMeasure()
| bool ompl::geometric::BITstar::ImplicitGraph::hasInformedMeasure | ( | ) | const |
Query whether the underlying state sampler can provide an informed measure.
Definition at line 1473 of file ImplicitGraph.cpp.
◆ minCost()
| ompl::base::Cost ompl::geometric::BITstar::ImplicitGraph::minCost | ( | ) | const |
Get the minimum cost solution possible for this problem.
Definition at line 1468 of file ImplicitGraph.cpp.
◆ nearestSamples()
| void ompl::geometric::BITstar::ImplicitGraph::nearestSamples | ( | const VertexPtr & | vertex, |
| VertexPtrVector * | neighbourSamples ) |
Get the nearest unconnected samples using the appropriate "near" definition (i.e., k or r).
Definition at line 285 of file ImplicitGraph.cpp.
◆ numFreeStatesPruned()
| unsigned int ompl::geometric::BITstar::ImplicitGraph::numFreeStatesPruned | ( | ) | const |
The number of states pruned.
Definition at line 1721 of file ImplicitGraph.cpp.
◆ numNearestLookups()
| unsigned int ompl::geometric::BITstar::ImplicitGraph::numNearestLookups | ( | ) | const |
The number of nearest neighbour calls.
Definition at line 1731 of file ImplicitGraph.cpp.
◆ numSamples()
| unsigned int ompl::geometric::BITstar::ImplicitGraph::numSamples | ( | ) | const |
The number of samples.
Definition at line 1698 of file ImplicitGraph.cpp.
◆ numStateCollisionChecks()
| unsigned int ompl::geometric::BITstar::ImplicitGraph::numStateCollisionChecks | ( | ) | const |
The number of state collision checks.
Definition at line 1736 of file ImplicitGraph.cpp.
◆ numStatesGenerated()
| unsigned int ompl::geometric::BITstar::ImplicitGraph::numStatesGenerated | ( | ) | const |
The total number of states generated.
Definition at line 1711 of file ImplicitGraph.cpp.
◆ numVertices()
| unsigned int ompl::geometric::BITstar::ImplicitGraph::numVertices | ( | ) | const |
The number of vertices in the search tree.
Definition at line 1703 of file ImplicitGraph.cpp.
◆ numVerticesConnected()
| unsigned int ompl::geometric::BITstar::ImplicitGraph::numVerticesConnected | ( | ) | const |
The total number of vertices added to the graph.
Definition at line 1716 of file ImplicitGraph.cpp.
◆ numVerticesDisconnected()
| unsigned int ompl::geometric::BITstar::ImplicitGraph::numVerticesDisconnected | ( | ) | const |
The number of tree vertices disconnected.
Definition at line 1726 of file ImplicitGraph.cpp.
◆ prune()
| std::pair< unsigned int, unsigned int > ompl::geometric::BITstar::ImplicitGraph::prune | ( | double | prunedMeasure | ) |
Prune the samples to the subproblem of the given measure. Returns the number of vertices disconnected and the number of samples removed.
Definition at line 631 of file ImplicitGraph.cpp.
◆ pruneSample()
| void ompl::geometric::BITstar::ImplicitGraph::pruneSample | ( | const VertexPtr & | sample | ) |
Remove an unconnected sample.
Definition at line 688 of file ImplicitGraph.cpp.
◆ pruneVertex()
| std::pair< unsigned int, unsigned int > ompl::geometric::BITstar::ImplicitGraph::pruneVertex | ( | const VertexPtr & | vertex | ) |
Remove a vertex and mark as pruned.
Definition at line 809 of file ImplicitGraph.cpp.
◆ recycleSample()
| void ompl::geometric::BITstar::ImplicitGraph::recycleSample | ( | const VertexPtr & | sample | ) |
Insert a sample into the set for recycled samples.
Definition at line 729 of file ImplicitGraph.cpp.
◆ registerAsVertex()
| void ompl::geometric::BITstar::ImplicitGraph::registerAsVertex | ( | const VertexPtr & | vertex | ) |
Add a vertex to the tree, optionally moving it from the set of unconnected samples.
Definition at line 736 of file ImplicitGraph.cpp.
◆ registerSolutionCost()
| void ompl::geometric::BITstar::ImplicitGraph::registerSolutionCost | ( | const ompl::base::Cost & | solutionCost | ) |
Mark that a solution has been found and that the graph should be limited to the given heuristic value.
Definition at line 350 of file ImplicitGraph.cpp.
◆ removeEdgeBetweenVertexAndParent()
| void ompl::geometric::BITstar::ImplicitGraph::removeEdgeBetweenVertexAndParent | ( | const VertexPtr & | child, |
| bool | cascadeCostUpdates ) |
Disconnect a vertex from its parent by removing the edges stored in itself, and its parents. Cascades cost updates if requested.
Definition at line 885 of file ImplicitGraph.cpp.
◆ removeFromSamples()
| void ompl::geometric::BITstar::ImplicitGraph::removeFromSamples | ( | const VertexPtr & | sample | ) |
Remove a sample from the sample set.
Definition at line 680 of file ImplicitGraph.cpp.
◆ removeFromVertices()
| unsigned int ompl::geometric::BITstar::ImplicitGraph::removeFromVertices | ( | const VertexPtr & | sample, |
| bool | moveToFree ) |
Remove a vertex from the tree, can optionally be allowed to move it to the set of unconnected samples if may still be useful.
Definition at line 758 of file ImplicitGraph.cpp.
◆ reset()
| void ompl::geometric::BITstar::ImplicitGraph::reset | ( | ) |
Reset the graph to the state of construction.
Definition at line 190 of file ImplicitGraph.cpp.
◆ setAverageNumOfAllowedFailedAttemptsWhenSampling()
| void ompl::geometric::BITstar::ImplicitGraph::setAverageNumOfAllowedFailedAttemptsWhenSampling | ( | std::size_t | number | ) |
Set the average number of allowed failed attempts when sampling.
Definition at line 1670 of file ImplicitGraph.cpp.
◆ setDropSamplesOnPrune()
| void ompl::geometric::BITstar::ImplicitGraph::setDropSamplesOnPrune | ( | bool | dropSamples | ) |
Set whether unconnected samples are dropped on pruning.
Definition at line 1610 of file ImplicitGraph.cpp.
◆ setJustInTimeSampling()
| void ompl::geometric::BITstar::ImplicitGraph::setJustInTimeSampling | ( | bool | useJit | ) |
Enable sampling "just-in-time", i.e., only when necessary for a nearest-neighbour search.
Definition at line 1580 of file ImplicitGraph.cpp.
◆ setNearestNeighbors()
| void ompl::geometric::BITstar::ImplicitGraph::setNearestNeighbors | ( | ) |
Set a different nearest neighbours datastructure.
Definition at line 1681 of file ImplicitGraph.cpp.
◆ setPruning()
| void ompl::geometric::BITstar::ImplicitGraph::setPruning | ( | bool | usePruning | ) |
Set whether samples that are provably not beneficial should be kept around.
Definition at line 1626 of file ImplicitGraph.cpp.
◆ setRewireFactor()
| void ompl::geometric::BITstar::ImplicitGraph::setRewireFactor | ( | double | rewireFactor | ) |
Set the rewiring scale factor, s, such that r_rrg = s \times r_rrg*.
Definition at line 1534 of file ImplicitGraph.cpp.
◆ setTrackApproximateSolutions()
| void ompl::geometric::BITstar::ImplicitGraph::setTrackApproximateSolutions | ( | bool | findApproximate | ) |
Set whether to track approximate solutions during the search.
Definition at line 1636 of file ImplicitGraph.cpp.
◆ setup()
| void ompl::geometric::BITstar::ImplicitGraph::setup | ( | const ompl::base::SpaceInformationPtr & | spaceInformation, |
| const ompl::base::ProblemDefinitionPtr & | problemDefinition, | ||
| CostHelper * | costHelper, | ||
| SearchQueue * | searchQueue, | ||
| const ompl::base::Planner * | plannerPtr, | ||
| ompl::base::PlannerInputStates & | inputStates ) |
Setup the ImplicitGraph, must be called before use. Does not take a copy of the PlannerInputStates, but checks it for starts/goals.
Definition at line 91 of file ImplicitGraph.cpp.
◆ setUseKNearest()
| void ompl::geometric::BITstar::ImplicitGraph::setUseKNearest | ( | bool | useKNearest | ) |
Enable a k-nearest search for instead of an r-disc search.
Definition at line 1552 of file ImplicitGraph.cpp.
◆ smallestDistanceToGoal()
| double ompl::geometric::BITstar::ImplicitGraph::smallestDistanceToGoal | ( | ) | const |
IF BEING TRACKED, returns the how close vertices in the tree are to the goal.
Definition at line 1494 of file ImplicitGraph.cpp.
◆ startVerticesBeginConst()
| BITstar::VertexPtrVector::const_iterator ompl::geometric::BITstar::ImplicitGraph::startVerticesBeginConst | ( | ) | const |
Returns a const-iterator to the front of the start-vertex vector.
Definition at line 1448 of file ImplicitGraph.cpp.
◆ startVerticesEndConst()
| BITstar::VertexPtrVector::const_iterator ompl::geometric::BITstar::ImplicitGraph::startVerticesEndConst | ( | ) | const |
Returns a const-iterator to the end of the start-vertex vector.
Definition at line 1453 of file ImplicitGraph.cpp.
◆ updateStartAndGoalStates()
| void ompl::geometric::BITstar::ImplicitGraph::updateStartAndGoalStates | ( | ompl::base::PlannerInputStates & | inputStates, |
| const base::PlannerTerminationCondition & | terminationCondition ) |
Adds any new goals or starts that have appeared in the problem definition to the vector of vertices and the queue. Creates a new informed sampler if necessary.
Definition at line 365 of file ImplicitGraph.cpp.
The documentation for this class was generated from the following files:
- ompl/geometric/planners/informedtrees/bitstar/ImplicitGraph.h
- ompl/geometric/planners/informedtrees/bitstar/src/ImplicitGraph.cpp