Loading...
Searching...
No Matches
VFRRT.cpp
1/*********************************************************************
2 * Software License Agreement (BSD License)
3 *
4 * Copyright (c) 2015, Caleb Voss and Wilson Beebe
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/* Authors: Caleb Voss, Wilson Beebe */
36
37#include <utility>
38
39#include "ompl/geometric/planners/rrt/VFRRT.h"
40#include "ompl/base/goals/GoalSampleableRegion.h"
41
42namespace ompl
43{
44 namespace magic
45 {
47 static const unsigned int VFRRT_MEAN_NORM_SAMPLES = 1000;
48 } // namespace magic
49} // namespace ompl
50
51ompl::geometric::VFRRT::VFRRT(const base::SpaceInformationPtr &si, VectorField vf, double exploration,
52 double initial_lambda, unsigned int update_freq)
53 : RRT(si), vf_(std::move(vf)), explorationSetting_(exploration), lambda_(initial_lambda), nth_step_(update_freq)
54{
55 setName("VFRRT");
56 maxDistance_ = si->getStateValidityCheckingResolution();
57}
58
60
62{
63 RRT::clear();
64 efficientCount_ = 0;
65 inefficientCount_ = 0;
66 explorationInefficiency_ = 0.;
67 step_ = 0;
68}
69
71{
72 RRT::setup();
73 vfdim_ = si_->getStateSpace()->getValueLocations().size();
74}
75
77{
78 ompl::base::State *rstate = si_->allocState();
79 double sum = 0.;
80 for (unsigned int i = 0; i < magic::VFRRT_MEAN_NORM_SAMPLES; i++)
81 {
82 sampler_->sampleUniform(rstate);
83 sum += vf_(rstate).norm();
84 }
85 si_->freeState(rstate);
87}
88
89Eigen::VectorXd ompl::geometric::VFRRT::getNewDirection(const base::State *qnear, const base::State *qrand)
90{
91 // Set vrand to be the normalized vector from qnear to qrand
92 Eigen::VectorXd vrand(vfdim_);
93 for (unsigned int i = 0; i < vfdim_; i++)
94 vrand[i] = *si_->getStateSpace()->getValueAddressAtIndex(qrand, i) -
95 *si_->getStateSpace()->getValueAddressAtIndex(qnear, i);
96 vrand /= si_->distance(qnear, qrand);
97
98 // Get the vector at qnear, and normalize
99 Eigen::VectorXd vfield = vf_(qnear);
100 const double lambdaScale = vfield.norm();
101 // In the case where there is no vector field present, vfield.norm() == 0,
102 // return the direction of the random state.
103 if (lambdaScale < std::numeric_limits<float>::epsilon())
104 return vrand;
105 vfield /= lambdaScale;
106 // Sample a weight from the distribution
107 const double omega = biasedSampling(vrand, vfield, lambdaScale);
108 // Determine updated direction
109 return computeAlphaBeta(omega, vrand, vfield);
110}
111
112double ompl::geometric::VFRRT::biasedSampling(const Eigen::VectorXd &vrand, const Eigen::VectorXd &vfield,
113 double lambdaScale)
114{
115 double sigma = .25 * (vrand - vfield).squaredNorm();
116 updateGain();
117 double scaledLambda = lambda_ * lambdaScale / meanNorm_;
118 double phi = scaledLambda / (1. - std::exp(-2. * scaledLambda));
119 double z = -std::log(1. - sigma * scaledLambda / phi) / scaledLambda;
120 return std::sqrt(2. * z);
121}
122
124{
125 if (step_ == nth_step_)
126 {
127 lambda_ = lambda_ * (1 - explorationInefficiency_ + explorationSetting_);
128 efficientCount_ = inefficientCount_ = 0;
129 explorationInefficiency_ = 0;
130 step_ = 0;
131 }
132 else
133 step_++;
134}
135
136Eigen::VectorXd ompl::geometric::VFRRT::computeAlphaBeta(double omega, const Eigen::VectorXd &vrand,
137 const Eigen::VectorXd &vfield)
138{
139 double w2 = omega * omega;
140 double c = vfield.dot(vrand);
141 double cc_1 = c * c - 1.;
142 double root = std::sqrt(cc_1 * w2 * (w2 - 4.));
143 double beta = -root / (2. * cc_1);
144 double sign = (beta < 0.) ? -1. : 1.;
145 beta *= sign;
146 double alpha = (sign * c * root + cc_1 * (2. - w2)) / (2. * cc_1);
147 return alpha * vfield + beta * vrand;
148}
149
151 const Eigen::VectorXd &v)
152{
153 base::State *newState = si_->allocState();
154 si_->copyState(newState, m->state);
155
156 double d = si_->distance(m->state, rstate);
157 if (d > maxDistance_)
158 d = maxDistance_;
159
160 const base::StateSpacePtr &space = si_->getStateSpace();
161 for (unsigned int i = 0; i < vfdim_; i++)
162 *space->getValueAddressAtIndex(newState, i) += d * v[i];
163 if (!v.hasNaN() && si_->checkMotion(m->state, newState))
164 {
165 auto *motion = new Motion();
166 motion->state = newState;
167 motion->parent = m;
169 nn_->add(motion);
170 return motion;
171 }
172 else
173 {
174 si_->freeState(newState);
175 inefficientCount_++;
176 return nullptr;
177 }
178}
179
181{
182 Motion *near = nn_->nearest(m);
183 if (distanceFunction(m, near) < si_->getStateValidityCheckingResolution())
184 inefficientCount_++;
185 else
186 efficientCount_++;
187 explorationInefficiency_ = inefficientCount_ / (double)(efficientCount_ + inefficientCount_);
188}
189
191{
193 base::Goal *goal = pdef_->getGoal().get();
194 auto *goal_s = dynamic_cast<base::GoalSampleableRegion *>(goal);
195
196 if (!sampler_)
197 sampler_ = si_->allocStateSampler();
198
199 meanNorm_ = determineMeanNorm();
200
201 while (const base::State *st = pis_.nextStart())
202 {
203 auto *motion = new Motion(si_);
204 si_->copyState(motion->state, st);
205 nn_->add(motion);
206 }
207
208 if (nn_->size() == 0)
209 {
210 OMPL_ERROR("%s: There are no valid initial states!", getName().c_str());
212 }
213
214 OMPL_INFORM("%s: Starting planning with %u states already in datastructure", getName().c_str(), nn_->size());
215
216 Motion *solution = nullptr;
217 Motion *approxsol = nullptr;
218 double approxdif = std::numeric_limits<double>::infinity();
219 auto *rmotion = new Motion(si_);
220 base::State *rstate = rmotion->state;
221 base::State *xstate = si_->allocState();
222
223 while (ptc == false)
224 {
225 // Sample random state (with goal biasing)
226 if (goal_s && rng_.uniform01() < goalBias_ && goal_s->canSample())
227 goal_s->sampleGoal(rstate);
228 else
229 sampler_->sampleUniform(rstate);
230
231 // Find closest state in the tree
232 Motion *nmotion = nn_->nearest(rmotion);
233
234 // Modify direction based on vector field before extending
235 Motion *motion = extendTree(nmotion, rstate, getNewDirection(nmotion->state, rstate));
236 if (!motion)
237 continue;
238
239 // Check if we can connect to the goal
240 double dist = 0;
241 bool sat = goal->isSatisfied(motion->state, &dist);
242 if (sat)
243 {
244 approxdif = dist;
245 solution = motion;
246 break;
247 }
248 if (dist < approxdif)
249 {
250 approxdif = dist;
251 approxsol = motion;
252 }
253 }
254
255 bool solved = false;
256 bool approximate = false;
257 if (solution == nullptr)
258 {
259 solution = approxsol;
260 approximate = true;
261 }
262
263 if (solution != nullptr)
264 {
265 lastGoalMotion_ = solution;
266
267 // Construct the solution path
268 std::vector<Motion *> mpath;
269 while (solution != nullptr)
270 {
271 mpath.push_back(solution);
272 solution = solution->parent;
273 }
274
275 // Set the solution path
276 auto path(std::make_shared<PathGeometric>(si_));
277 for (int i = mpath.size() - 1; i >= 0; --i)
278 path->append(mpath[i]->state);
279 pdef_->addSolutionPath(path, approximate, approxdif, name_);
280 solved = true;
281 }
282
283 si_->freeState(xstate);
284 if (rmotion->state)
285 si_->freeState(rmotion->state);
286 delete rmotion;
287
288 OMPL_INFORM("%s: Created %u states", getName().c_str(), nn_->size());
289
290 return {solved, approximate};
291}
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.
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
ProblemDefinitionPtr pdef_
The user set problem definition.
Definition Planner.h:404
std::string name_
The name of this planner.
Definition Planner.h:410
void setName(const std::string &name)
Set the name of the planner.
Definition Planner.cpp:61
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
Representation of a motion.
Definition RRT.h:148
Motion * parent
The parent motion in the exploration tree.
Definition RRT.h:163
base::State * state
The state contained by the motion.
Definition RRT.h:160
RNG rng_
The random number generator.
Definition RRT.h:192
void setup() override
Perform extra configuration steps, if needed. This call will also issue a call to ompl::base::SpaceIn...
Definition RRT.cpp:71
base::StateSamplerPtr sampler_
State sampler.
Definition RRT.h:176
double distanceFunction(const Motion *a, const Motion *b) const
Compute distance between motions (actually distance between contained states).
Definition RRT.h:170
RRT(const base::SpaceInformationPtr &si, bool addIntermediateStates=false)
Constructor.
Definition RRT.cpp:42
void clear() override
Clear all internal datastructures. Planner settings are not affected. Subsequent calls to solve() wil...
Definition RRT.cpp:61
double maxDistance_
The maximum length of a motion to be added to a tree.
Definition RRT.h:186
Motion * lastGoalMotion_
The most recent goal motion. Used for PlannerData computation.
Definition RRT.h:195
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:183
std::shared_ptr< NearestNeighbors< Motion * > > nn_
A nearest-neighbors datastructure containing the tree of motions.
Definition RRT.h:179
double biasedSampling(const Eigen::VectorXd &vrand, const Eigen::VectorXd &vfield, double lambdaScale)
Definition VFRRT.cpp:112
VFRRT(const base::SpaceInformationPtr &si, VectorField vf, double exploration, double initial_lambda, unsigned int update_freq)
Definition VFRRT.cpp:51
double determineMeanNorm()
Definition VFRRT.cpp:76
base::PlannerStatus solve(const base::PlannerTerminationCondition &ptc) override
Definition VFRRT.cpp:190
void clear() override
Definition VFRRT.cpp:61
Eigen::VectorXd getNewDirection(const base::State *qnear, const base::State *qrand)
Definition VFRRT.cpp:89
void setup() override
Perform extra configuration steps, if needed. This call will also issue a call to ompl::base::SpaceIn...
Definition VFRRT.cpp:70
Motion * extendTree(Motion *m, base::State *rstate, const Eigen::VectorXd &v)
Definition VFRRT.cpp:150
void updateExplorationEfficiency(Motion *m)
Definition VFRRT.cpp:180
Eigen::VectorXd computeAlphaBeta(double omega, const Eigen::VectorXd &vrand, const Eigen::VectorXd &vfield)
Definition VFRRT.cpp:136
#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 includes magic constants used in various places in OMPL.
Definition Constraint.h:52
static const unsigned int VFRRT_MEAN_NORM_SAMPLES
Number of sampler to determine mean vector field norm in gVFRRT.
Definition VFRRT.cpp:47
Main namespace. Contains everything in this library.
STL namespace.
A class to store the exit status of Planner::solve().
@ INVALID_START
Invalid start state or no start state specified.