RRT.cpp
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 #include "ompl/control/planners/rrt/RRT.h"
38 #include "ompl/base/goals/GoalSampleableRegion.h"
39 #include "ompl/tools/config/SelfConfig.h"
40 #include <limits>
41 
42 ompl::control::RRT::RRT(const SpaceInformationPtr &si) : base::Planner(si, "RRT")
43 {
45  siC_ = si.get();
46  addIntermediateStates_ = false;
47  lastGoalMotion_ = nullptr;
48 
49  goalBias_ = 0.05;
50 
51  Planner::declareParam<double>("goal_bias", this, &RRT::setGoalBias, &RRT::getGoalBias, "0.:.05:1.");
52  Planner::declareParam<bool>("intermediate_states", this, &RRT::setIntermediateStates, &RRT::getIntermediateStates);
53 }
54 
55 ompl::control::RRT::~RRT()
56 {
57  freeMemory();
58 }
59 
61 {
63  if (!nn_)
64  nn_.reset(tools::SelfConfig::getDefaultNearestNeighbors<Motion *>(this));
65  nn_->setDistanceFunction([this](const Motion *a, const Motion *b)
66  {
67  return distanceFunction(a, b);
68  });
69 }
70 
72 {
73  Planner::clear();
74  sampler_.reset();
75  controlSampler_.reset();
76  freeMemory();
77  if (nn_)
78  nn_->clear();
79  lastGoalMotion_ = nullptr;
80 }
81 
83 {
84  if (nn_)
85  {
86  std::vector<Motion *> motions;
87  nn_->list(motions);
88  for (auto &motion : motions)
89  {
90  if (motion->state)
91  si_->freeState(motion->state);
92  if (motion->control)
93  siC_->freeControl(motion->control);
94  delete motion;
95  }
96  }
97 }
98 
100 {
101  checkValidity();
102  base::Goal *goal = pdef_->getGoal().get();
103  base::GoalSampleableRegion *goal_s = dynamic_cast<base::GoalSampleableRegion *>(goal);
104 
105  while (const base::State *st = pis_.nextStart())
106  {
107  auto *motion = new Motion(siC_);
108  si_->copyState(motion->state, st);
109  siC_->nullControl(motion->control);
110  nn_->add(motion);
111  }
112 
113  if (nn_->size() == 0)
114  {
115  OMPL_ERROR("%s: There are no valid initial states!", getName().c_str());
117  }
118 
119  if (!sampler_)
120  sampler_ = si_->allocStateSampler();
121  if (!controlSampler_)
123 
124  OMPL_INFORM("%s: Starting planning with %u states already in datastructure", getName().c_str(), nn_->size());
125 
126  Motion *solution = nullptr;
127  Motion *approxsol = nullptr;
128  double approxdif = std::numeric_limits<double>::infinity();
129 
130  auto *rmotion = new Motion(siC_);
131  base::State *rstate = rmotion->state;
132  Control *rctrl = rmotion->control;
133  base::State *xstate = si_->allocState();
134 
135  while (ptc == false)
136  {
137  /* sample random state (with goal biasing) */
138  if (goal_s && rng_.uniform01() < goalBias_ && goal_s->canSample())
139  goal_s->sampleGoal(rstate);
140  else
141  sampler_->sampleUniform(rstate);
142 
143  /* find closest state in the tree */
144  Motion *nmotion = nn_->nearest(rmotion);
145 
146  /* sample a random control that attempts to go towards the random state, and also sample a control duration */
147  unsigned int cd = controlSampler_->sampleTo(rctrl, nmotion->control, nmotion->state, rmotion->state);
148 
150  {
151  // this code is contributed by Jennifer Barry
152  std::vector<base::State *> pstates;
153  cd = siC_->propagateWhileValid(nmotion->state, rctrl, cd, pstates, true);
154 
155  if (cd >= siC_->getMinControlDuration())
156  {
157  Motion *lastmotion = nmotion;
158  bool solved = false;
159  size_t p = 0;
160  for (; p < pstates.size(); ++p)
161  {
162  /* create a motion */
163  auto *motion = new Motion();
164  motion->state = pstates[p];
165  // we need multiple copies of rctrl
166  motion->control = siC_->allocControl();
167  siC_->copyControl(motion->control, rctrl);
168  motion->steps = 1;
169  motion->parent = lastmotion;
170  lastmotion = motion;
171  nn_->add(motion);
172  double dist = 0.0;
173  solved = goal->isSatisfied(motion->state, &dist);
174  if (solved)
175  {
176  approxdif = dist;
177  solution = motion;
178  break;
179  }
180  if (dist < approxdif)
181  {
182  approxdif = dist;
183  approxsol = motion;
184  }
185  }
186 
187  // free any states after we hit the goal
188  while (++p < pstates.size())
189  si_->freeState(pstates[p]);
190  if (solved)
191  break;
192  }
193  else
194  for (auto &pstate : pstates)
195  si_->freeState(pstate);
196  }
197  else
198  {
199  if (cd >= siC_->getMinControlDuration())
200  {
201  /* create a motion */
202  auto *motion = new Motion(siC_);
203  si_->copyState(motion->state, rmotion->state);
204  siC_->copyControl(motion->control, rctrl);
205  motion->steps = cd;
206  motion->parent = nmotion;
207 
208  nn_->add(motion);
209  double dist = 0.0;
210  bool solv = goal->isSatisfied(motion->state, &dist);
211  if (solv)
212  {
213  approxdif = dist;
214  solution = motion;
215  break;
216  }
217  if (dist < approxdif)
218  {
219  approxdif = dist;
220  approxsol = motion;
221  }
222  }
223  }
224  }
225 
226  bool solved = false;
227  bool approximate = false;
228  if (solution == nullptr)
229  {
230  solution = approxsol;
231  approximate = true;
232  }
233 
234  if (solution != nullptr)
235  {
236  lastGoalMotion_ = solution;
237 
238  /* construct the solution path */
239  std::vector<Motion *> mpath;
240  while (solution != nullptr)
241  {
242  mpath.push_back(solution);
243  solution = solution->parent;
244  }
245 
246  /* set the solution path */
247  auto path(std::make_shared<PathControl>(si_));
248  for (int i = mpath.size() - 1; i >= 0; --i)
249  if (mpath[i]->parent)
250  path->append(mpath[i]->state, mpath[i]->control, mpath[i]->steps * siC_->getPropagationStepSize());
251  else
252  path->append(mpath[i]->state);
253  solved = true;
254  pdef_->addSolutionPath(path, approximate, approxdif, getName());
255  }
256 
257  if (rmotion->state)
258  si_->freeState(rmotion->state);
259  if (rmotion->control)
260  siC_->freeControl(rmotion->control);
261  delete rmotion;
262  si_->freeState(xstate);
263 
264  OMPL_INFORM("%s: Created %u states", getName().c_str(), nn_->size());
265 
266  return base::PlannerStatus(solved, approximate);
267 }
268 
270 {
271  Planner::getPlannerData(data);
272 
273  std::vector<Motion *> motions;
274  if (nn_)
275  nn_->list(motions);
276 
277  double delta = siC_->getPropagationStepSize();
278 
279  if (lastGoalMotion_)
281 
282  for (auto m : motions)
283  {
284  if (m->parent)
285  {
286  if (data.hasControls())
287  data.addEdge(base::PlannerDataVertex(m->parent->state), base::PlannerDataVertex(m->state),
288  control::PlannerDataEdgeControl(m->control, m->steps * delta));
289  else
290  data.addEdge(base::PlannerDataVertex(m->parent->state), base::PlannerDataVertex(m->state));
291  }
292  else
293  data.addStartVertex(base::PlannerDataVertex(m->state));
294  }
295 }
DirectedControlSamplerPtr controlSampler_
Control sampler.
Definition: RRT.h:174
DirectedControlSamplerPtr allocDirectedControlSampler() const
Allocate an instance of the DirectedControlSampler to use. This will be the default (SimpleDirectedCo...
bool approximateSolutions
Flag indicating whether the planner is able to compute approximate solutions.
Definition: Planner.h:212
Object containing planner generated vertex and edge data. It is assumed that all vertices are unique...
Definition: PlannerData.h:174
double getPropagationStepSize() const
Propagation is performed at integer multiples of a specified step size. This function returns the val...
unsigned int getMinControlDuration() const
Get the minimum number of steps a control is propagated for.
unsigned int propagateWhileValid(const base::State *state, const Control *control, int steps, base::State *result) const
Propagate the model of the system forward, starting at a given state, with a given control...
void nullControl(Control *control) const
Make the control have no effect if it were to be applied to a state for any amount of time...
Definition of an abstract control.
Definition: Control.h:47
unsigned int addGoalVertex(const PlannerDataVertex &v)
Adds the given vertex to the graph data, and marks it as a start vertex. The vertex index is returned...
Abstract definition of goals.
Definition: Goal.h:62
std::shared_ptr< NearestNeighbors< Motion * > > nn_
A nearest-neighbors datastructure containing the tree of motions.
Definition: RRT.h:180
Encapsulate a termination condition for a motion planner. Planners will call operator() to decide whe...
void setup() override
Perform extra configuration steps, if needed. This call will also issue a call to ompl::base::SpaceIn...
Definition: RRT.cpp:60
base::State * state
The state contained by the motion.
Definition: RRT.h:149
Representation of an edge in PlannerData for planning with controls. This structure encodes a specifi...
Definition: PlannerData.h:60
RRT(const SpaceInformationPtr &si)
Constructor.
Definition: RRT.cpp:42
void freeMemory()
Free the memory allocated by this planner.
Definition: RRT.cpp:82
double distanceFunction(const Motion *a, const Motion *b) const
Compute distance between motions (actually distance between contained states)
Definition: RRT.h:165
Control * allocControl() const
Allocate memory for a control.
bool getIntermediateStates() const
Return true if the intermediate states generated along motions are to be added to the tree itself...
Definition: RRT.h:101
bool addIntermediateStates_
Flag indicating whether intermediate states are added to the built tree of motions.
Definition: RRT.h:187
ProblemDefinitionPtr pdef_
The user set problem definition.
Definition: Planner.h:418
virtual void sampleGoal(State *st) const =0
Sample a state in the goal region.
void setIntermediateStates(bool addIntermediateStates)
Specify whether the intermediate states generated along motions are to be added to the tree itself...
Definition: RRT.h:108
double uniform01()
Generate a random real between 0 and 1.
Definition: RandomNumbers.h:68
base::StateSamplerPtr sampler_
State sampler.
Definition: RRT.h:171
Base class for a vertex in the PlannerData structure. All derived classes must implement the clone an...
Definition: PlannerData.h:58
Invalid start state or no start state specified.
Definition: PlannerStatus.h:56
Abstract definition of a goal region that can be sampled.
Representation of a motion.
Definition: RRT.h:133
void copyControl(Control *destination, const Control *source) const
Copy a control to another.
#define OMPL_ERROR(fmt,...)
Log a formatted error string.
Definition: Console.h:64
Control * control
The control contained by the motion.
Definition: RRT.h:152
bool canSample() const
Return true if maxSampleCount() > 0, since in this case samples can certainly be produced.
Motion * lastGoalMotion_
The most recent goal motion. Used for PlannerData computation.
Definition: RRT.h:193
virtual void setup()
Perform extra configuration steps, if needed. This call will also issue a call to ompl::base::SpaceIn...
Definition: Planner.cpp:87
A class to store the exit status of Planner::solve()
Definition: PlannerStatus.h:48
virtual bool addEdge(unsigned int v1, unsigned int v2, const PlannerDataEdge &edge=PlannerDataEdge(), Cost weight=Cost(1.0))
Adds a directed edge between the given vertex indexes. An optional edge structure and weight can be s...
unsigned int addStartVertex(const PlannerDataVertex &v)
Adds the given vertex to the graph data, and marks it as a start vertex. The vertex index is returned...
Definition of an abstract state.
Definition: State.h:49
virtual void checkValidity()
Check to see if the planner is in a working state (setup has been called, a goal was set...
Definition: Planner.cpp:101
virtual bool isSatisfied(const State *st) const =0
Return true if the state satisfies the goal constraints.
PlannerInputStates pis_
Utility class to extract valid input states.
Definition: Planner.h:421
A shared pointer wrapper for ompl::control::SpaceInformation.
base::PlannerStatus solve(const base::PlannerTerminationCondition &ptc) override
Continue solving for some amount of time. Return true if solution was found.
Definition: RRT.cpp:99
PlannerSpecs specs_
The specifications of the planner (its capabilities)
Definition: Planner.h:427
const State * nextStart()
Return the next valid start state or nullptr if no more valid start states are available.
Definition: Planner.cpp:230
virtual bool hasControls() const
Indicate whether any information about controls (ompl::control::Control) is stored in this instance...
const std::string & getName() const
Get the name of the planner.
Definition: Planner.cpp:56
void setGoalBias(double goalBias)
Definition: RRT.h:88
void freeControl(Control *control) const
Free the memory of a control.
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:269
const SpaceInformation * siC_
The base::SpaceInformation cast as control::SpaceInformation, for convenience.
Definition: RRT.h:177
SpaceInformationPtr si_
The space information for which planning is done.
Definition: Planner.h:415
double getGoalBias() const
Get the goal bias the planner is using.
Definition: RRT.h:94
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:184
void clear() override
Clear datastructures. Call this function if the input data to the planner has changed and you do not ...
Definition: RRT.cpp:71
RNG rng_
The random number generator.
Definition: RRT.h:190
#define OMPL_INFORM(fmt,...)
Log a formatted information string.
Definition: Console.h:68