ImplicitGraph.cpp
97 // Store that I am setup so that any debug-level tests will pass. This requires assuring that this function
126 // Add any start and goals vertices that exist to the queue, but do NOT wait for any more goals:
136 // A not horrible place to start would be hypercube proportional to the distance between the start and
137 // goal. It's not *great*, but at least it sort of captures the order-of-magnitude of the problem.
151 throw ompl::Exception("For unbounded planning problems, at least one start and one goal must exist "
159 // The scale on the maximum distance, i.e. the width of the hypercube is equal to this value times the
192 // Reset everything to the state of construction OTHER than planner name and settings/parameters
274 // Using RRTstar as an example, this order gives us the distance FROM the queried state TO the other
285 void BITstar::ImplicitGraph::nearestSamples(const VertexPtr &vertex, VertexPtrVector *neighbourSamples)
309 // base::PlannerDataVertex takes a raw pointer to a state. I want to guarantee, that the state lives as long
366 ompl::base::PlannerInputStates &inputStates, const base::PlannerTerminationCondition &terminationCondition)
375 Add the new starts and goals to the vectors of said vertices. Do goals first, as they are only added as
376 samples. We do this as nested conditions so we always call nextGoal(ptc) at least once (regardless of
377 whether there are moreGoalStates or not) in case we have been given a non trivial PTC that wants us to wait,
378 but do *not* call it again if there are no more goals (as in the nontrivial PTC case, doing so would cause
408 And then do the same for starts. We do this last as the starts are added to the queue, which uses a
409 cost-to-go heuristic in it's ordering, and for that we want all the goals updated. As there is no way to
410 wait for new *start* states, this loop can be cleaner There is no need to rebuild the queue when we add
411 start vertices, as the queue is ordered on current cost-to-come, and adding a start doesn't change that.
445 // The end point of the vector to consider. We will delete by swapping elements to the end, moving this
499 // Similarly, if we added a goal and have previously pruned starts, we will have to do the same on those
505 // The end point of the vector to consider. We will delete by swapping elements to the end, moving this
581 // Iterate through the existing vertices and find the current best approximate solution (if enabled)
589 // Make sure that if we have a goal, we also have a start, since there's no way to wait for more *starts*
592 OMPL_WARN("%s (ImplicitGraph): The problem has a goal but not a start. BIT* cannot find a solution "
624 // We don't add actual *new* samples until the next time "nearestSamples" is called. This is to support JIT
691 // The use count of the passed shared pointer. Used in debug mode to assert that we took ownership of our
695 // A copy of the sample pointer to be removed so we can't delete it out from under ourselves (occurs when
755 unsigned int BITstar::ImplicitGraph::removeFromVertices(const VertexPtr &vertex, bool moveToFree)
761 // The use count of the passed shared pointer. Used in debug mode to assert that we took ownership of our
765 // A copy of the vertex pointer to be removed so we can't delete it out from under ourselves (occurs when
788 // Yes, the vertex is still useful as a sample. Track as recycled so they are reused as samples in the
797 // No, the vertex is not useful anymore. Mark as pruned. This functions as a lock to prevent accessing
806 std::pair<unsigned int, unsigned int> BITstar::ImplicitGraph::pruneVertex(const VertexPtr &vertex)
812 // The use count of the passed shared pointer. Used in debug mode to assert that we took ownership of our
816 // A copy of the sample pointer to be removed so we can't delete it out from under ourselves (occurs when
882 void BITstar::ImplicitGraph::removeEdgeBetweenVertexAndParent(const VertexPtr &child, bool cascadeCostUpdates)
887 throw ompl::Exception("An orphaned vertex has been passed for disconnection. Something went wrong.");
891 // Check if my parent has already been pruned. This can occur if we're cascading child disconnections.
911 // Check if we need to generate new samples inorder to completely cover the neighbourhood of the vertex
920 // Calculate the sample density given the number of samples per batch and the measure of this batch
922 double sampleDensity = static_cast<double>(numNewSamplesInCurrentBatch_) / approximationMeasure_;
931 // And the fractional part represents the probability of one more sample. I like being pedantic.
1020 // The end point of the vector to consider. We will delete by swapping elements to the end, moving this
1030 // It has, remove the start vertex DO NOT consider it as a sample. It is marked as a root node,
1031 // so having it as a sample would cause all kinds of problems, also it shouldn't be possible for
1032 // it to ever be useful as a sample anyway, unless there is a very weird cost function in play.
1089 // The end point of the vector to consider. We will delete by swapping elements to the end, moving this
1167 // We don't need to update our approximate solution (if we're providing one) as we will only prune once a
1237 // Prune the vertex if it could cannot part of a better solution in the current graph. Greater-than just in
1240 return costHelpPtr_->isCostWorseThan(costHelpPtr_->currentHeuristicVertex(vertex), solutionCost_);
1257 return costHelpPtr_->isCostWorseThanOrEquivalentTo(costHelpPtr_->lowerBoundHeuristicVertex(sample),
1277 ompl::base::Cost BITstar::ImplicitGraph::calculateNeighbourhoodCost(const VertexConstPtr &vertex) const
1288 // We are, return the maximum heuristic cost that represents a sample in the neighbourhood of the given
1290 // There is no point generating samples worse the best solution (maxCost_) even if those samples are in
1323 // If this is the first batch, we will be calculating the connection limits from only the starts and goals
1324 // for an RGG with m samples. That will be a complex graph. In this case, let us calculate the connection
1325 // limits considering the samples about to be generated. Doing so is equivalent to setting an upper-bound on
1439 BITstar::VertexPtrVector::const_iterator BITstar::ImplicitGraph::startVerticesBeginConst() const
1449 BITstar::VertexPtrVector::const_iterator BITstar::ImplicitGraph::goalVerticesBeginConst() const
1548 OMPL_WARN("%s (ImplicitGraph): The k-nearest variant of BIT* cannot be used with JIT sampling, "
1576 OMPL_WARN("%s (ImplicitGraph): Just-in-time sampling cannot be used with the k-nearest variant of "
1588 OMPL_INFORM("%s (ImplicitGraph): Just-in-time sampling is currently only implemented for problems "
1661 void BITstar::ImplicitGraph::setAverageNumOfAllowedFailedAttemptsWhenSampling(std::size_t number)
1674 // Check if the problem is already setup, if so, the NN structs have data in them and you can't really
1678 OMPL_WARN("%s (ImplicitGraph): The nearest neighbour datastructures cannot be changed once the problem "
void nearestSamples(const VertexPtr &vertex, VertexPtrVector *neighbourSamples)
Get the nearest unconnected samples using the appropriate "near" definition (i.e.,...
Definition: ImplicitGraph.cpp:285
Random number generation. An instance of this class cannot be used by multiple threads at once (membe...
Definition: RandomNumbers.h:89
PlannerTerminationCondition plannerAlwaysTerminatingCondition()
Simple termination condition that always returns true. The termination condition will always be met.
Definition: PlannerTerminationCondition.cpp:190
void setAverageNumOfAllowedFailedAttemptsWhenSampling(std::size_t number)
Set the average number of allowed failed attempts when sampling.
Definition: ImplicitGraph.cpp:1661
bool haveMoreStartStates() const
Check if there are more potential start states.
Definition: Planner.cpp:339
void addToSamples(const VertexPtr &sample)
Add an unconnected sample.
Definition: ImplicitGraph.cpp:651
void setDropSamplesOnPrune(bool dropSamples)
Set whether unconnected samples are dropped on pruning.
Definition: ImplicitGraph.cpp:1601
unsigned int numStatesGenerated() const
The total number of states generated.
Definition: ImplicitGraph.cpp:1702
void setRewireFactor(double rewireFactor)
Set the rewiring scale factor, s, such that r_rrg = s \times r_rrg*.
Definition: ImplicitGraph.cpp:1525
bool hasAStart() const
Gets whether the graph contains a start or not.
Definition: ImplicitGraph.cpp:1429
void setTrackApproximateSolutions(bool findApproximate)
Set whether to track approximate solutions during the search.
Definition: ImplicitGraph.cpp:1627
A shared pointer wrapper for ompl::base::SpaceInformation.
Helper class to extract valid start & goal states. Usually used internally by planners.
Definition: Planner.h:141
VertexPtrVector::const_iterator goalVerticesBeginConst() const
Returns a const-iterator to the front of the goal-vertex vector.
Definition: ImplicitGraph.cpp:1449
VertexPtrVector::const_iterator goalVerticesEndConst() const
Returns a const-iterator to the end of the goal-vertex vector.
Definition: ImplicitGraph.cpp:1454
std::shared_ptr< const Vertex > VertexConstPtr
A shared pointer to a const vertex.
Definition: BITstar.h:215
unsigned int numVertices() const
The number of vertices in the search tree.
Definition: ImplicitGraph.cpp:1694
A queue of edges, sorted according to a sort key.
Definition: SearchQueue.h:128
bool hasAGoal() const
Gets whether the graph contains a goal or not.
Definition: ImplicitGraph.cpp:1434
void setUseKNearest(bool useKNearest)
Enable a k-nearest search for instead of an r-disc search.
Definition: ImplicitGraph.cpp:1543
void getGraphAsPlannerData(ompl::base::PlannerData &data) const
Adds the graph to the given PlannerData struct.
Definition: ImplicitGraph.cpp:305
std::function< std::string()> NameFunc
A utility functor for ImplicitGraph and SearchQueue.
Definition: BITstar.h:245
std::pair< VertexConstPtr, VertexConstPtr > VertexConstPtrPair
A pair of const vertices, i.e., an edge.
Definition: BITstar.h:233
void registerAsVertex(const VertexPtr &vertex)
Add a vertex to the tree, optionally moving it from the set of unconnected samples.
Definition: ImplicitGraph.cpp:733
bool getUseKNearest() const
Get whether a k-nearest search is being used.
Definition: ImplicitGraph.cpp:1566
void log(const char *file, int line, LogLevel level, const char *m,...)
Root level logging function. This should not be invoked directly, but rather used via a logging macro...
Definition: Console.cpp:120
VertexPtrVector getCopyOfSamples() const
Get a copy of all samples.
Definition: ImplicitGraph.cpp:1518
Definition of a cost value. Can represent the cost of a motion or the cost of a state.
Definition: Cost.h:111
void setPruning(bool usePruning)
Set whether samples that are provably not beneficial should be kept around.
Definition: ImplicitGraph.cpp:1617
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,...
Definition: ImplicitGraph.cpp:91
VertexPtrVector::const_iterator startVerticesEndConst() const
Returns a const-iterator to the end of the start-vertex vector.
Definition: ImplicitGraph.cpp:1444
unsigned int numVerticesDisconnected() const
The number of tree vertices disconnected.
Definition: ImplicitGraph.cpp:1717
A helper class to handle the various heuristic functions in one place.
Definition: CostHelper.h:133
bool canSampleBePruned(const VertexPtr &sample) const
Returns whether the sample can be pruned, i.e., whether it could ever provide a better solution....
Definition: ImplicitGraph.cpp:1243
std::pair< unsigned int, unsigned int > pruneVertex(const VertexPtr &vertex)
Remove a vertex and mark as pruned.
Definition: ImplicitGraph.cpp:806
Object containing planner generated vertex and edge data. It is assumed that all vertices are unique,...
Definition: PlannerData.h:238
double unitNBallMeasure(unsigned int N)
The Lebesgue measure (i.e., "volume") of an n-dimensional ball with a unit radius.
Definition: GeometricEquations.cpp:55
double getInformedMeasure(const ompl::base::Cost &cost) const
Query the underlying state sampler for the informed measure of the problem.
Definition: ImplicitGraph.cpp:1469
Encapsulate a termination condition for a motion planner. Planners will call operator() to decide whe...
Definition: PlannerTerminationCondition.h:127
const State * nextStart()
Return the next valid start state or nullptr if no more valid start states are available.
Definition: Planner.cpp:228
void removeFromSamples(const VertexPtr &sample)
Remove a sample from the sample set.
Definition: ImplicitGraph.cpp:677
double distance(const VertexConstPtr &a, const VertexConstPtr &b) const
Computes the distance between two states.
Definition: ImplicitGraph.cpp:259
unsigned int numVerticesConnected() const
The total number of vertices added to the graph.
Definition: ImplicitGraph.cpp:1707
std::vector< VertexPtr > VertexPtrVector
A vector of shared pointers to vertices.
Definition: BITstar.h:221
const State * nextGoal(const PlannerTerminationCondition &ptc)
Return the next valid goal state or nullptr if no more valid goal states are available....
Definition: Planner.cpp:265
Abstract representation of a container that can perform nearest neighbors queries.
Definition: NearestNeighbors.h:79
VertexConstPtr closestVertexToGoal() const
IF BEING TRACKED, returns the closest vertex in the tree to the goal.
Definition: ImplicitGraph.cpp:1474
void removeEdgeBetweenVertexAndParent(const VertexPtr &child, bool cascadeCostUpdates)
Disconnect a vertex from its parent by removing the edges stored in itself, and its parents....
Definition: ImplicitGraph.cpp:882
A shared pointer wrapper for ompl::base::ProblemDefinition.
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 a...
Definition: ImplicitGraph.cpp:365
unsigned int numStateCollisionChecks() const
The number of state collision checks.
Definition: ImplicitGraph.cpp:1727
std::size_t getAverageNumOfAllowedFailedAttemptsWhenSampling() const
Get the average number of allowed failed attempts when sampling.
Definition: ImplicitGraph.cpp:1666
unsigned int numFreeStatesPruned() const
The number of states pruned.
Definition: ImplicitGraph.cpp:1712
unsigned int numNearestLookups() const
The number of nearest neighbour calls.
Definition: ImplicitGraph.cpp:1722
bool hasInformedMeasure() const
Query whether the underlying state sampler can provide an informed measure.
Definition: ImplicitGraph.cpp:1464
void recycleSample(const VertexPtr &sample)
Insert a sample into the set for recycled samples.
Definition: ImplicitGraph.cpp:726
unsigned int addVertex(const PlannerDataVertex &st)
Adds the given vertex to the graph data. The vertex index is returned. Duplicates are not added....
Definition: PlannerData.cpp:391
void pruneSample(const VertexPtr &sample)
Remove an unconnected sample.
Definition: ImplicitGraph.cpp:685
bool getJustInTimeSampling() const
Get whether we're using just-in-time sampling.
Definition: ImplicitGraph.cpp:1596
double smallestDistanceToGoal() const
IF BEING TRACKED, returns the how close vertices in the tree are to the goal.
Definition: ImplicitGraph.cpp:1485
bool getTrackApproximateSolutions() const
Get whether approximate solutions are tracked during the search.
Definition: ImplicitGraph.cpp:1656
ompl::base::Cost minCost() const
Get the minimum cost solution possible for this problem.
Definition: ImplicitGraph.cpp:1459
bool getDropSamplesOnPrune() const
Get whether unconnected samples are dropped on pruning.
Definition: ImplicitGraph.cpp:1622
unsigned int addStartVertex(const PlannerDataVertex &v)
Adds the given vertex to the graph data, and marks it as a start vertex. The vertex index is returned...
Definition: PlannerData.cpp:413
bool haveMoreGoalStates() const
Check if there are more potential goal states.
Definition: Planner.cpp:346
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...
Definition: ImplicitGraph.cpp:755
void setNearestNeighbors()
Set a different nearest neighbours datastructure.
Definition: ImplicitGraph.cpp:1672
unsigned int getConnectivityK() const
Get the k of this k-nearest RGG.
Definition: ImplicitGraph.cpp:1496
bool canVertexBeDisconnected(const VertexPtr &vertex) const
Returns whether the vertex can be pruned, i.e., whether it could provide a better solution given....
Definition: ImplicitGraph.cpp:1231
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...
Definition: ImplicitGraph.cpp:628
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...
Definition: ImplicitGraph.cpp:350
VertexPtrVector::const_iterator startVerticesBeginConst() const
Returns a const-iterator to the front of the start-vertex vector.
Definition: ImplicitGraph.cpp:1439
virtual bool addEdge(unsigned int v1, unsigned int v2, const PlannerDataEdge &edge=PlannerDataEdge(), Cost weight=Cost(1.0))
Adds a directed edge between the given vertex indexes. An optional edge structure and weight can be s...
Definition: PlannerData.cpp:432
void setJustInTimeSampling(bool useJit)
Definition: ImplicitGraph.cpp:1571
Base class for a vertex in the PlannerData structure. All derived classes must implement the clone an...
Definition: PlannerData.h:122
Main namespace. Contains everything in this library.
Definition: MultiLevelPlanarManipulatorDemo.cpp:65
virtual void setDistanceFunction(const DistanceFunction &distFun)
Set the distance function to use.
Definition: NearestNeighbors.h:122
void addNewSamples(const unsigned int &numSamples)
Increase the resolution of the graph-based approximation of the continuous search domain by adding a ...
Definition: ImplicitGraph.cpp:599