STRIDE.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: Bryant Gipson, Mark Moll, Ioan Sucan */
36 
37 #include "ompl/geometric/planners/stride/STRIDE.h"
38 // enable sampling from the GNAT data structure
39 #define GNAT_SAMPLER
40 #include "ompl/datastructures/NearestNeighborsGNAT.h"
41 #include "ompl/base/goals/GoalSampleableRegion.h"
42 #include "ompl/tools/config/SelfConfig.h"
43 #include <limits>
44 #include <cassert>
45 
46 ompl::geometric::STRIDE::STRIDE(const base::SpaceInformationPtr &si, bool useProjectedDistance, unsigned int degree,
47  unsigned int minDegree, unsigned int maxDegree, unsigned int maxNumPtsPerLeaf,
48  double estimatedDimension)
49  : base::Planner(si, "STRIDE")
50  , useProjectedDistance_(useProjectedDistance)
51  , degree_(degree)
52  , minDegree_(minDegree)
53  , maxDegree_(maxDegree)
54  , maxNumPtsPerLeaf_(maxNumPtsPerLeaf)
55  , estimatedDimension_(estimatedDimension)
56 {
58 
59  if (estimatedDimension_ < 1.)
60  estimatedDimension_ = si->getStateDimension();
61 
62  Planner::declareParam<double>("range", this, &STRIDE::setRange, &STRIDE::getRange, "0.:1.:10000.");
63  Planner::declareParam<double>("goal_bias", this, &STRIDE::setGoalBias, &STRIDE::getGoalBias, "0.:.05:1.");
64  Planner::declareParam<bool>("use_projected_distance", this, &STRIDE::setUseProjectedDistance,
66  Planner::declareParam<unsigned int>("degree", this, &STRIDE::setDegree, &STRIDE::getDegree, "2:20");
67  Planner::declareParam<unsigned int>("max_degree", this, &STRIDE::setMaxDegree, &STRIDE::getMaxDegree, "2:20");
68  Planner::declareParam<unsigned int>("min_degree", this, &STRIDE::setMinDegree, &STRIDE::getMinDegree, "2:20");
69  Planner::declareParam<unsigned int>("max_pts_per_leaf", this, &STRIDE::setMaxNumPtsPerLeaf,
70  &STRIDE::getMaxNumPtsPerLeaf, "1:200");
71  Planner::declareParam<double>("estimated_dimension", this, &STRIDE::setEstimatedDimension,
73  Planner::declareParam<double>("min_valid_path_fraction", this, &STRIDE::setMinValidPathFraction,
74  &STRIDE::getMinValidPathFraction, "0.:.05:1.");
75 }
76 
77 ompl::geometric::STRIDE::~STRIDE()
78 {
79  freeMemory();
80 }
81 
83 {
84  Planner::setup();
85  tools::SelfConfig sc(si_, getName());
86  sc.configureProjectionEvaluator(projectionEvaluator_);
87  sc.configurePlannerRange(maxDistance_);
88  setupTree();
89 }
90 
92 {
93  tree_.reset(
94  new NearestNeighborsGNAT<Motion *>(degree_, minDegree_, maxDegree_, maxNumPtsPerLeaf_, estimatedDimension_));
95  if (useProjectedDistance_)
96  tree_->setDistanceFunction([this](const Motion *a, const Motion *b)
97  {
98  return projectedDistanceFunction(a, b);
99  });
100  else
101  tree_->setDistanceFunction([this](const Motion *a, const Motion *b)
102  {
103  return distanceFunction(a, b);
104  });
105 }
106 
108 {
109  Planner::clear();
110  sampler_.reset();
111  freeMemory();
112  setupTree();
113 }
114 
116 {
117  if (tree_)
118  {
119  std::vector<Motion *> motions;
120  tree_->list(motions);
121  for (auto &motion : motions)
122  {
123  if (motion->state)
124  si_->freeState(motion->state);
125  delete motion;
126  }
127  tree_.reset();
128  }
129 }
130 
132 {
133  checkValidity();
134  base::Goal *goal = pdef_->getGoal().get();
135  auto *goal_s = dynamic_cast<base::GoalSampleableRegion *>(goal);
136 
137  while (const base::State *st = pis_.nextStart())
138  {
139  auto *motion = new Motion(si_);
140  si_->copyState(motion->state, st);
141  addMotion(motion);
142  }
143 
144  if (tree_->size() == 0)
145  {
146  OMPL_ERROR("%s: There are no valid initial states!", getName().c_str());
148  }
149 
150  if (!sampler_)
151  sampler_ = si_->allocValidStateSampler();
152 
153  OMPL_INFORM("%s: Starting planning with %u states already in datastructure", getName().c_str(), tree_->size());
154 
155  Motion *solution = nullptr;
156  Motion *approxsol = nullptr;
157  double approxdif = std::numeric_limits<double>::infinity();
158  base::State *xstate = si_->allocState();
159 
160  while (ptc == false)
161  {
162  /* Decide on a state to expand from */
163  Motion *existing = selectMotion();
164  assert(existing);
165 
166  /* sample random state (with goal biasing) */
167  if (goal_s && rng_.uniform01() < goalBias_ && goal_s->canSample())
168  goal_s->sampleGoal(xstate);
169  else if (!sampler_->sampleNear(xstate, existing->state, maxDistance_))
170  continue;
171 
172  std::pair<base::State *, double> fail(xstate, 0.0);
173  bool keep = si_->checkMotion(existing->state, xstate, fail) || fail.second > minValidPathFraction_;
174 
175  if (keep)
176  {
177  /* create a motion */
178  auto *motion = new Motion(si_);
179  si_->copyState(motion->state, xstate);
180  motion->parent = existing;
181 
182  addMotion(motion);
183  double dist = 0.0;
184  bool solved = goal->isSatisfied(motion->state, &dist);
185  if (solved)
186  {
187  approxdif = dist;
188  solution = motion;
189  break;
190  }
191  if (dist < approxdif)
192  {
193  approxdif = dist;
194  approxsol = motion;
195  }
196  }
197  }
198 
199  bool solved = false;
200  bool approximate = false;
201  if (solution == nullptr)
202  {
203  solution = approxsol;
204  approximate = true;
205  }
206 
207  if (solution != nullptr)
208  {
209  /* construct the solution path */
210  std::vector<Motion *> mpath;
211  while (solution != nullptr)
212  {
213  mpath.push_back(solution);
214  solution = solution->parent;
215  }
216 
217  /* set the solution path */
218  auto path(std::make_shared<PathGeometric>(si_));
219  for (int i = mpath.size() - 1; i >= 0; --i)
220  path->append(mpath[i]->state);
221  pdef_->addSolutionPath(path, approximate, approxdif, getName());
222  solved = true;
223  }
224 
225  si_->freeState(xstate);
226 
227  OMPL_INFORM("%s: Created %u states", getName().c_str(), tree_->size());
228 
229  return {solved, approximate};
230 }
231 
233 {
234  tree_->add(motion);
235 }
236 
238 {
239  return tree_->sample(rng_);
240 }
241 
243 {
244  Planner::getPlannerData(data);
245 
246  std::vector<Motion *> motions;
247  tree_->list(motions);
248  for (auto &motion : motions)
249  {
250  if (motion->parent == nullptr)
251  data.addStartVertex(base::PlannerDataVertex(motion->state, 1));
252  else
253  data.addEdge(base::PlannerDataVertex(motion->parent->state, 1), base::PlannerDataVertex(motion->state, 1));
254  }
255 }
void setMaxDegree(unsigned int maxDegree)
Set maximum degree of a node in the GNAT.
Definition: STRIDE.h:179
void setGoalBias(double goalBias)
In the process of randomly selecting states in the state space to attempt to go towards,...
Definition: STRIDE.h:132
void setDegree(unsigned int degree)
Set desired degree of a node in the GNAT.
Definition: STRIDE.h:159
void configurePlannerRange(double &range)
Compute what a good length for motion segments is.
Definition: SelfConfig.cpp:225
Geometric Near-neighbor Access Tree (GNAT), a data structure for nearest neighbor search.
void setMinValidPathFraction(double fraction)
When extending a motion, the planner can decide to keep the first valid part of it,...
Definition: STRIDE.h:236
Definition of an abstract state.
Definition: State.h:113
base::State * state
The state contained by the motion.
Definition: STRIDE.h:283
This class contains methods that automatically configure various parameters for motion planning....
Definition: SelfConfig.h:123
unsigned int getMaxDegree() const
Set maximum degree of a node in the GNAT.
Definition: STRIDE.h:184
double getGoalBias() const
Get the goal bias the planner is using.
Definition: STRIDE.h:138
void setup() override
Perform extra configuration steps, if needed. This call will also issue a call to ompl::base::SpaceIn...
Definition: STRIDE.cpp:82
void setUseProjectedDistance(bool useProjectedDistance)
Set whether nearest neighbors are computed based on distances in a projection of the state rather dis...
Definition: STRIDE.h:146
#define OMPL_INFORM(fmt,...)
Log a formatted information string.
Definition: Console.h:68
void setEstimatedDimension(double estimatedDimension)
Set estimated dimension of the free space, which is needed to compute the sampling weight for a node ...
Definition: STRIDE.h:203
unsigned int getDegree() const
Get desired degree of a node in the GNAT.
Definition: STRIDE.h:164
base::PlannerStatus solve(const base::PlannerTerminationCondition &ptc) override
Function that can solve the motion planning problem. This function can be called multiple times on th...
Definition: STRIDE.cpp:131
double getRange() const
Get the range the planner is using.
Definition: STRIDE.h:226
Object containing planner generated vertex and edge data. It is assumed that all vertices are unique,...
Definition: PlannerData.h:238
STRIDE(const base::SpaceInformationPtr &si, bool useProjectedDistance=false, unsigned int degree=16, unsigned int minDegree=12, unsigned int maxDegree=18, unsigned int maxNumPtsPerLeaf=6, double estimatedDimension=0.0)
Constructor.
Definition: STRIDE.cpp:46
Encapsulate a termination condition for a motion planner. Planners will call operator() to decide whe...
PlannerSpecs specs_
The specifications of the planner (its capabilities)
Definition: Planner.h:486
void freeMemory()
Free the memory allocated by this planner.
Definition: STRIDE.cpp:115
A class to store the exit status of Planner::solve()
void setRange(double distance)
Set the range the planner is supposed to use.
Definition: STRIDE.h:220
void addMotion(Motion *motion)
Add a motion to the exploration tree.
Definition: STRIDE.cpp:232
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: STRIDE.cpp:242
The definition of a motion.
Definition: STRIDE.h:270
Abstract definition of goals.
Definition: Goal.h:126
double getMinValidPathFraction() const
Get the value of the fraction set by setMinValidPathFraction()
Definition: STRIDE.h:242
unsigned int getMaxNumPtsPerLeaf() const
Get maximum number of elements stored in a leaf node of the GNAT.
Definition: STRIDE.h:196
void setMinDegree(unsigned int minDegree)
Set minimum degree of a node in the GNAT.
Definition: STRIDE.h:169
double estimatedDimension_
Estimate of the local dimensionality of the free space around a state.
Definition: STRIDE.h:345
Motion * selectMotion()
Select a motion to continue the expansion of the tree from.
Definition: STRIDE.cpp:237
double getEstimatedDimension() const
Get estimated dimension of the free space, which is needed to compute the sampling weight for a node ...
Definition: STRIDE.h:210
void setupTree()
Initialize GNAT data structure.
Definition: STRIDE.cpp:91
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...
void configureProjectionEvaluator(base::ProjectionEvaluatorPtr &proj)
If proj is undefined, it is set to the default projection reported by base::StateSpace::getDefaultPro...
Definition: SelfConfig.cpp:231
Motion * parent
The parent motion in the exploration tree.
Definition: STRIDE.h:286
#define OMPL_ERROR(fmt,...)
Log a formatted error string.
Definition: Console.h:64
bool approximateSolutions
Flag indicating whether the planner is able to compute approximate solutions.
Definition: Planner.h:259
void setMaxNumPtsPerLeaf(unsigned int maxNumPtsPerLeaf)
Set maximum number of elements stored in a leaf node of the GNAT.
Definition: STRIDE.h:190
bool getUseProjectedDistance() const
Return whether nearest neighbors are computed based on distances in a projection of the state rather ...
Definition: STRIDE.h:153
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...
Abstract definition of a goal region that can be sampled.
@ INVALID_START
Invalid start state or no start state specified.
void clear() override
Clear all internal datastructures. Planner settings are not affected. Subsequent calls to solve() wil...
Definition: STRIDE.cpp:107
Base class for a vertex in the PlannerData structure. All derived classes must implement the clone an...
Definition: PlannerData.h:122
unsigned int getMinDegree() const
Get minimum degree of a node in the GNAT.
Definition: STRIDE.h:174