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_CONTROL_PLANNERS_RRT_RRT_
38 #define OMPL_CONTROL_PLANNERS_RRT_RRT_
39 
40 #include "ompl/control/planners/PlannerIncludes.h"
41 #include "ompl/datastructures/NearestNeighbors.h"
42 
43 namespace ompl
44 {
45  namespace control
46  {
65  class RRT : public base::Planner
66  {
67  public:
69  RRT(const SpaceInformationPtr &si);
70 
71  ~RRT() override;
72 
74  base::PlannerStatus solve(const base::PlannerTerminationCondition &ptc) override;
75 
79  void clear() override;
80 
88  void setGoalBias(double goalBias)
89  {
90  goalBias_ = goalBias;
91  }
92 
94  double getGoalBias() const
95  {
96  return goalBias_;
97  }
98 
101  bool getIntermediateStates() const
102  {
103  return addIntermediateStates_;
104  }
105 
108  void setIntermediateStates(bool addIntermediateStates)
109  {
110  addIntermediateStates_ = addIntermediateStates;
111  }
112 
113  void getPlannerData(base::PlannerData &data) const override;
114 
116  template <template <typename T> class NN>
117  void setNearestNeighbors()
118  {
119  if (nn_ && nn_->size() != 0)
120  OMPL_WARN("Calling setNearestNeighbors will clear all states.");
121  clear();
122  nn_ = std::make_shared<NN<Motion *>>();
123  setup();
124  }
125 
126  void setup() override;
127 
128  protected:
133  class Motion
134  {
135  public:
136  Motion() = default;
137 
139  Motion(const SpaceInformation *si)
140  : state(si->allocState()), control(si->allocControl())
141  {
142  }
143 
144  ~Motion() = default;
145 
147  base::State *state{nullptr};
148 
150  Control *control{nullptr};
151 
153  unsigned int steps{0};
154 
156  Motion *parent{nullptr};
157  };
158 
160  void freeMemory();
161 
163  double distanceFunction(const Motion *a, const Motion *b) const
164  {
165  return si_->distance(a->state, b->state);
166  }
167 
169  base::StateSamplerPtr sampler_;
170 
173 
175  const SpaceInformation *siC_;
176 
178  std::shared_ptr<NearestNeighbors<Motion *>> nn_;
179 
182  double goalBias_{0.05};
183 
185  bool addIntermediateStates_{false};
186 
188  RNG rng_;
189 
191  Motion *lastGoalMotion_{nullptr};
192  };
193  }
194 }
195 
196 #endif
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: RRT.cpp:263
base::PlannerStatus solve(const base::PlannerTerminationCondition &ptc) override
Continue solving for some amount of time. Return true if solution was found.
Definition: RRT.cpp:93
const SpaceInformation * siC_
The base::SpaceInformation cast as control::SpaceInformation, for convenience.
Definition: RRT.h:271
bool addIntermediateStates_
Flag indicating whether intermediate states are added to the built tree of motions.
Definition: RRT.h:281
A shared pointer wrapper for ompl::base::SpaceInformation.
Control * control
The control contained by the motion.
Definition: RRT.h:246
RRT(const SpaceInformationPtr &si)
Constructor.
Definition: RRT.cpp:42
base::StateSamplerPtr sampler_
State sampler.
Definition: RRT.h:265
double getGoalBias() const
Get the goal bias the planner is using.
Definition: RRT.h:190
void setNearestNeighbors()
Set a different nearest neighbors datastructure.
Definition: RRT.h:213
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:278
DirectedControlSamplerPtr controlSampler_
Control sampler.
Definition: RRT.h:268
Motion * parent
The parent motion in the exploration tree.
Definition: RRT.h:252
RNG rng_
The random number generator.
Definition: RRT.h:284
void clear() override
Clear datastructures. Call this function if the input data to the planner has changed and you do not ...
Definition: RRT.cpp:65
bool getIntermediateStates() const
Return true if the intermediate states generated along motions are to be added to the tree itself.
Definition: RRT.h:197
std::shared_ptr< NearestNeighbors< Motion * > > nn_
A nearest-neighbors datastructure containing the tree of motions.
Definition: RRT.h:274
#define OMPL_WARN(fmt,...)
Log a formatted warning string.
Definition: Console.h:66
void setIntermediateStates(bool addIntermediateStates)
Specify whether the intermediate states generated along motions are to be added to the tree itself.
Definition: RRT.h:204
A shared pointer wrapper for ompl::control::DirectedControlSampler.
SpaceInformationPtr si_
The space information for which planning is done.
Definition: Planner.h:474
double distanceFunction(const Motion *a, const Motion *b) const
Compute distance between motions (actually distance between contained states)
Definition: RRT.h:259
unsigned int steps
The number of steps the control is applied for.
Definition: RRT.h:249
base::State * state
The state contained by the motion.
Definition: RRT.h:243
Motion * lastGoalMotion_
The most recent goal motion. Used for PlannerData computation.
Definition: RRT.h:287
void setGoalBias(double goalBias)
Definition: RRT.h:184
void freeMemory()
Free the memory allocated by this planner.
Definition: RRT.cpp:76
void setup() override
Perform extra configuration steps, if needed. This call will also issue a call to ompl::base::SpaceIn...
Definition: RRT.cpp:57
Main namespace. Contains everything in this library.