KPIECE1.cpp
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2010, Rice University
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 Rice University 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/kpiece/KPIECE1.h"
38 #include "ompl/base/goals/GoalSampleableRegion.h"
39 #include "ompl/tools/config/SelfConfig.h"
40 #include "ompl/util/Exception.h"
41 #include <limits>
42 #include <cassert>
43 
44 ompl::control::KPIECE1::KPIECE1(const SpaceInformationPtr &si) : base::Planner(si, "KPIECE1")
45 {
47 
48  siC_ = si.get();
50 
51  Planner::declareParam<double>("goal_bias", this, &KPIECE1::setGoalBias, &KPIECE1::getGoalBias, "0.:.05:1.");
52  Planner::declareParam<double>("border_fraction", this, &KPIECE1::setBorderFraction, &KPIECE1::getBorderFraction,
53  "0.:0.05:1.");
54  Planner::declareParam<unsigned int>("max_close_samples", this, &KPIECE1::setMaxCloseSamplesCount,
56  Planner::declareParam<double>("bad_score_factor", this, &KPIECE1::setBadCellScoreFactor,
58  Planner::declareParam<double>("good_score_factor", this, &KPIECE1::setGoodCellScoreFactor,
60 }
61 
62 ompl::control::KPIECE1::~KPIECE1()
63 {
64  freeMemory();
65 }
66 
68 {
69  Planner::setup();
70  tools::SelfConfig sc(si_, getName());
71  sc.configureProjectionEvaluator(projectionEvaluator_);
72 
73  if (badScoreFactor_ < std::numeric_limits<double>::epsilon() || badScoreFactor_ > 1.0)
74  throw Exception("Bad cell score factor must be in the range (0,1]");
75  if (goodScoreFactor_ < std::numeric_limits<double>::epsilon() || goodScoreFactor_ > 1.0)
76  throw Exception("Good cell score factor must be in the range (0,1]");
77  if (selectBorderFraction_ < std::numeric_limits<double>::epsilon() || selectBorderFraction_ > 1.0)
78  throw Exception("The fraction of time spent selecting border cells must be in the range (0,1]");
79 
80  tree_.grid.setDimension(projectionEvaluator_->getDimension());
81 }
82 
84 {
85  Planner::clear();
86  controlSampler_.reset();
87  freeMemory();
88  tree_.grid.clear();
89  tree_.size = 0;
90  tree_.iteration = 1;
91  lastGoalMotion_ = nullptr;
92 }
93 
95 {
96  freeGridMotions(tree_.grid);
97 }
98 
100 {
101  for (const auto &it : grid)
102  freeCellData(it.second->data);
103 }
104 
106 {
107  for (auto &motion : cdata->motions)
108  freeMotion(motion);
109  delete cdata;
110 }
111 
113 {
114  if (motion->state)
115  si_->freeState(motion->state);
116  if (motion->control)
117  siC_->freeControl(motion->control);
118  delete motion;
119 }
120 
122 {
123  if (samples.empty())
124  {
125  CloseSample cs(cell, motion, distance);
126  samples.insert(cs);
127  return true;
128  }
129  // if the sample we're considering is closer to the goal than the worst sample in the
130  // set of close samples, we include it
131  if (samples.rbegin()->distance > distance)
132  {
133  // if the inclusion would go above the maximum allowed size,
134  // remove the last element
135  if (samples.size() >= maxSize)
136  samples.erase(--samples.end());
137  CloseSample cs(cell, motion, distance);
138  samples.insert(cs);
139  return true;
140  }
141 
142  return false;
143 }
144 
146 // this is the factor by which distances are inflated when considered for addition to closest samples
147 static const double CLOSE_MOTION_DISTANCE_INFLATION_FACTOR = 1.1;
149 
151 {
152  if (samples.size() > 0)
153  {
154  scell = samples.begin()->cell;
155  smotion = samples.begin()->motion;
156  // average the highest & lowest distances and multiply by CLOSE_MOTION_DISTANCE_INFLATION_FACTOR
157  // (make the distance appear artificially longer)
158  double d =
159  (samples.begin()->distance + samples.rbegin()->distance) * (CLOSE_MOTION_DISTANCE_INFLATION_FACTOR / 2.0);
160  samples.erase(samples.begin());
161  consider(scell, smotion, d);
162  return true;
163  }
164  return false;
165 }
166 
167 unsigned int ompl::control::KPIECE1::findNextMotion(const std::vector<Grid::Coord> &coords, unsigned int index,
168  unsigned int count)
169 {
170  for (unsigned int i = index + 1; i < count; ++i)
171  if (coords[i] != coords[index])
172  return i - 1;
173 
174  return count - 1;
175 }
176 
178 {
179  checkValidity();
180  base::Goal *goal = pdef_->getGoal().get();
181 
182  while (const base::State *st = pis_.nextStart())
183  {
184  auto *motion = new Motion(siC_);
185  si_->copyState(motion->state, st);
186  siC_->nullControl(motion->control);
187  addMotion(motion, 1.0);
188  }
189 
190  if (tree_.grid.size() == 0)
191  {
192  OMPL_ERROR("%s: There are no valid initial states!", getName().c_str());
194  }
195 
196  if (!controlSampler_)
197  controlSampler_ = siC_->allocControlSampler();
198 
199  OMPL_INFORM("%s: Starting planning with %u states already in datastructure", getName().c_str(), tree_.size);
200 
201  Motion *solution = nullptr;
202  Motion *approxsol = nullptr;
203  double approxdif = std::numeric_limits<double>::infinity();
204 
205  Control *rctrl = siC_->allocControl();
206 
207  std::vector<base::State *> states(siC_->getMaxControlDuration() + 1);
208  std::vector<Grid::Coord> coords(states.size(), Grid::Coord(projectionEvaluator_->getDimension()));
209  std::vector<Grid::Cell *> cells(coords.size());
210 
211  for (auto &state : states)
212  state = si_->allocState();
213 
214  // samples that were found to be the best, so far
215  CloseSamples closeSamples(nCloseSamples_);
216 
217  while (ptc == false)
218  {
219  tree_.iteration++;
220 
221  /* Decide on a state to expand from */
222  Motion *existing = nullptr;
223  Grid::Cell *ecell = nullptr;
224 
225  if (closeSamples.canSample() && rng_.uniform01() < goalBias_)
226  {
227  if (!closeSamples.selectMotion(existing, ecell))
228  selectMotion(existing, ecell);
229  }
230  else
231  selectMotion(existing, ecell);
232  assert(existing);
233 
234  /* sample a random control */
235  controlSampler_->sampleNext(rctrl, existing->control, existing->state);
236 
237  /* propagate */
238  unsigned int cd =
239  controlSampler_->sampleStepCount(siC_->getMinControlDuration(), siC_->getMaxControlDuration());
240  cd = siC_->propagateWhileValid(existing->state, rctrl, cd, states, false);
241 
242  /* if we have enough steps */
243  if (cd >= siC_->getMinControlDuration())
244  {
245  std::size_t avgCov_two_thirds = (2 * tree_.size) / (3 * tree_.grid.size());
246  bool interestingMotion = false;
247 
248  // split the motion into smaller ones, so we do not cross cell boundaries
249  for (unsigned int i = 0; i < cd; ++i)
250  {
251  projectionEvaluator_->computeCoordinates(states[i], coords[i]);
252  cells[i] = tree_.grid.getCell(coords[i]);
253  if (!cells[i])
254  interestingMotion = true;
255  else
256  {
257  if (!interestingMotion && cells[i]->data->motions.size() <= avgCov_two_thirds)
258  interestingMotion = true;
259  }
260  }
261 
262  if (interestingMotion || rng_.uniform01() < 0.05)
263  {
264  unsigned int index = 0;
265  while (index < cd)
266  {
267  unsigned int nextIndex = findNextMotion(coords, index, cd);
268  auto *motion = new Motion(siC_);
269  si_->copyState(motion->state, states[nextIndex]);
270  siC_->copyControl(motion->control, rctrl);
271  motion->steps = nextIndex - index + 1;
272  motion->parent = existing;
273 
274  double dist = 0.0;
275  bool solv = goal->isSatisfied(motion->state, &dist);
276  Grid::Cell *toCell = addMotion(motion, dist);
277 
278  if (solv)
279  {
280  approxdif = dist;
281  solution = motion;
282  break;
283  }
284  if (dist < approxdif)
285  {
286  approxdif = dist;
287  approxsol = motion;
288  }
289 
290  closeSamples.consider(toCell, motion, dist);
291 
292  // new parent will be the newly created motion
293  existing = motion;
294  index = nextIndex + 1;
295  }
296 
297  if (solution)
298  break;
299  }
300 
301  // update cell score
302  ecell->data->score *= goodScoreFactor_;
303  }
304  else
305  ecell->data->score *= badScoreFactor_;
306 
307  tree_.grid.update(ecell);
308  }
309 
310  bool solved = false;
311  bool approximate = false;
312  if (solution == nullptr)
313  {
314  solution = approxsol;
315  approximate = true;
316  }
317 
318  if (solution != nullptr)
319  {
320  lastGoalMotion_ = solution;
321 
322  /* construct the solution path */
323  std::vector<Motion *> mpath;
324  while (solution != nullptr)
325  {
326  mpath.push_back(solution);
327  solution = solution->parent;
328  }
329 
330  /* set the solution path */
331  auto path(std::make_shared<PathControl>(si_));
332  for (int i = mpath.size() - 1; i >= 0; --i)
333  if (mpath[i]->parent)
334  path->append(mpath[i]->state, mpath[i]->control, mpath[i]->steps * siC_->getPropagationStepSize());
335  else
336  path->append(mpath[i]->state);
337 
338  pdef_->addSolutionPath(path, approximate, approxdif, getName());
339  solved = true;
340  }
341 
342  siC_->freeControl(rctrl);
343  for (auto &state : states)
344  si_->freeState(state);
345 
346  OMPL_INFORM("%s: Created %u states in %u cells (%u internal + %u external)", getName().c_str(), tree_.size,
347  tree_.grid.size(), tree_.grid.countInternal(), tree_.grid.countExternal());
348 
349  return {solved, approximate};
350 }
351 
353 {
354  scell = rng_.uniform01() < std::max(selectBorderFraction_, tree_.grid.fracExternal()) ? tree_.grid.topExternal() :
355  tree_.grid.topInternal();
356 
357  // We are running on finite precision, so our update scheme will end up
358  // with 0 values for the score. This is where we fix the problem
359  if (scell->data->score < std::numeric_limits<double>::epsilon())
360  {
361  OMPL_DEBUG("%s: Numerical precision limit reached. Resetting costs.", getName().c_str());
362  std::vector<CellData *> content;
363  content.reserve(tree_.grid.size());
364  tree_.grid.getContent(content);
365  for (auto &it : content)
366  it->score += 1.0 + log((double)(it->iteration));
367  tree_.grid.updateAll();
368  }
369 
370  if (scell && !scell->data->motions.empty())
371  {
372  scell->data->selections++;
373  smotion = scell->data->motions[rng_.halfNormalInt(0, scell->data->motions.size() - 1)];
374  return true;
375  }
376  else
377  return false;
378 }
379 
381 // this is the offset added to estimated distances to the goal, so we avoid division by 0
382 static const double DISTANCE_TO_GOAL_OFFSET = 1e-3;
384 
386 {
387  Grid::Coord coord(projectionEvaluator_->getDimension());
388  projectionEvaluator_->computeCoordinates(motion->state, coord);
389  Grid::Cell *cell = tree_.grid.getCell(coord);
390  if (cell)
391  {
392  cell->data->motions.push_back(motion);
393  cell->data->coverage += motion->steps;
394  tree_.grid.update(cell);
395  }
396  else
397  {
398  cell = tree_.grid.createCell(coord);
399  cell->data = new CellData();
400  cell->data->motions.push_back(motion);
401  cell->data->coverage = motion->steps;
402  cell->data->iteration = tree_.iteration;
403  cell->data->selections = 1;
404  cell->data->score = (1.0 + log((double)(tree_.iteration))) / (DISTANCE_TO_GOAL_OFFSET + dist);
405  tree_.grid.add(cell);
406  }
407  tree_.size++;
408  return cell;
409 }
410 
412 {
413  Planner::getPlannerData(data);
414 
415  Grid::CellArray cells;
416  tree_.grid.getCells(cells);
417 
418  double delta = siC_->getPropagationStepSize();
419 
420  if (lastGoalMotion_)
421  data.addGoalVertex(base::PlannerDataVertex(lastGoalMotion_->state));
422 
423  for (auto &cell : cells)
424  {
425  for (const auto &m : cell->data->motions)
426  {
427  if (m->parent)
428  {
429  if (data.hasControls())
430  data.addEdge(base::PlannerDataVertex(m->parent->state),
431  base::PlannerDataVertex(m->state, cell->border ? 2 : 1),
432  control::PlannerDataEdgeControl(m->control, m->steps * delta));
433  else
434  data.addEdge(base::PlannerDataVertex(m->parent->state),
435  base::PlannerDataVertex(m->state, cell->border ? 2 : 1));
436  }
437  else
438  data.addStartVertex(base::PlannerDataVertex(m->state, cell->border ? 2 : 1));
439 
440  // A state created as a parent first may have an improper tag variable
441  data.tagState(m->state, cell->border ? 2 : 1);
442  }
443  }
444 }
Control * control
The control contained by this motion.
Definition: KPIECE1.h:312
Information about a known good sample (closer to the goal than others)
Definition: KPIECE1.h:366
void freeCellData(CellData *cdata)
Free the memory for the data contained in a grid cell.
Definition: KPIECE1.cpp:105
bool canSample() const
Return true if samples can be selected from this set.
Definition: KPIECE1.h:413
Definition of an abstract control.
Definition: Control.h:111
A shared pointer wrapper for ompl::base::SpaceInformation.
base::State * state
The state contained by this motion.
Definition: KPIECE1.h:309
Representation of an edge in PlannerData for planning with controls. This structure encodes a specifi...
Definition: PlannerData.h:124
std::vector< Motion * > motions
The set of motions contained in this grid cell.
Definition: KPIECE1.h:329
void setMaxCloseSamplesCount(unsigned int nCloseSamples)
When motions reach close to the goal, they are stored in a separate queue to allow biasing towards th...
Definition: KPIECE1.h:260
void setGoodCellScoreFactor(double good)
Set the factor that is to be applied to a cell's score when an expansion from that cell succeedes.
Definition: KPIECE1.h:239
Definition of an abstract state.
Definition: State.h:113
This class contains methods that automatically configure various parameters for motion planning....
Definition: SelfConfig.h:123
void onCellUpdate(EventCellUpdate event, void *arg)
Definition: GridB.h:163
Bounded set of good samples.
Definition: KPIECE1.h:391
Grid::Cell * addMotion(Motion *motion, double dist)
Add a motion to the grid containing motions. As a hint, dist specifies the distance to the goal from ...
Definition: KPIECE1.cpp:385
double getGoalBias() const
Definition: KPIECE1.h:196
void setBorderFraction(double bp)
Set the fraction of time for focusing on the border (between 0 and 1). This is the minimum fraction u...
Definition: KPIECE1.h:207
double getGoodCellScoreFactor() const
Get the factor that is multiplied to a cell's score if extending a motion from that cell succeeded.
Definition: KPIECE1.h:246
Motion * parent
The parent motion in the exploration tree.
Definition: KPIECE1.h:318
Grid grid
A grid containing motions, imposed on a projection of the state space.
Definition: KPIECE1.h:432
void log(const char *file, int line, LogLevel level, const char *m,...)
Root level logging function. This should not be invoked directly, but rather used via a logging macro...
Definition: Console.cpp:120
bool tagState(const State *st, int tag)
Set the integer tag associated with the given state. If the given state does not exist in a vertex,...
static void computeImportance(Grid::Cell *cell, void *)
This function is provided as a calback to the grid datastructure to update the importance of a cell.
Definition: KPIECE1.h:445
#define OMPL_INFORM(fmt,...)
Log a formatted information string.
Definition: Console.h:68
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: KPIECE1.cpp:411
double getBadCellScoreFactor() const
Get the factor that is multiplied to a cell's score if extending a motion from that cell failed.
Definition: KPIECE1.h:253
bool consider(Grid::Cell *cell, Motion *motion, double distance)
Evaluate whether motion motion, part of cell cell is good enough to be part of the set of samples clo...
Definition: KPIECE1.cpp:121
typename GridN< CellData * >::CellArray CellArray
The datatype for arrays of cells.
Definition: GridB.h:122
TreeData tree_
The tree datastructure.
Definition: KPIECE1.h:487
void freeMotion(Motion *motion)
Free the memory for a motion.
Definition: KPIECE1.cpp:112
Object containing planner generated vertex and edge data. It is assumed that all vertices are unique,...
Definition: PlannerData.h:238
Representation of a motion for this algorithm.
Definition: KPIECE1.h:296
void freeGridMotions(Grid &grid)
Free the memory for the motions contained in a grid.
Definition: KPIECE1.cpp:99
Encapsulate a termination condition for a motion planner. Planners will call operator() to decide whe...
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: KPIECE1.cpp:177
PlannerSpecs specs_
The specifications of the planner (its capabilities)
Definition: Planner.h:486
bool selectMotion(Motion *&smotion, Grid::Cell *&scell)
Select the top sample (closest to the goal) and update its position in the set subsequently (pretend ...
Definition: KPIECE1.cpp:150
unsigned int getMaxCloseSamplesCount() const
Get the maximum number of samples to store in the queue of samples that are close to the goal.
Definition: KPIECE1.h:266
Eigen::VectorXi Coord
Definition of a coordinate within this grid.
Definition: Grid.h:119
void setBadCellScoreFactor(double bad)
Set the factor that is to be applied to a cell's score when an expansion from that cell fails.
Definition: KPIECE1.h:232
bool selectMotion(Motion *&smotion, Grid::Cell *&scell)
Select a motion and the cell it is part of from the grid of motions. This is where preference is give...
Definition: KPIECE1.cpp:352
A class to store the exit status of Planner::solve()
typename GridN< CellData * >::Cell Cell
Definition of a cell in this grid.
Definition: GridB.h:119
void setup() override
Perform extra configuration steps, if needed. This call will also issue a call to ompl::base::SpaceIn...
Definition: KPIECE1.cpp:67
void setGoalBias(double goalBias)
Definition: KPIECE1.h:190
Definition of a cell in this grid.
Definition: Grid.h:122
unsigned int findNextMotion(const std::vector< Grid::Coord > &coords, unsigned int index, unsigned int count)
When generated motions are to be added to the tree of motions, they often need to be split,...
Definition: KPIECE1.cpp:167
virtual bool isSatisfied(const State *st) const =0
Return true if the state satisfies the goal constraints.
The data held by a cell in the grid of motions.
Definition: KPIECE1.h:322
Abstract definition of goals.
Definition: Goal.h:126
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
#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
KPIECE1(const SpaceInformationPtr &si)
Constructor.
Definition: KPIECE1.cpp:44
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 addGoalVertex(const PlannerDataVertex &v)
Adds the given vertex to the graph data, and marks it as a start vertex. The vertex index is returned...
void freeMemory()
Free all the memory allocated by this planner.
Definition: KPIECE1.cpp:94
_T data
The data we store in the cell.
Definition: Grid.h:125
The exception type for ompl.
Definition: Exception.h:78
@ INVALID_START
Invalid start state or no start state specified.
unsigned int steps
The number of steps the control is applied for.
Definition: KPIECE1.h:315
const SpaceInformation * siC_
The base::SpaceInformation cast as control::SpaceInformation, for convenience.
Definition: KPIECE1.h:490
#define OMPL_DEBUG(fmt,...)
Log a formatted debugging string.
Definition: Console.h:70
Base class for a vertex in the PlannerData structure. All derived classes must implement the clone an...
Definition: PlannerData.h:122
virtual bool hasControls() const
Indicate whether any information about controls (ompl::control::Control) is stored in this instance.
double getBorderFraction() const
Get the fraction of time to focus exploration on boundary.
Definition: KPIECE1.h:214
void clear() override
Clear all internal datastructures. Planner settings are not affected. Subsequent calls to solve() wil...
Definition: KPIECE1.cpp:83