All Classes Namespaces Functions Variables Typedefs Enumerations Enumerator Friends
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/datastructures/NearestNeighbors.h"
42 
43 #include <fstream>
44 
45 namespace ompl
46 {
47 
48  namespace geometric
49  {
50 
67  class LBTRRT : public base::Planner
68  {
69  public:
70 
73 
74  virtual ~LBTRRT (void);
75 
76  virtual void getPlannerData(base::PlannerData &data) const;
77 
79 
80  virtual void clear(void);
81 
91  void setGoalBias(double goalBias)
92  {
93  goalBias_ = goalBias;
94  }
95 
97  double getGoalBias(void) const
98  {
99  return goalBias_;
100  }
101 
107  void setRange(double distance)
108  {
109  maxDistance_ = distance;
110  }
111 
113  double getRange(void) const
114  {
115  return maxDistance_;
116  }
117 
119  template<template<typename T> class NN>
121  {
122  nn_.reset(new NN<Motion*>());
123  }
124 
125  virtual void setup(void);
126 
128  void setApproximationFactor (double epsilon)
129  {
130  epsilon_ = epsilon;
131  }
132 
134  double getApproximationFactor (void) const
135  {
136  return epsilon_;
137  }
138  protected:
139 
141  static const double kRRG; // = 5.5
142 
147  class Motion
148  {
149  public:
150 
151  Motion(void) : state(NULL), parentLb_(NULL), parentApx_(NULL), costLb_(0.0), costApx_(0.0)
152  {
153  }
154 
156  Motion(const base::SpaceInformationPtr &si) : state(si->allocState()), parentLb_(NULL), parentApx_(NULL), costLb_(0.0), costApx_(0.0)
157  {
158  }
159 
160  ~Motion(void)
161  {
162  }
163 
166 
169 
172 
173  double costLb_, costApx_;
174 
175  std::vector<Motion*> childrenLb_;
176  std::vector<Motion*> childrenApx_;
177  };
178 
179  struct IsLessThan
180  {
181  IsLessThan (LBTRRT* plannerPtr, Motion * motion_): plannerPtr_(plannerPtr), motion(motion_)
182  {
183  }
184 
185  bool operator() (const Motion * motionA, const Motion * motionB)
186  {
187  double sqDistA = plannerPtr_->distanceFunction(motionA, motion);
188  double distA = std::sqrt(sqDistA);
189 
190  double sqDistB = plannerPtr_->distanceFunction(motionB, motion);
191  double distB = std::sqrt(sqDistB);
192 
193  return (motionA->costLb_ + distA < motionB->costLb_ + distB);
194  }
195  LBTRRT* plannerPtr_;
196  Motion* motion;
197  }; //IsLessThan
198 
200  void attemptNodeUpdate(Motion* potentialParent, Motion* child);
201 
203  void updateChildCostsLb(Motion *m, double delta);
204 
206  void updateChildCostsApx(Motion *m, double delta);
207 
209  void removeFromParentLb(Motion *m);
210 
212  void removeFromParentApx(Motion *m);
213 
215  void removeFromParent(const Motion *m, std::vector<Motion*>& vec);
216 
218  void freeMemory(void);
219 
221  double distanceFunction(const Motion* a, const Motion* b) const
222  {
223  return si_->distance(a->state, b->state);
224  }
225 
228 
230  boost::shared_ptr< NearestNeighbors<Motion*> > nn_;
231 
233  double goalBias_;
234 
236  double maxDistance_;
237 
239  double epsilon_;
240 
243 
246  };
247 
248  }
249 }
250 
251 #endif //OMPL_GEOMETRIC_PLANNERS_RRT_LBT_RRT_
void updateChildCostsApx(Motion *m, double delta)
update the child cost of the approximation tree
Definition: LBTRRT.cpp:313
void attemptNodeUpdate(Motion *potentialParent, Motion *child)
attempt to rewire the trees
Definition: LBTRRT.cpp:238
void removeFromParentLb(Motion *m)
remove motion from its parent in the lower bound tree
Definition: LBTRRT.cpp:322
Object containing planner generated vertex and edge data. It is assumed that all vertices are unique...
Definition: PlannerData.h:164
double getRange(void) const
Get the range the planner is using.
Definition: LBTRRT.h:113
void setApproximationFactor(double epsilon)
Set the apprimation factor.
Definition: LBTRRT.h:128
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:105
LBTRRT(const base::SpaceInformationPtr &si)
Constructor.
Definition: LBTRRT.cpp:46
Motion * parentLb_
The parent motion in the exploration tree.
Definition: LBTRRT.h:168
A boost shared pointer wrapper for ompl::base::StateSampler.
Encapsulate a termination condition for a motion planner. Planners will call operator() to decide whe...
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:283
double maxDistance_
The maximum length of a motion to be added to a tree.
Definition: LBTRRT.h:236
base::State * state
The state contained by the motion.
Definition: LBTRRT.h:165
Lower Bound Tree Rapidly-exploring Random Trees.
Definition: LBTRRT.h:67
double distanceFunction(const Motion *a, const Motion *b) const
Compute distance between motions (actually distance between contained states)
Definition: LBTRRT.h:221
void removeFromParentApx(Motion *m)
remove motion from its parent in the approximation tree
Definition: LBTRRT.cpp:326
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:233
RNG rng_
The random number generator.
Definition: LBTRRT.h:242
Random number generation. An instance of this class cannot be used by multiple threads at once (membe...
Definition: RandomNumbers.h:54
double getApproximationFactor(void) const
Get the apprimation factor.
Definition: LBTRRT.h:134
Motion * lastGoalMotion_
The most recent goal motion. Used for PlannerData computation.
Definition: LBTRRT.h:245
Base class for a planner.
Definition: Planner.h:227
void freeMemory(void)
Free the memory allocated by this planner.
Definition: LBTRRT.cpp:90
void updateChildCostsLb(Motion *m, double delta)
update the child cost of the lower bound tree
Definition: LBTRRT.cpp:305
A class to store the exit status of Planner::solve()
Definition: PlannerStatus.h:48
A boost shared pointer wrapper for ompl::base::SpaceInformation.
double epsilon_
approximation factor
Definition: LBTRRT.h:239
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:107
virtual void clear(void)
Clear all internal datastructures. Planner settings are not affected. Subsequent calls to solve() wil...
Definition: LBTRRT.cpp:69
Motion * parentApx_
The parent motion in the exploration tree.
Definition: LBTRRT.h:171
Motion(const base::SpaceInformationPtr &si)
Constructor that allocates memory for the state.
Definition: LBTRRT.h:156
static const double kRRG
kRRG = 2e~5.5 is a valid choice for all problem instances
Definition: LBTRRT.h:141
boost::shared_ptr< NearestNeighbors< Motion * > > nn_
A nearest-neighbors datastructure containing the tree of motions.
Definition: LBTRRT.h:230
void setGoalBias(double goalBias)
Set the goal bias.
Definition: LBTRRT.h:91
Representation of a motion.
Definition: LBTRRT.h:147
SpaceInformationPtr si_
The space information for which planning is done.
Definition: Planner.h:392
void removeFromParent(const Motion *m, std::vector< Motion * > &vec)
remove motion from a vector
Definition: LBTRRT.cpp:330
double getGoalBias(void) const
Get the goal bias the planner is using.
Definition: LBTRRT.h:97
void setNearestNeighbors(void)
Set a different nearest neighbors datastructure.
Definition: LBTRRT.h:120
base::StateSamplerPtr sampler_
State sampler.
Definition: LBTRRT.h:227
virtual void setup(void)
Perform extra configuration steps, if needed. This call will also issue a call to ompl::base::SpaceIn...
Definition: LBTRRT.cpp:79