Loading...
Searching...
No Matches
EITstar.h
1/*********************************************************************
2 * Software License Agreement (BSD License)
3 *
4 * Copyright (c) 2019, University of Oxford
5 * All rights reserved.
6 *
7 * Redistribution and use in source and binary forms, with or without
8 * modification, are permitted provided that the following conditions
9 * are met:
10 *
11 * * Redistributions of source code must retain the above copyright
12 * notice, this list of conditions and the following disclaimer.
13 * * Redistributions in binary form must reproduce the above
14 * copyright notice, this list of conditions and the following
15 * disclaimer in the documentation and/or other materials provided
16 * with the distribution.
17 * * Neither the name of the University of Toronto nor the names of its
18 * contributors may be used to endorse or promote products derived
19 * from this software without specific prior written permission.
20 *
21 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22 * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23 * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24 * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25 * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26 * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27 * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28 * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30 * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31 * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32 * POSSIBILITY OF SUCH DAMAGE.
33 *********************************************************************/
34
35// Authors: Marlin Strub
36
37#ifndef OMPL_GEOMETRIC_PLANNERS_INFORMEDTREES_EITSTAR_
38#define OMPL_GEOMETRIC_PLANNERS_INFORMEDTREES_EITSTAR_
39
40#include <memory>
41
42#include "ompl/base/Cost.h"
43#include "ompl/base/Planner.h"
44#include "ompl/base/SpaceInformation.h"
45
46#include "ompl/geometric/PathGeometric.h"
47#include "ompl/geometric/planners/informedtrees/eitstar/Direction.h"
48#include "ompl/geometric/planners/informedtrees/eitstar/RandomGeometricGraph.h"
49#include "ompl/geometric/planners/informedtrees/eitstar/ForwardQueue.h"
50#include "ompl/geometric/planners/informedtrees/eitstar/ReverseQueue.h"
51
52namespace ompl
53{
54 namespace geometric
55 {
89
92 {
93 public:
95 explicit EITstar(const std::shared_ptr<ompl::base::SpaceInformation> &spaceInfo);
96
98 ~EITstar();
99
101 void setup() override;
102
105 solve(const ompl::base::PlannerTerminationCondition &terminationCondition) override;
106
109 void clear() override;
110
113 void clearQuery() override;
114
117
119 void setBatchSize(unsigned int numSamples);
120
122 unsigned int getBatchSize() const;
123
125 void setInitialNumberOfSparseCollisionChecks(std::size_t numChecks);
126
128 void setRadiusFactor(double factor);
129
131 double getRadiusFactor() const;
132
134 void setSuboptimalityFactor(double factor);
135
137 void enablePruning(bool prune);
138
140 bool isPruningEnabled() const;
141
143 void trackApproximateSolutions(bool track);
144
147
149 void setUseKNearest(bool useKNearest);
150
152 bool getUseKNearest() const;
153
155 void setMaxNumberOfGoals(unsigned int numberOfGoals);
156
158 unsigned int getMaxNumberOfGoals() const;
159
161 bool isForwardQueueEmpty() const;
162
164 std::vector<eitstar::Edge> getForwardQueue() const;
165
167 unsigned int getForwardEffort() const;
168
170 bool isReverseQueueEmpty() const;
171
173 std::vector<eitstar::Edge> getReverseQueue() const;
174
176 std::vector<eitstar::Edge> getReverseTree() const;
177
180
183
185 bool isStart(const std::shared_ptr<eitstar::State> &state) const;
186
188 bool isGoal(const std::shared_ptr<eitstar::State> &state) const;
189
191 void getPlannerData(base::PlannerData &data) const override;
192
193 protected:
194 // ---
195 // The settings that turn EIT* into EIRM*.
196 // ---
197
199 void enableMultiquery(bool multiquery);
200
202 bool isMultiqueryEnabled() const;
203
205 void setStartGoalPruningThreshold(unsigned int threshold);
206
208 unsigned int getStartGoalPruningThreshold() const;
209
210 private:
214 void iterate(const ompl::base::PlannerTerminationCondition &terminationCondition);
215
217 void iterateReverseSearch();
218
220 void iterateForwardSearch();
221
224 void improveApproximation(const ompl::base::PlannerTerminationCondition &terminationCondition);
225
231 bool continueSolving(const ompl::base::PlannerTerminationCondition &terminationCondition) const;
232
235 bool continueReverseSearch() const;
236
239 bool continueForwardSearch() const;
240
242 void restartReverseSearch();
243
245 void updateExactSolution();
246
249 void updateApproximateSolution();
250
255
259
263 ensureStartAndGoalStates(const ompl::base::PlannerTerminationCondition &terminationCondition);
264
266 std::shared_ptr<ompl::geometric::PathGeometric>
267 getPathToState(const std::shared_ptr<eitstar::State> &state) const;
268
270 void updateExactSolution(const std::shared_ptr<eitstar::State> &goalState);
271
274 void updateApproximateSolution(const std::shared_ptr<eitstar::State> &state);
275
277 void updateCurrentCostToCome(const std::shared_ptr<eitstar::State> &state);
278
280 ompl::base::Cost computeCostToGoToGoal(const std::shared_ptr<eitstar::State> &state) const;
281
283 void informAboutNewSolution() const;
284
286 void informAboutPlannerStatus(ompl::base::PlannerStatus::StatusType status) const;
287
289 unsigned int countNumVerticesInForwardTree() const;
290
292 unsigned int countNumVerticesInReverseTree() const;
293
295 std::vector<eitstar::Edge> expand(const std::shared_ptr<eitstar::State> &state) const;
296
298 std::vector<eitstar::Edge> expandUnlessGoal(const std::shared_ptr<eitstar::State> &state) const;
299
301 bool isClosed(const std::shared_ptr<eitstar::Vertex> &vertex) const;
302
304 bool isInForwardTree(const eitstar::Edge &edge) const;
305
307 bool isInReverseTree(const eitstar::Edge &edge) const;
308
310 bool doesImproveReversePath(const eitstar::Edge &edge) const;
311
313 bool doesImproveReverseTree(const eitstar::Edge &edge, const ompl::base::Cost &edgeCost) const;
314
316 bool couldImproveForwardPath(const eitstar::Edge &edge) const;
317
319 bool couldImproveForwardTree(const eitstar::Edge &edge) const;
320
322 bool doesImproveForwardPath(const eitstar::Edge &edge, const ompl::base::Cost &edgeCost) const;
323
325 bool doesImproveForwardTree(const eitstar::Edge &edge, const ompl::base::Cost &edgeCost) const;
326
328 ompl::base::Cost estimateCostToTarget(const eitstar::Edge &edge) const;
329
331 unsigned int estimateEffortToTarget(const eitstar::Edge &edge) const;
332
334 bool isValid(const eitstar::Edge &edge) const;
335
337 bool couldBeValid(const eitstar::Edge &edge) const;
338
341 bool isValidAtResolution(const eitstar::Edge &edge, std::size_t numChecks) const;
342
344 bool isBetter(const ompl::base::Cost &lhs, const ompl::base::Cost &rhs) const;
345
347 ompl::base::Cost combine(const ompl::base::Cost &lhs, const ompl::base::Cost &rhs) const;
348
350 template <typename... Costs>
351 ompl::base::Cost combine(const ompl::base::Cost &cost, const Costs &...costs) const
352 {
353 return combine(cost, combine(costs...));
354 }
355
357 void expandStartVerticesIntoForwardQueue();
358
360 void expandGoalVerticesIntoReverseQueue();
361
364
366 unsigned int batchSize_{100u};
367
369 double suboptimalityFactor_{std::numeric_limits<double>::infinity()};
370
372 std::size_t initialNumSparseCollisionChecks_{1u};
373
376 std::size_t numSparseCollisionChecksCurrentLevel_{1u};
377
380 std::size_t numSparseCollisionChecksPreviousLevel_{0u};
381
383 bool isMultiqueryEnabled_{false};
384
386 bool isPruningEnabled_{true};
387
389 bool trackApproximateSolutions_{true};
390
392 ompl::base::State *detectionState_;
393
395 std::vector<std::shared_ptr<eitstar::Vertex>> startVertices_;
396
398 std::vector<std::shared_ptr<eitstar::Vertex>> goalVertices_;
399
401 std::unique_ptr<eitstar::ForwardQueue> forwardQueue_;
402
404 std::unique_ptr<eitstar::ReverseQueue> reverseQueue_;
405
407 std::size_t iteration_{0u};
408
410 std::size_t reverseSearchTag_{1u};
411
413 std::size_t startExpansionGraphTag_{0u};
414
416 std::shared_ptr<ompl::base::ProblemDefinition> &problem_ = ompl::base::Planner::pdef_;
417
419 std::shared_ptr<ompl::base::SpaceInformation> &spaceInfo_ = ompl::base::Planner::si_;
420
422 std::shared_ptr<ompl::base::StateSpace> space_;
423
425 std::shared_ptr<ompl::base::OptimizationObjective> objective_;
426
428 std::shared_ptr<ompl::base::MotionValidator> motionValidator_;
429
431 ompl::base::Cost solutionCost_{std::numeric_limits<double>::signaling_NaN()};
432
434 ompl::base::Cost reverseCost_{std::numeric_limits<double>::signaling_NaN()};
435
437 ompl::base::Cost approximateSolutionCost_{std::numeric_limits<double>::signaling_NaN()};
438
440 ompl::base::Cost approximateSolutionCostToGoal_{std::numeric_limits<double>::signaling_NaN()};
441
443 mutable unsigned int numProcessedEdges_{0u};
444
446 mutable unsigned int numCollisionCheckedEdges_{0u};
447 };
448
449 } // namespace geometric
450
451} // namespace ompl
452
453#endif // OMPL_GEOMETRIC_PLANNERS_INFORMEDTREES_EITSTAR_
Definition of a cost value. Can represent the cost of a motion or the cost of a state.
Definition Cost.h:48
Object containing planner generated vertex and edge data. It is assumed that all vertices are unique,...
Encapsulate a termination condition for a motion planner. Planners will call operator() to decide whe...
Base class for a planner.
Definition Planner.h:216
ProblemDefinitionPtr pdef_
The user set problem definition.
Definition Planner.h:404
SpaceInformationPtr si_
The space information for which planning is done.
Definition Planner.h:401
bool areApproximateSolutionsTracked() const
Returns whether approximate solutions are tracked or not.
Definition EITstar.cpp:352
bool isReverseQueueEmpty() const
Returns true if the reverse queue is empty.
Definition EITstar.cpp:383
unsigned int getStartGoalPruningThreshold() const
Get threshold at which we prune starts/goals.
Definition EITstar.cpp:332
void setStartGoalPruningThreshold(unsigned int threshold)
Set start/goal pruning threshold.
Definition EITstar.cpp:327
ompl::base::Cost bestCost() const
Returns the cost of the current best solution.
Definition EITstar.cpp:279
double getRadiusFactor() const
Returns the radius factor.
Definition EITstar.cpp:306
bool isMultiqueryEnabled() const
Get wheter multiquery is enabled or not.
Definition EITstar.cpp:322
void clear() override
Clears all internal planner structures but retains settings. Subsequent calls to solve() will start f...
Definition EITstar.cpp:213
void enableMultiquery(bool multiquery)
Set wheter multiquery is enabled or not.
Definition EITstar.cpp:316
void setBatchSize(unsigned int numSamples)
Sets the number of samples per batch.
Definition EITstar.cpp:284
bool isGoal(const std::shared_ptr< eitstar::State > &state) const
Checks whether the state is a goal state.
void setup() override
Setup the parts of the planner that rely on the problem definition being set.
Definition EITstar.cpp:96
void setRadiusFactor(double factor)
Sets the radius factor.
Definition EITstar.cpp:301
~EITstar()
Destructs this instance of EIT*.
Definition EITstar.cpp:91
void setMaxNumberOfGoals(unsigned int numberOfGoals)
Set the maximum number of goals EIT* will sample from sampleable goal regions.
Definition EITstar.cpp:367
eitstar::Edge getNextReverseEdge() const
Returns the next edge in the reverse queue.
Definition EITstar.cpp:439
void trackApproximateSolutions(bool track)
Sets whether to track approximate solutions or not.
Definition EITstar.cpp:347
std::vector< eitstar::Edge > getReverseQueue() const
Returns a copy of the reverse queue.
Definition EITstar.cpp:394
std::vector< eitstar::Edge > getForwardQueue() const
Returns a copy of the forward queue.
Definition EITstar.cpp:389
void setInitialNumberOfSparseCollisionChecks(std::size_t numChecks)
Sets the initial number of collision checks on the reverse search.
Definition EITstar.cpp:294
bool isStart(const std::shared_ptr< eitstar::State > &state) const
Checks whether the state is a start state.
eitstar::Edge getNextForwardEdge() const
Returns the next edge in the forward queue.
Definition EITstar.cpp:429
unsigned int getForwardEffort() const
Returns the effort of the edge at the top of the forward queue.
Definition EITstar.cpp:848
ompl::base::PlannerStatus solve(const ompl::base::PlannerTerminationCondition &terminationCondition) override
Solves the provided motion planning problem, respecting the given termination condition.
Definition EITstar.cpp:173
void setSuboptimalityFactor(double factor)
Sets the (initial) suboptimality factor.
Definition EITstar.cpp:311
void enablePruning(bool prune)
Set whether pruning is enabled or not.
Definition EITstar.cpp:337
EITstar(const std::shared_ptr< ompl::base::SpaceInformation > &spaceInfo)
Constructs an instance of EIT* using the provided space information.
Definition EITstar.cpp:52
void getPlannerData(base::PlannerData &data) const override
Returns the planner data.
Definition EITstar.cpp:449
bool isForwardQueueEmpty() const
Returns true if the forward queue is empty.
Definition EITstar.cpp:377
unsigned int getMaxNumberOfGoals() const
Returns the maximum number of goals EIT* will sample from sampleable goal regions.
Definition EITstar.cpp:372
std::vector< eitstar::Edge > getReverseTree() const
Returns copies of the edges in the reverse tree.
Definition EITstar.cpp:399
void setUseKNearest(bool useKNearest)
Set whether to use a k-nearest RGG connection model. If false, EIT* uses an r-disc model.
Definition EITstar.cpp:357
unsigned int getBatchSize() const
Returns the number of samples per batch.
Definition EITstar.cpp:289
bool getUseKNearest() const
Returns whether to use a k-nearest RGG connection model. If false, EIT* uses an r-disc model.
Definition EITstar.cpp:362
void clearQuery() override
Clears all query-specific information, such as start and goal states and search trees....
Definition EITstar.cpp:248
bool isPruningEnabled() const
Returns whether pruning is enabled or not.
Definition EITstar.cpp:342
This namespace contains code that is specific to planning under geometric constraints.
Main namespace. Contains everything in this library.
A class to store the exit status of Planner::solve().
StatusType
The possible values of the status returned by a planner.
A struct for basic edge data.
Definition Edge.h:57