TRRT.h
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2008, Willow Garage, Inc.
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: Dave Coleman */
36 
37 #ifndef OMPL_GEOMETRIC_PLANNERS_RRT_TRRT_
38 #define OMPL_GEOMETRIC_PLANNERS_RRT_TRRT_
39 
40 #include "ompl/geometric/planners/PlannerIncludes.h"
41 #include "ompl/datastructures/NearestNeighbors.h"
42 #include "ompl/base/OptimizationObjective.h"
43 
44 /*
45  NOTES:
46  **Variable Names that have been converted to longer versions from standards:
47  nearest_neighbors_ -> nn_
48  planner_termination_condition -> ptc
49 
50  **Inherited Member Variables Key:
51  si_ -> SpaceInformation
52  pdef_ -> ProblemDefinition
53  pis_ -> PlannerInputStates - Utility class to extract valid input states
54 */
55 
56 
57 namespace ompl
58 {
59 
60  namespace geometric
61  {
77  class TRRT : public base::Planner
78  {
79  public:
80 
83 
84  virtual ~TRRT();
85 
86  virtual void getPlannerData(base::PlannerData &data) const;
87 
88  virtual base::PlannerStatus solve(const base::PlannerTerminationCondition &plannerTerminationCondition);
89 
90  virtual void clear();
91 
101  void setGoalBias(double goalBias)
102  {
103  goalBias_ = goalBias;
104  }
105 
107  double getGoalBias() const
108  {
109  return goalBias_;
110  }
111 
117  void setRange(double distance)
118  {
119  maxDistance_ = distance;
120  }
121 
123  double getRange() const
124  {
125  return maxDistance_;
126  }
127 
129  void setMaxStatesFailed( double maxStatesFailed )
130  {
131  maxStatesFailed_ = maxStatesFailed;
132  }
133 
135  double getMaxStatesFailed( void ) const
136  {
137  return maxStatesFailed_;
138  }
139 
141  void setTempChangeFactor( double tempChangeFactor )
142  {
143  tempChangeFactor_ = tempChangeFactor;
144  }
145 
147  double getTempChangeFactor( void ) const
148  {
149  return tempChangeFactor_;
150  }
151 
153  void setMinTemperature( double minTemperature )
154  {
155  minTemperature_ = minTemperature;
156  }
157 
159  double getMinTemperature( void ) const
160  {
161  return minTemperature_;
162  }
163 
165  void setInitTemperature( double initTemperature )
166  {
167  initTemperature_ = initTemperature;
168  }
169 
171  double getInitTemperature( void ) const
172  {
173  return initTemperature_;
174  }
175 
178  void setFrontierThreshold( double frontier_threshold )
179  {
180  frontierThreshold_ = frontier_threshold;
181  }
182 
185  double getFrontierThreshold( void ) const
186  {
187  return frontierThreshold_;
188  }
189 
192  void setFrontierNodeRatio( double frontierNodeRatio )
193  {
194  frontierNodeRatio_ = frontierNodeRatio;
195  }
196 
199  double getFrontierNodeRatio( void ) const
200  {
201  return frontierNodeRatio_;
202  }
203 
205  void setKConstant( double kConstant )
206  {
207  kConstant_ = kConstant;
208  }
209 
211  double getKConstant( void ) const
212  {
213  return kConstant_;
214  }
215 
217  template<template<typename T> class NN>
219  {
220  nearestNeighbors_.reset(new NN<Motion*>());
221  }
222 
223  virtual void setup();
224 
225  protected:
226 
227 
232  class Motion
233  {
234  public:
235 
236  Motion() : state(NULL), parent(NULL)
237  {
238  }
239 
241  Motion(const base::SpaceInformationPtr &si) : state(si->allocState()), parent(NULL)
242  {
243  }
244 
245  ~Motion()
246  {
247  }
248 
251 
254 
257 
258  };
259 
261  void freeMemory();
262 
264  double distanceFunction(const Motion *a, const Motion *b) const
265  {
266  return si_->distance(a->state, b->state);
267  }
268 
274  bool transitionTest( double childCost, double parentCost, double distance );
275 
277  bool minExpansionControl( double randMotionDistance );
278 
281 
283  boost::shared_ptr< NearestNeighbors<Motion*> > nearestNeighbors_;
284 
286  double goalBias_;
287 
289  double maxDistance_;
290 
293 
296 
298  bool verbose_;
299 
300  // *********************************************************************************************************
301  // TRRT-Specific Variables
302  // *********************************************************************************************************
303 
304  // Transtion Test -----------------------------------------------------------------------
305 
309  double temp_;
310 
314  double kConstant_;
315 
317  unsigned int maxStatesFailed_;
318 
321 
324 
327 
329  unsigned int numStatesFailed_;
330 
331 
332  // Minimum Expansion Control --------------------------------------------------------------
333 
336  double frontierCount_;
337 
340 
343 
346  };
347  }
348 }
349 
350 #endif
Object containing planner generated vertex and edge data. It is assumed that all vertices are unique...
Definition: PlannerData.h:164
double getFrontierThreshold(void) const
Get the distance between a new state and the nearest neighbor that qualifies that state as being a fr...
Definition: TRRT.h:185
void setKConstant(double kConstant)
Set the constant value used to normalize the expression.
Definition: TRRT.h:205
double initTemperature_
A very low value at initialization to authorize very easy positive slopes.
Definition: TRRT.h:326
boost::shared_ptr< NearestNeighbors< Motion * > > nearestNeighbors_
A nearest-neighbors datastructure containing the tree of motions.
Definition: TRRT.h:283
unsigned int maxStatesFailed_
Max number of rejections allowed.
Definition: TRRT.h:317
A boost shared pointer wrapper for ompl::base::StateSampler.
void setNearestNeighbors()
Set a different nearest neighbors datastructure.
Definition: TRRT.h:218
double temp_
Temperature parameter used to control the difficulty level of transition tests. Low temperatures limi...
Definition: TRRT.h:309
double getFrontierNodeRatio(void) const
Get the ratio between adding nonfrontier nodes to frontier nodes, for example .1 is 1/10 or one nonfr...
Definition: TRRT.h:199
void setMinTemperature(double minTemperature)
Set the minimum the temperature can drop to before being floored at that value.
Definition: TRRT.h:153
double getGoalBias() const
Get the goal bias the planner is using.
Definition: TRRT.h:107
Motion * parent
The parent motion in the exploration tree.
Definition: TRRT.h:253
void setTempChangeFactor(double tempChangeFactor)
Set the factor by which the temperature rises or falls based on current acceptance/rejection rate...
Definition: TRRT.h:141
Encapsulate a termination condition for a motion planner. Planners will call operator() to decide whe...
RNG rng_
The random number generator.
Definition: TRRT.h:292
double maxDistance_
The maximum length of a motion to be added to a tree.
Definition: TRRT.h:289
bool transitionTest(double childCost, double parentCost, double distance)
Filter irrelevant configuration regarding the search of low-cost paths before inserting into tree...
Definition: TRRT.cpp:421
double getKConstant(void) const
Get the constant value used to normalize the expression.
Definition: TRRT.h:211
double frontierThreshold_
The distance between an old state and a new state that qualifies it as a frontier state...
Definition: TRRT.h:339
double kConstant_
Constant value used to normalize expression. Based on order of magnitude of the considered costs...
Definition: TRRT.h:314
Main namespace. Contains everything in this library.
Definition: Cost.h:42
double getInitTemperature(void) const
Get the initial temperature at the beginning of the algorithm. Should be low.
Definition: TRRT.h:171
TRRT(const base::SpaceInformationPtr &si)
Constructor.
Definition: TRRT.cpp:44
void setGoalBias(double goalBias)
Set the goal bias.
Definition: TRRT.h:101
Random number generation. An instance of this class cannot be used by multiple threads at once (membe...
Definition: RandomNumbers.h:54
double getRange() const
Get the range the planner is using.
Definition: TRRT.h:123
Representation of a motion.
Definition: TRRT.h:232
Motion * lastGoalMotion_
The most recent goal motion. Used for PlannerData computation.
Definition: TRRT.h:295
Base class for a planner.
Definition: Planner.h:232
base::Cost cost
Cost of the state.
Definition: TRRT.h:256
ompl::base::OptimizationObjectivePtr opt_
The optimization objective being optimized by TRRT.
Definition: TRRT.h:345
void setRange(double distance)
Set the range the planner is supposed to use.
Definition: TRRT.h:117
base::State * state
The state contained by the motion.
Definition: TRRT.h:250
A class to store the exit status of Planner::solve()
Definition: PlannerStatus.h:48
base::StateSamplerPtr sampler_
State sampler.
Definition: TRRT.h:280
A boost shared pointer wrapper for ompl::base::SpaceInformation.
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: TRRT.cpp:400
double distanceFunction(const Motion *a, const Motion *b) const
Compute distance between motions (actually distance between contained states)
Definition: TRRT.h:264
double getTempChangeFactor(void) const
Get the factor by which the temperature rises or falls based on current acceptance/rejection rate...
Definition: TRRT.h:147
void setMaxStatesFailed(double maxStatesFailed)
Set the maximum number of states that can be rejected before the temperature starts to rise...
Definition: TRRT.h:129
Definition of an abstract state.
Definition: State.h:50
virtual base::PlannerStatus solve(const base::PlannerTerminationCondition &plannerTerminationCondition)
Function that can solve the motion planning problem. This function can be called multiple times on th...
Definition: TRRT.cpp:174
double getMinTemperature(void) const
Get the minimum the temperature can drop to before being floored at that value.
Definition: TRRT.h:159
double goalBias_
The fraction of time the goal is picked as the state to expand towards (if such a state is available)...
Definition: TRRT.h:286
double getMaxStatesFailed(void) const
Get the maximum number of states that can be rejected before the temperature starts to rise...
Definition: TRRT.h:135
A boost shared pointer wrapper for ompl::base::OptimizationObjective.
void setFrontierNodeRatio(double frontierNodeRatio)
Set the ratio between adding nonfrontier nodes to frontier nodes, for example .1 is 1/10 or one nonfr...
Definition: TRRT.h:192
double minTemperature_
Prevent temperature from dropping too far.
Definition: TRRT.h:323
bool minExpansionControl(double randMotionDistance)
Use ratio to prefer frontier nodes to nonfrontier ones.
Definition: TRRT.cpp:479
void setInitTemperature(double initTemperature)
Set the initial temperature at the beginning of the algorithm. Should be low.
Definition: TRRT.h:165
Motion(const base::SpaceInformationPtr &si)
Constructor that allocates memory for the state.
Definition: TRRT.h:241
Transition-based Rapidly-exploring Random Trees.
Definition: TRRT.h:77
bool verbose_
Output debug info.
Definition: TRRT.h:298
double nonfrontierCount_
Ratio counters for nodes that expand the search space versus those that do not.
Definition: TRRT.h:335
SpaceInformationPtr si_
The space information for which planning is done.
Definition: Planner.h:397
double tempChangeFactor_
Failure temperature factor used when max_num_failed_ failures occur.
Definition: TRRT.h:320
void freeMemory()
Free the memory allocated by this planner.
Definition: TRRT.cpp:157
double frontierNodeRatio_
Target ratio of nonfrontier nodes to frontier nodes. rho.
Definition: TRRT.h:342
unsigned int numStatesFailed_
Failure counter for states that are rejected.
Definition: TRRT.h:329
virtual void setup()
Perform extra configuration steps, if needed. This call will also issue a call to ompl::base::SpaceIn...
Definition: TRRT.cpp:96
virtual void clear()
Clear all internal datastructures. Planner settings are not affected. Subsequent calls to solve() wil...
Definition: TRRT.cpp:80
Definition of a cost value. Can represent the cost of a motion or the cost of a state.
Definition: Cost.h:47
void setFrontierThreshold(double frontier_threshold)
Set the distance between a new state and the nearest neighbor that qualifies that state as being a fr...
Definition: TRRT.h:178