BiTRRT.h
1 /*********************************************************************
2 * Software License Agreement (BSD License)
3 *
4 * Copyright (c) 2015, Rice University
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 Rice University 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 /* Author: Ryan Luna */
36 
37 #ifndef OMPL_GEOMETRIC_PLANNERS_RRT_BITRRT_
38 #define OMPL_GEOMETRIC_PLANNERS_RRT_BITRRT_
39 
40 #include <cmath>
41 #include "ompl/geometric/planners/PlannerIncludes.h"
42 #include "ompl/datastructures/NearestNeighbors.h"
43 #include "ompl/base/OptimizationObjective.h"
44 
45 namespace ompl
46 {
47  namespace geometric
48  {
67 
69  class BiTRRT : public base::Planner
70  {
71  public:
74  ~BiTRRT() override;
75  void clear() override;
76  void setup() override;
77  void getPlannerData(base::PlannerData &data) const override;
79 
83  void setRange(double distance)
84  {
85  maxDistance_ = distance;
86  }
87 
89  double getRange() const
90  {
91  return maxDistance_;
92  }
93 
99  void setTempChangeFactor(double factor)
100  {
101  tempChangeFactor_ = exp(factor);
102  }
103 
106  double getTempChangeFactor() const
107  {
108  return log(tempChangeFactor_);
109  }
110 
114  void setCostThreshold(double maxCost)
115  {
116  costThreshold_ = base::Cost(maxCost);
117  }
118 
122  double getCostThreshold() const
123  {
124  return costThreshold_.value();
125  }
126 
129  void setInitTemperature(double initTemperature)
130  {
131  initTemperature_ = initTemperature;
132  }
133 
135  double getInitTemperature() const
136  {
137  return initTemperature_;
138  }
139 
142  void setFrontierThreshold(double frontierThreshold)
143  {
144  frontierThreshold_ = frontierThreshold;
145  }
146 
149  double getFrontierThreshold() const
150  {
151  return frontierThreshold_;
152  }
153 
157  void setFrontierNodeRatio(double frontierNodeRatio)
158  {
159  frontierNodeRatio_ = frontierNodeRatio;
160  }
161 
164  double getFrontierNodeRatio() const
165  {
166  return frontierNodeRatio_;
167  }
168 
170  template <template <typename T> class NN>
172  {
173  if ((tStart_ && tStart_->size() != 0) || (tGoal_ && tGoal_->size() != 0))
174  OMPL_WARN("Calling setNearestNeighbors will clear all states.");
175  clear();
176  tStart_ = std::make_shared<NN<Motion *>>();
177  tGoal_ = std::make_shared<NN<Motion *>>();
178  setup();
179  }
180 
181  protected:
183  class Motion
184  {
185  public:
187  Motion() = default;
188 
190  Motion(const base::SpaceInformationPtr &si) : state(si->allocState())
191  {
192  }
193 
194  ~Motion() = default;
195 
197  base::State *state{nullptr};
198 
200  Motion *parent{nullptr};
201 
204 
207  const base::State *root{nullptr};
208  };
209 
211  void freeMemory();
212 
215  typedef std::shared_ptr<NearestNeighbors<Motion *>> TreeData;
216 
219  Motion *addMotion(const base::State *state, TreeData &tree, Motion *parent = nullptr);
220 
225  bool transitionTest(const base::Cost &motionCost);
226 
229  bool minExpansionControl(double dist);
230 
233  {
240  };
241 
244  GrowResult extendTree(Motion *toMotion, TreeData &tree, Motion *&result);
245 
248  GrowResult extendTree(Motion *nearest, TreeData &tree, Motion *toMotion, Motion *&result);
249 
252  bool connectTrees(Motion *nmotion, TreeData &tree, Motion *xmotion);
253 
255  double distanceFunction(const Motion *a, const Motion *b) const
256  {
257  return si_->distance(a->state, b->state);
258  }
259 
261  double maxDistance_{0.};
262 
266 
269 
272 
274  base::Cost costThreshold_{std::numeric_limits<double>::infinity()};
275 
277  double initTemperature_{100.};
278 
281  double frontierThreshold_{0.};
282 
284  double frontierNodeRatio_{.1};
285 
287  double temp_;
288 
291 
294 
298 
301  std::pair<Motion *, Motion *> connectionPoint_{nullptr, nullptr};
302 
304  TreeData tStart_;
305 
307  TreeData tGoal_;
308 
311  };
312  }
313 }
314 
315 #endif
Object containing planner generated vertex and edge data. It is assumed that all vertices are unique...
Definition: PlannerData.h:174
base::PlannerStatus solve(const base::PlannerTerminationCondition &ptc) override
Function that can solve the motion planning problem. This function can be called multiple times on th...
Definition: BiTRRT.cpp:331
Motion * addMotion(const base::State *state, TreeData &tree, Motion *parent=nullptr)
Add a state to the given tree. The motion created is returned.
Definition: BiTRRT.cpp:166
void setup() override
Perform extra configuration steps, if needed. This call will also issue a call to ompl::base::SpaceIn...
Definition: BiTRRT.cpp:115
double frontierThreshold_
The distance between an existing state and a new state that qualifies it as a frontier state...
Definition: BiTRRT.h:281
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
base::State * state
The state contained by the motion.
Definition: BiTRRT.h:197
bool minExpansionControl(double dist)
Use frontier node ratio to filter nodes that do not add new information to the search tree...
Definition: BiTRRT.cpp:212
bool transitionTest(const base::Cost &motionCost)
Transition test that filters transitions based on the motion cost. If the motion cost is near or belo...
Definition: BiTRRT.cpp:185
GrowResult extendTree(Motion *toMotion, TreeData &tree, Motion *&result)
Extend tree toward the state in rmotion. Store the result of the extension, if any, in result.
Definition: BiTRRT.cpp:262
base::Cost bestCost_
The most desirable (e.g., minimum) cost value in the search tree.
Definition: BiTRRT.h:268
double getFrontierThreshold() const
Get the distance between a new state and the nearest neighbor that qualifies a state as being a front...
Definition: BiTRRT.h:149
Encapsulate a termination condition for a motion planner. Planners will call operator() to decide whe...
Motion * parent
The parent motion in the exploration tree.
Definition: BiTRRT.h:200
double nonfrontierCount_
A count of the number of non-frontier nodes in the trees.
Definition: BiTRRT.h:290
TreeData tStart_
The start tree.
Definition: BiTRRT.h:304
BiTRRT(const base::SpaceInformationPtr &si)
Constructor.
Definition: BiTRRT.cpp:45
std::shared_ptr< NearestNeighbors< Motion * > > TreeData
The nearest-neighbors data structure that contains the entire the tree of motions generated during pl...
Definition: BiTRRT.h:215
void getPlannerData(base::PlannerData &data) const override
Get information about the current run of the motion planner. Repeated calls to this function will upd...
Definition: BiTRRT.cpp:464
double initTemperature_
The temperature that planning begins at.
Definition: BiTRRT.h:277
double connectionRange_
The range at which the algorithm will attempt to connect the two trees.
Definition: BiTRRT.h:297
void setFrontierNodeRatio(double frontierNodeRatio)
Set the ratio between adding non-frontier nodes to frontier nodes. For example: .1 is one non-frontie...
Definition: BiTRRT.h:157
base::Cost worstCost_
The least desirable (e.g., maximum) cost value in the search tree.
Definition: BiTRRT.h:271
double tempChangeFactor_
The factor by which the temperature is increased after a failed transition test.
Definition: BiTRRT.h:265
double maxDistance_
The maximum length of a motion to be added to a tree.
Definition: BiTRRT.h:261
std::pair< Motion *, Motion * > connectionPoint_
The most recent connection point for the two trees. Used for PlannerData computation.
Definition: BiTRRT.h:301
Main namespace. Contains everything in this library.
Definition: AppBase.h:21
double getInitTemperature() const
Get the initial temperature at the start of planning.
Definition: BiTRRT.h:135
Motion(const base::SpaceInformationPtr &si)
Constructor that allocates memory for the state.
Definition: BiTRRT.h:190
void setNearestNeighbors()
Set a different nearest neighbors datastructure.
Definition: BiTRRT.h:171
void freeMemory()
Free all memory allocated during planning.
Definition: BiTRRT.cpp:70
Base class for a planner.
Definition: Planner.h:223
double getRange() const
Get the range the planner is using.
Definition: BiTRRT.h:89
double getFrontierNodeRatio() const
Get the ratio between adding non-frontier nodes to frontier nodes.
Definition: BiTRRT.h:164
GrowResult
The result of a call to extendTree.
Definition: BiTRRT.h:232
const base::State * root
Pointer to the root of the tree this motion is contained in.
Definition: BiTRRT.h:207
void setTempChangeFactor(double factor)
Set the factor by which the temperature is increased after a failed transition test. This value should be in the range (0, 1], typically close to zero (default is 0.1). This value is an exponential (e^factor) that is multiplied with the current temperature.
Definition: BiTRRT.h:99
TreeData tGoal_
The goal tree.
Definition: BiTRRT.h:307
A class to store the exit status of Planner::solve()
Definition: PlannerStatus.h:48
void setInitTemperature(double initTemperature)
Set the initial temperature at the start of planning. Should be high to allow for initial exploration...
Definition: BiTRRT.h:129
Progress was made toward extension.
Definition: BiTRRT.h:237
A shared pointer wrapper for ompl::base::SpaceInformation.
double getTempChangeFactor() const
Get the factor by which the temperature is increased after a failed transition.
Definition: BiTRRT.h:106
double frontierCount_
A count of the number of frontier nodes in the trees.
Definition: BiTRRT.h:293
Definition of an abstract state.
Definition: State.h:49
double distanceFunction(const Motion *a, const Motion *b) const
Compute distance between motions (actually distance between contained states)
Definition: BiTRRT.h:255
ompl::base::OptimizationObjectivePtr opt_
The objective (cost function) being optimized.
Definition: BiTRRT.h:310
#define OMPL_WARN(fmt,...)
Log a formatted warning string.
Definition: Console.h:66
*double getCostThreshold() const
Get the cost threshold (default is infinity). Any motion cost that is not better than this cost (acco...
Definition: BiTRRT.h:122
void setFrontierThreshold(double frontierThreshold)
Set the distance between a new state and the nearest neighbor that qualifies a state as being a front...
Definition: BiTRRT.h:142
Motion()=default
Default constructor.
No extension was possible.
Definition: BiTRRT.h:235
Representation of a motion in the search tree.
Definition: BiTRRT.h:183
A shared pointer wrapper for ompl::base::OptimizationObjective.
double frontierNodeRatio_
The target ratio of non-frontier nodes to frontier nodes.
Definition: BiTRRT.h:284
void setRange(double distance)
Set the maximum possible length of any one motion in the search tree. Very short/long motions may inh...
Definition: BiTRRT.h:83
double value() const
The value of the cost.
Definition: Cost.h:56
base::Cost costThreshold_
All motion costs must be better than this cost (default is infinity)
Definition: BiTRRT.h:274
SpaceInformationPtr si_
The space information for which planning is done.
Definition: Planner.h:406
void setCostThreshold(double maxCost)
Set the cost threshold (default is infinity). Any motion cost that is not better than this cost (acco...
Definition: BiTRRT.h:114
base::Cost cost
Cost of the state.
Definition: BiTRRT.h:203
bool connectTrees(Motion *nmotion, TreeData &tree, Motion *xmotion)
Attempt to connect tree to nmotion, which is in the other tree. xmotion is scratch space and will be ...
Definition: BiTRRT.cpp:270
Bi-directional Transition-based Rapidly-exploring Random Trees.
Definition: BiTRRT.h:69
The desired state was reached during extension.
Definition: BiTRRT.h:239
Definition of a cost value. Can represent the cost of a motion or the cost of a state.
Definition: Cost.h:47
void clear() override
Clear all internal datastructures. Planner settings are not affected. Subsequent calls to solve() wil...
Definition: BiTRRT.cpp:97
double temp_
The current temperature.
Definition: BiTRRT.h:287