Loading...
Searching...
No Matches
ProjEST.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/geometric/planners/est/ProjEST.h"
38#include "ompl/base/goals/GoalSampleableRegion.h"
39#include "ompl/tools/config/SelfConfig.h"
40#include <limits>
41#include <cassert>
42
43ompl::geometric::ProjEST::ProjEST(const base::SpaceInformationPtr &si) : base::Planner(si, "ProjEST")
44{
45 specs_.approximateSolutions = true;
46 specs_.directed = true;
47
48 Planner::declareParam<double>("range", this, &ProjEST::setRange, &ProjEST::getRange, "0.:1.:10000.");
49 Planner::declareParam<double>("goal_bias", this, &ProjEST::setGoalBias, &ProjEST::getGoalBias, "0.:.05:1.");
50}
51
52ompl::geometric::ProjEST::~ProjEST()
53{
54 freeMemory();
55}
56
58{
59 Planner::setup();
63
64 tree_.grid.setDimension(projectionEvaluator_->getDimension());
65}
66
68{
69 Planner::clear();
70 sampler_.reset();
71 freeMemory();
72 tree_.grid.clear();
73 tree_.size = 0;
74 pdf_.clear();
75 lastGoalMotion_ = nullptr;
76}
77
79{
80 for (const auto &it : tree_.grid)
81 {
82 for (auto &motion : it.second->data.motions_)
83 {
84 if (motion->state != nullptr)
85 si_->freeState(motion->state);
86 delete motion;
87 }
88 }
89}
90
92{
94 base::Goal *goal = pdef_->getGoal().get();
95 auto *goal_s = dynamic_cast<base::GoalSampleableRegion *>(goal);
96
97 if (goal_s == nullptr)
98 {
99 OMPL_ERROR("%s: Unknown type of goal", getName().c_str());
101 }
102
103 if (!goal_s->couldSample())
104 {
105 OMPL_ERROR("%s: Insufficient states in sampleable goal region", getName().c_str());
107 }
108
109 while (const base::State *st = pis_.nextStart())
110 {
111 auto *motion = new Motion(si_);
112 si_->copyState(motion->state, st);
113 addMotion(motion);
114 }
115
116 if (tree_.grid.empty())
117 {
118 OMPL_ERROR("%s: There are no valid initial states!", getName().c_str());
120 }
121
122 if (!sampler_)
123 sampler_ = si_->allocValidStateSampler();
124
125 OMPL_INFORM("%s: Starting planning with %u states already in datastructure", getName().c_str(), tree_.size);
126
127 Motion *solution = nullptr;
128 Motion *approxsol = nullptr;
129 double approxdif = std::numeric_limits<double>::infinity();
130 base::State *xstate = si_->allocState();
131
132 while (!ptc)
133 {
134 /* Decide on a state to expand from */
135 Motion *existing = selectMotion();
136 assert(existing);
137
138 /* sample random state (with goal biasing) */
139 if (rng_.uniform01() < goalBias_ && goal_s->canSample())
140 goal_s->sampleGoal(xstate);
141 else if (!sampler_->sampleNear(xstate, existing->state, maxDistance_))
142 continue;
143
144 if (si_->checkMotion(existing->state, xstate))
145 {
146 /* create a motion */
147 auto *motion = new Motion(si_);
148 si_->copyState(motion->state, xstate);
149 motion->parent = existing;
150
151 addMotion(motion);
152 double dist = 0.0;
153 bool solved = goal->isSatisfied(motion->state, &dist);
154 if (solved)
155 {
156 approxdif = dist;
157 solution = motion;
158 break;
159 }
160 if (dist < approxdif)
161 {
162 approxdif = dist;
163 approxsol = motion;
164 }
165 }
166 }
167
168 bool solved = false;
169 bool approximate = false;
170 if (solution == nullptr)
171 {
172 solution = approxsol;
173 approximate = true;
174 }
175
176 if (solution != nullptr)
177 {
178 lastGoalMotion_ = solution;
179
180 /* construct the solution path */
181 std::vector<Motion *> mpath;
182 while (solution != nullptr)
183 {
184 mpath.push_back(solution);
185 solution = solution->parent;
186 }
187
188 /* set the solution path */
189 auto path(std::make_shared<PathGeometric>(si_));
190 for (int i = mpath.size() - 1; i >= 0; --i)
191 path->append(mpath[i]->state);
192 pdef_->addSolutionPath(path, approximate, approxdif, getName());
193 solved = true;
194 }
195
196 si_->freeState(xstate);
197
198 OMPL_INFORM("%s: Created %u states in %u cells", getName().c_str(), tree_.size, tree_.grid.size());
199
200 return {solved, approximate};
201}
202
204{
205 GridCell *cell = pdf_.sample(rng_.uniform01());
206 return (cell != nullptr) && !cell->data.empty() ? cell->data[rng_.uniformInt(0, cell->data.size() - 1)] : nullptr;
207}
208
210{
211 Grid<MotionInfo>::Coord coord(projectionEvaluator_->getDimension());
212 projectionEvaluator_->computeCoordinates(motion->state, coord);
213 GridCell *cell = tree_.grid.getCell(coord);
214 if (cell != nullptr)
215 {
216 cell->data.push_back(motion);
217 pdf_.update(cell->data.elem_, 1.0 / cell->data.size());
218 }
219 else
220 {
221 cell = tree_.grid.createCell(coord);
222 cell->data.push_back(motion);
223 tree_.grid.add(cell);
224 cell->data.elem_ = pdf_.add(cell, 1.0);
225 }
226 tree_.size++;
227}
228
230{
231 Planner::getPlannerData(data);
232
233 std::vector<MotionInfo> motionInfo;
234 tree_.grid.getContent(motionInfo);
235
236 if (lastGoalMotion_ != nullptr)
238
239 for (auto &m : motionInfo)
240 for (auto &motion : m.motions_)
241 {
242 if (motion->parent == nullptr)
243 data.addStartVertex(base::PlannerDataVertex(motion->state));
244 else
245 data.addEdge(base::PlannerDataVertex(motion->parent->state), base::PlannerDataVertex(motion->state));
246 }
247}
Eigen::VectorXi Coord
Definition of a coordinate within this grid.
Definition Grid.h:55
Abstract definition of a goal region that can be sampled.
Abstract definition of goals.
Definition Goal.h:63
virtual bool isSatisfied(const State *st) const =0
Return true if the state satisfies the goal constraints.
Base class for a vertex in the PlannerData structure. All derived classes must implement the clone an...
Definition PlannerData.h:59
Object containing planner generated vertex and edge data. It is assumed that all vertices are unique,...
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...
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...
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...
Encapsulate a termination condition for a motion planner. Planners will call operator() to decide whe...
PlannerInputStates pis_
Utility class to extract valid input states.
Definition Planner.h:407
PlannerSpecs specs_
The specifications of the planner (its capabilities).
Definition Planner.h:413
ProblemDefinitionPtr pdef_
The user set problem definition.
Definition Planner.h:404
const std::string & getName() const
Get the name of the planner.
Definition Planner.cpp:56
SpaceInformationPtr si_
The space information for which planning is done.
Definition Planner.h:401
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:106
Definition of an abstract state.
Definition State.h:50
The definition of a motion.
Definition ProjEST.h:145
Motion * parent
The parent motion in the exploration tree.
Definition ProjEST.h:160
base::State * state
The state contained by the motion.
Definition ProjEST.h:157
TreeData tree_
The exploration tree constructed by this algorithm.
Definition ProjEST.h:223
RNG rng_
The random number generator.
Definition ProjEST.h:237
Grid< MotionInfo >::Cell GridCell
A grid cell.
Definition ProjEST.h:166
Motion * lastGoalMotion_
The most recent goal motion. Used for PlannerData computation.
Definition ProjEST.h:243
double getRange() const
Get the range the planner is using.
Definition ProjEST.h:113
void setup() override
Perform extra configuration steps, if needed. This call will also issue a call to ompl::base::SpaceIn...
Definition ProjEST.cpp:57
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 ProjEST.cpp:91
void addMotion(Motion *motion)
Add a motion to the exploration tree.
Definition ProjEST.cpp:209
CellPDF pdf_
The PDF used for selecting a cell from which to sample a motion.
Definition ProjEST.h:240
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 ProjEST.cpp:229
void freeMemory()
Free the memory allocated by this planner.
Definition ProjEST.cpp:78
base::ProjectionEvaluatorPtr projectionEvaluator_
This algorithm uses a discretization (a grid) to guide the exploration. The exploration is imposed on...
Definition ProjEST.h:227
double goalBias_
The fraction of time the goal is picked as the state to expand towards (if such a state is available)...
Definition ProjEST.h:231
base::ValidStateSamplerPtr sampler_
Valid state sampler.
Definition ProjEST.h:220
double getGoalBias() const
Get the goal bias the planner is using.
Definition ProjEST.h:97
Motion * selectMotion()
Select a motion to continue the expansion of the tree from.
Definition ProjEST.cpp:203
double maxDistance_
The maximum length of a motion to be added to a tree.
Definition ProjEST.h:234
void setGoalBias(double goalBias)
In the process of randomly selecting states in the state space to attempt to go towards,...
Definition ProjEST.h:91
void clear() override
Clear all internal datastructures. Planner settings are not affected. Subsequent calls to solve() wil...
Definition ProjEST.cpp:67
ProjEST(const base::SpaceInformationPtr &si)
Constructor.
Definition ProjEST.cpp:43
void setRange(double distance)
Set the range the planner is supposed to use.
Definition ProjEST.h:107
This class contains methods that automatically configure various parameters for motion planning....
Definition SelfConfig.h:59
void configurePlannerRange(double &range)
Compute what a good length for motion segments is.
void configureProjectionEvaluator(base::ProjectionEvaluatorPtr &proj)
If proj is undefined, it is set to the default projection reported by base::StateSpace::getDefaultPro...
#define OMPL_INFORM(fmt,...)
Log a formatted information string.
Definition Console.h:68
#define OMPL_ERROR(fmt,...)
Log a formatted error string.
Definition Console.h:64
This namespace contains sampling based planning routines shared by both planning under geometric cons...
_T data
The data we store in the cell.
Definition Grid.h:61
A class to store the exit status of Planner::solve().
@ INVALID_START
Invalid start state or no start state specified.
@ INVALID_GOAL
Invalid goal state.
@ UNRECOGNIZED_GOAL_TYPE
The goal is of a type that a planner does not recognize.