RRT.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: Ioan Sucan */
36 
37 #ifndef OMPL_GEOMETRIC_PLANNERS_RRT_RRT_
38 #define OMPL_GEOMETRIC_PLANNERS_RRT_RRT_
39 
40 #include "ompl/geometric/planners/PlannerIncludes.h"
41 #include "ompl/datastructures/NearestNeighbors.h"
42 
43 namespace ompl
44 {
45 
46  namespace geometric
47  {
48 
65  class RRT : public base::Planner
66  {
67  public:
68 
70  RRT(const base::SpaceInformationPtr &si);
71 
72  virtual ~RRT();
73 
74  virtual void getPlannerData(base::PlannerData &data) const;
75 
77 
78  virtual void clear();
79 
89  void setGoalBias(double goalBias)
90  {
91  goalBias_ = goalBias;
92  }
93 
95  double getGoalBias() const
96  {
97  return goalBias_;
98  }
99 
105  void setRange(double distance)
106  {
107  maxDistance_ = distance;
108  }
109 
111  double getRange() const
112  {
113  return maxDistance_;
114  }
115 
117  template<template<typename T> class NN>
119  {
120  nn_.reset(new NN<Motion*>());
121  }
122 
123  virtual void setup();
124 
125  protected:
126 
127 
132  class Motion
133  {
134  public:
135 
136  Motion() : state(NULL), parent(NULL)
137  {
138  }
139 
141  Motion(const base::SpaceInformationPtr &si) : state(si->allocState()), parent(NULL)
142  {
143  }
144 
145  ~Motion()
146  {
147  }
148 
151 
154 
155  };
156 
158  void freeMemory();
159 
161  double distanceFunction(const Motion *a, const Motion *b) const
162  {
163  return si_->distance(a->state, b->state);
164  }
165 
168 
170  boost::shared_ptr< NearestNeighbors<Motion*> > nn_;
171 
173  double goalBias_;
174 
176  double maxDistance_;
177 
180 
183  };
184 
185  }
186 }
187 
188 #endif
double maxDistance_
The maximum length of a motion to be added to a tree.
Definition: RRT.h:176
base::StateSamplerPtr sampler_
State sampler.
Definition: RRT.h:167
Motion(const base::SpaceInformationPtr &si)
Constructor that allocates memory for the state.
Definition: RRT.h:141
Object containing planner generated vertex and edge data. It is assumed that all vertices are unique...
Definition: PlannerData.h:164
virtual void setup()
Perform extra configuration steps, if needed. This call will also issue a call to ompl::base::SpaceIn...
Definition: RRT.cpp:70
Motion * parent
The parent motion in the exploration tree.
Definition: RRT.h:153
A boost shared pointer wrapper for ompl::base::StateSampler.
void setRange(double distance)
Set the range the planner is supposed to use.
Definition: RRT.h:105
Encapsulate a termination condition for a motion planner. Planners will call operator() to decide whe...
double getGoalBias() const
Get the goal bias the planner is using.
Definition: RRT.h:95
virtual void clear()
Clear all internal datastructures. Planner settings are not affected. Subsequent calls to solve() wil...
Definition: RRT.cpp:60
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: RRT.cpp:210
boost::shared_ptr< NearestNeighbors< Motion * > > nn_
A nearest-neighbors datastructure containing the tree of motions.
Definition: RRT.h:170
Main namespace. Contains everything in this library.
Definition: Cost.h:42
Random number generation. An instance of this class cannot be used by multiple threads at once (membe...
Definition: RandomNumbers.h:54
RNG rng_
The random number generator.
Definition: RRT.h:179
Base class for a planner.
Definition: Planner.h:232
double distanceFunction(const Motion *a, const Motion *b) const
Compute distance between motions (actually distance between contained states)
Definition: RRT.h:161
double getRange() const
Get the range the planner is using.
Definition: RRT.h:111
A class to store the exit status of Planner::solve()
Definition: PlannerStatus.h:48
Rapidly-exploring Random Trees.
Definition: RRT.h:65
A boost shared pointer wrapper for ompl::base::SpaceInformation.
void freeMemory()
Free the memory allocated by this planner.
Definition: RRT.cpp:81
Definition of an abstract state.
Definition: State.h:50
Motion * lastGoalMotion_
The most recent goal motion. Used for PlannerData computation.
Definition: RRT.h:182
Representation of a motion.
Definition: RRT.h:132
RRT(const base::SpaceInformationPtr &si)
Constructor.
Definition: RRT.cpp:42
void setNearestNeighbors()
Set a different nearest neighbors datastructure.
Definition: RRT.h:118
SpaceInformationPtr si_
The space information for which planning is done.
Definition: Planner.h:397
double goalBias_
The fraction of time the goal is picked as the state to expand towards (if such a state is available)...
Definition: RRT.h:173
void setGoalBias(double goalBias)
Set the goal bias.
Definition: RRT.h:89
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: RRT.cpp:96
base::State * state
The state contained by the motion.
Definition: RRT.h:150