LBTRRT.h
1 /*********************************************************************
2 * Software License Agreement (BSD License)
3 *
4 * Copyright (c) 2013, Oren Salzman
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 Willow Garage 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: Oren Salzman, Sertac Karaman, Ioan Sucan */
36 
37 #ifndef OMPL_GEOMETRIC_PLANNERS_RRT_LBT_RRT_
38 #define OMPL_GEOMETRIC_PLANNERS_RRT_LBT_RRT_
39 
40 #include "ompl/geometric/planners/PlannerIncludes.h"
41 #include "ompl/base/OptimizationObjective.h"
42 #include "ompl/datastructures/NearestNeighbors.h"
43 
44 #include <fstream>
45 
46 namespace ompl
47 {
48 
49  namespace geometric
50  {
51 
68  class LBTRRT : public base::Planner
69  {
70  public:
71 
74 
75  virtual ~LBTRRT ();
76 
77  virtual void getPlannerData(base::PlannerData &data) const;
78 
80 
81  virtual void clear();
82 
92  void setGoalBias(double goalBias)
93  {
94  goalBias_ = goalBias;
95  }
96 
98  double getGoalBias() const
99  {
100  return goalBias_;
101  }
102 
108  void setRange(double distance)
109  {
110  maxDistance_ = distance;
111  }
112 
114  double getRange() const
115  {
116  return maxDistance_;
117  }
118 
120  template<template<typename T> class NN>
122  {
123  nn_.reset(new NN<Motion*>());
124  }
125 
126  virtual void setup();
127 
129  void setApproximationFactor (double epsilon)
130  {
131  epsilon_ = epsilon;
132  }
133 
135  double getApproximationFactor () const
136  {
137  return epsilon_;
138  }
139 
141  // Planner progress property functions
142  std::string getIterationCount() const
143  {
144  return boost::lexical_cast<std::string>(iterations_);
145  }
146  std::string getBestCost() const
147  {
148  return boost::lexical_cast<std::string>(bestCost_);
149  }
150 
151  protected:
152 
154  static const double kRRG; // = 5.5
155 
160  class Motion
161  {
162  public:
163 
164  Motion() : state(NULL), parentLb_(NULL), parentApx_(NULL), costLb_(0.0), costApx_(0.0)
165  {
166  }
167 
169  Motion(const base::SpaceInformationPtr &si) : state(si->allocState()), parentLb_(NULL), parentApx_(NULL), costLb_(0.0), costApx_(0.0)
170  {
171  }
172 
173  ~Motion()
174  {
175  }
176 
179 
182 
185 
192 
193  std::vector<Motion*> childrenLb_;
194  std::vector<Motion*> childrenApx_;
195  };
196 
197  struct CostCompare
198  {
199  CostCompare(const base::OptimizationObjective &opt, Motion *motion_): opt_(opt), motion(motion_)
200  {
201  }
202 
203  bool operator() (const Motion *motionA, const Motion *motionB)
204  {
205  base::Cost costA = opt_.combineCosts(motionA->costLb_, opt_.motionCost(motionA->state, motion->state));
206  base::Cost costB = opt_.combineCosts(motionB->costLb_, opt_.motionCost(motionB->state, motion->state));
207  return opt_.isCostBetterThan(costA, costB);
208  }
210  Motion *motion;
211  }; //IsLessThan
212 
214  bool attemptNodeUpdate(Motion *potentialParent, Motion *child);
215 
217  void updateChildCostsLb(Motion *m);
218 
220  void updateChildCostsApx(Motion *m);
221 
223  void removeFromParentLb(Motion *m);
224 
226  void removeFromParentApx(Motion *m);
227 
229  void removeFromParent(const Motion *m, std::vector<Motion*>& vec);
230 
232  void freeMemory();
233 
235  double distanceFunction(const Motion *a, const Motion *b) const
236  {
237  return si_->distance(a->state, b->state);
238  }
239  /* \brief Compute cost to move from state in motion a to state in motion b */
240  base::Cost costFunction(const Motion *a, const Motion *b) const
241  {
242  return opt_->motionCost(a->state, b->state);
243  }
246 
248  boost::shared_ptr< NearestNeighbors<Motion*> > nn_;
249 
251  double goalBias_;
252 
254  double maxDistance_;
255 
257  double epsilon_;
258 
261 
264 
267 
269  std::vector<Motion*> goalMotions_;
270 
272  // Planner progress properties
274  unsigned int iterations_;
277 
278  };
279 
280  }
281 }
282 
283 #endif //OMPL_GEOMETRIC_PLANNERS_RRT_LBT_RRT_
void removeFromParentLb(Motion *m)
remove motion from its parent in the lower bound tree
Definition: LBTRRT.cpp:405
Object containing planner generated vertex and edge data. It is assumed that all vertices are unique...
Definition: PlannerData.h:164
void setApproximationFactor(double epsilon)
Set the apprimation factor.
Definition: LBTRRT.h:129
void freeMemory()
Free the memory allocated by this planner.
Definition: LBTRRT.cpp:122
virtual base::PlannerStatus solve(const base::PlannerTerminationCondition &ptc)
Function that can solve the motion planning problem. This function can be called multiple times on th...
Definition: LBTRRT.cpp:137
LBTRRT(const base::SpaceInformationPtr &si)
Constructor.
Definition: LBTRRT.cpp:46
bool attemptNodeUpdate(Motion *potentialParent, Motion *child)
attempt to rewire the trees
Definition: LBTRRT.cpp:321
Motion * parentLb_
The parent motion in the exploration tree.
Definition: LBTRRT.h:181
double distanceFunction(const Motion *a, const Motion *b) const
Compute distance between motions (actually distance between contained states)
Definition: LBTRRT.h:235
A boost shared pointer wrapper for ompl::base::StateSampler.
double getGoalBias() const
Get the goal bias the planner is using.
Definition: LBTRRT.h:98
Encapsulate a termination condition for a motion planner. Planners will call operator() to decide whe...
double maxDistance_
The maximum length of a motion to be added to a tree.
Definition: LBTRRT.h:254
base::State * state
The state contained by the motion.
Definition: LBTRRT.h:178
Lower Bound Tree Rapidly-exploring Random Trees.
Definition: LBTRRT.h:68
void removeFromParentApx(Motion *m)
remove motion from its parent in the approximation tree
Definition: LBTRRT.cpp:409
double goalBias_
The fraction of time the goal is picked as the state to expand towards (if such a state is available)...
Definition: LBTRRT.h:251
base::Cost costLb_
Cost lower bound on path from start to state.
Definition: LBTRRT.h:187
virtual void setup()
Perform extra configuration steps, if needed. This call will also issue a call to ompl::base::SpaceIn...
Definition: LBTRRT.cpp:89
Main namespace. Contains everything in this library.
Definition: Cost.h:42
RNG rng_
The random number generator.
Definition: LBTRRT.h:260
Random number generation. An instance of this class cannot be used by multiple threads at once (membe...
Definition: RandomNumbers.h:54
Motion * lastGoalMotion_
The most recent goal motion. Used for PlannerData computation.
Definition: LBTRRT.h:266
Base class for a planner.
Definition: Planner.h:232
double getRange() const
Get the range the planner is using.
Definition: LBTRRT.h:114
void removeFromParent(const Motion *m, std::vector< Motion *> &vec)
remove motion from a vector
Definition: LBTRRT.cpp:413
virtual void getPlannerData(base::PlannerData &data) const
Get information about the current run of the motion planner. Repeated calls to this function will upd...
Definition: LBTRRT.cpp:367
A class to store the exit status of Planner::solve()
Definition: PlannerStatus.h:48
void updateChildCostsLb(Motion *m)
update the child cost of the lower bound tree
Definition: LBTRRT.cpp:388
A boost shared pointer wrapper for ompl::base::SpaceInformation.
double epsilon_
approximation factor
Definition: LBTRRT.h:257
void updateChildCostsApx(Motion *m)
update the child cost of the approximation tree
Definition: LBTRRT.cpp:396
Definition of an abstract state.
Definition: State.h:50
void setRange(double distance)
Set the range the planner is supposed to use.
Definition: LBTRRT.h:108
base::OptimizationObjectivePtr opt_
Objective we&#39;re optimizing.
Definition: LBTRRT.h:263
Motion * parentApx_
The parent motion in the exploration tree.
Definition: LBTRRT.h:184
Abstract definition of optimization objectives.
Motion(const base::SpaceInformationPtr &si)
Constructor that allocates memory for the state.
Definition: LBTRRT.h:169
A boost shared pointer wrapper for ompl::base::OptimizationObjective.
virtual void clear()
Clear all internal datastructures. Planner settings are not affected. Subsequent calls to solve() wil...
Definition: LBTRRT.cpp:75
static const double kRRG
kRRG = 2e~5.5 is a valid choice for all problem instances
Definition: LBTRRT.h:154
boost::shared_ptr< NearestNeighbors< Motion * > > nn_
A nearest-neighbors datastructure containing the tree of motions.
Definition: LBTRRT.h:248
std::vector< Motion * > goalMotions_
A list of states in the tree that satisfy the goal condition.
Definition: LBTRRT.h:269
double getApproximationFactor() const
Get the apprimation factor.
Definition: LBTRRT.h:135
void setGoalBias(double goalBias)
Set the goal bias.
Definition: LBTRRT.h:92
Representation of a motion.
Definition: LBTRRT.h:160
SpaceInformationPtr si_
The space information for which planning is done.
Definition: Planner.h:397
base::Cost incCost_
The incremental lower bound cost of this motion&#39;s parent to this motion (this is stored to save dista...
Definition: LBTRRT.h:191
void setNearestNeighbors()
Set a different nearest neighbors datastructure.
Definition: LBTRRT.h:121
Definition of a cost value. Can represent the cost of a motion or the cost of a state.
Definition: Cost.h:47
unsigned int iterations_
Number of iterations the algorithm performed.
Definition: LBTRRT.h:274
base::StateSamplerPtr sampler_
State sampler.
Definition: LBTRRT.h:245
base::Cost costApx_
Approximate cost on path from start to state.
Definition: LBTRRT.h:189
base::Cost bestCost_
Best cost found so far by algorithm.
Definition: LBTRRT.h:276