Loading...
Searching...
No Matches
AtlasStateSpace.h
1/*********************************************************************
2 * Software License Agreement (BSD License)
3 *
4 * Copyright (c) 2014, 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: Zachary Kingston, Caleb Voss */
36
37#ifndef OMPL_BASE_SPACES_ATLAS_STATE_SPACE_
38#define OMPL_BASE_SPACES_ATLAS_STATE_SPACE_
39
40#include "ompl/base/StateSampler.h"
41#include "ompl/base/ValidStateSampler.h"
42#include "ompl/base/Constraint.h"
43#include "ompl/datastructures/NearestNeighborsGNAT.h"
44#include "ompl/datastructures/PDF.h"
45
46#include "ompl/base/spaces/constraint/ConstrainedStateSpace.h"
47
48#include <boost/math/constants/constants.hpp>
49
50namespace ompl
51{
52 namespace magic
53 {
54 static const unsigned int ATLAS_STATE_SPACE_SAMPLES = 50;
55 static const double ATLAS_STATE_SPACE_EPSILON = 0.05;
56 static const double ATLAS_STATE_SPACE_RHO_MULTIPLIER = 5;
57 static const double ATLAS_STATE_SPACE_ALPHA = boost::math::constants::pi<double>() / 8.0;
58 static const double ATLAS_STATE_SPACE_EXPLORATION = 0.75;
59 static const unsigned int ATLAS_STATE_SPACE_MAX_CHARTS_PER_EXTENSION = 200;
60 static const double ATLAS_STATE_SPACE_BACKOFF = 0.75;
61 } // namespace magic
62
63 namespace base
64 {
66
67 OMPL_CLASS_FORWARD(AtlasChart);
69
71
72 OMPL_CLASS_FORWARD(AtlasStateSpace);
74
76 class AtlasStateSampler : public StateSampler
77 {
78 public:
80
83 void sampleUniform(State *state) override;
84
88 void sampleUniformNear(State *state, const State *near, double distance) override;
89
92 void sampleGaussian(State *state, const State *mean, double stdDev) override;
93
94 private:
96 const AtlasStateSpace *atlas_;
97
99 mutable RNG rng_;
100 };
101
125
129 {
130 public:
131 using AtlasChartBiasFunction = std::function<double(AtlasChart *)>;
132 using NNElement = std::pair<const StateType *, std::size_t>;
133
137 {
138 public:
143
146 {
147 return chart_;
148 }
149
151 void setChart(AtlasChart *c) const
152 {
153 chart_ = c;
154 }
155
156 private:
158 mutable AtlasChart *chart_{nullptr};
159 };
160
162 AtlasStateSpace(const StateSpacePtr &ambientSpace, const ConstraintPtr &constraint, bool separate = true);
163
165 ~AtlasStateSpace() override;
166
168 void clear() override;
169
172 {
173 return std::make_shared<AtlasStateSampler>(this);
174 }
175
178 {
179 return std::make_shared<AtlasStateSampler>(this);
180 }
181
182 void copyState(State *destination, const State *source) const override
183 {
184 ConstrainedStateSpace::copyState(destination, source);
185 destination->as<StateType>()->setChart(source->as<StateType>()->getChart());
186 }
187
189 State *allocState() const override
190 {
191 return new StateType(this);
192 }
193
196
200 void setEpsilon(double epsilon)
201 {
202 if (epsilon <= 0)
203 throw ompl::Exception("ompl::base::AtlasStateSpace::setEpsilon(): "
204 "epsilon must be positive.");
205 epsilon_ = epsilon;
206 }
207
210 void setRho(double rho)
211 {
212 if (rho <= 0)
213 throw ompl::Exception("ompl::base::AtlasStateSpace::setRho(): "
214 "rho must be positive.");
215 rho_ = rho;
216 rho_s_ = rho_ / std::pow(1 - exploration_, 1.0 / k_);
217 }
218
222 void setAlpha(double alpha)
223 {
224 if (alpha <= 0 || alpha >= boost::math::constants::pi<double>() / 2.)
225 throw ompl::Exception("ompl::base::AtlasStateSpace::setAlpha(): "
226 "alpha must be in (0, pi/2).");
227 cos_alpha_ = std::cos(alpha);
228 }
229
235 void setExploration(double exploration)
236 {
237 if (exploration >= 1)
238 throw ompl::Exception("ompl::base::AtlasStateSpace::setExploration(): "
239 "exploration must be in [0, 1).");
240 exploration_ = exploration;
241
242 // Update sampling radius
243 setRho(rho_);
244 }
245
249 void setMaxChartsPerExtension(unsigned int charts)
250 {
251 maxChartsPerExtension_ = charts;
252 }
253
255 void setBiasFunction(const AtlasChartBiasFunction &biasFunction)
256 {
257 biasFunction_ = biasFunction;
258 }
259
261 void setSeparated(bool separate)
262 {
263 separate_ = separate;
264 }
265
267 void setBackoff(double backoff)
268 {
269 backoff_ = backoff;
270 }
271
273 double getEpsilon() const
274 {
275 return epsilon_;
276 }
277
279 double getRho() const
280 {
281 return rho_;
282 }
283
285 double getAlpha() const
286 {
287 return std::acos(cos_alpha_);
288 }
289
291 double getExploration() const
292 {
293 return exploration_;
294 }
295
297 double getRho_s() const
298 {
299 return rho_s_;
300 }
301
303 unsigned int getMaxChartsPerExtension() const
304 {
306 }
307
309 bool isSeparated() const
310 {
311 return separate_;
312 }
313
315 std::size_t getChartCount() const
316 {
317 return charts_.size();
318 }
319
321 double getBackoff() const
322 {
323 return backoff_;
324 }
325
327
330
333 AtlasChart *newChart(const StateType *state) const;
334
336 AtlasChart *sampleChart() const;
337
340 AtlasChart *owningChart(const StateType *state) const;
341
347 AtlasChart *getChart(const StateType *state, bool force = false, bool *created = nullptr) const;
348
350
353
357 AtlasChart *anchorChart(const State *state) const;
358
367 bool discreteGeodesic(const State *from, const State *to, bool interpolate = false,
368 std::vector<State *> *geodesic = nullptr) const override;
369
371
374
378 double estimateFrontierPercent() const;
379
381 void printPLY(std::ostream &out) const;
382
384
385 protected:
387 mutable std::vector<StateType *> anchors_;
388
390 mutable std::vector<AtlasChart *> charts_;
391
394
398
401
403 double epsilon_{ompl::magic::ATLAS_STATE_SPACE_EPSILON};
404
406 double rho_;
407
410
413
415 mutable double rho_s_;
416
418 double backoff_{ompl::magic::ATLAS_STATE_SPACE_BACKOFF};
419
421 unsigned int maxChartsPerExtension_{ompl::magic::ATLAS_STATE_SPACE_MAX_CHARTS_PER_EXTENSION};
422
424
426 AtlasChartBiasFunction biasFunction_;
427
430
432 mutable RNG rng_;
433 };
434 } // namespace base
435} // namespace ompl
436
437#endif
The exception type for ompl.
Definition Exception.h:47
Geometric Near-neighbor Access Tree (GNAT), a data structure for nearest neighbor search.
A container that supports probabilistic sampling over weighted data.
Definition PDF.h:49
Random number generation. An instance of this class cannot be used by multiple threads at once (membe...
Tangent space and bounding polytope approximating some patch of the manifold.
Definition AtlasChart.h:53
void sampleUniform(State *state) override
Sample a state uniformly from the charted regions of the manifold. Return sample in state.
void sampleGaussian(State *state, const State *mean, double stdDev) override
Sample a state uniformly from a normal distribution with given mean and stdDev. Return sample in stat...
AtlasStateSampler(const AtlasStateSpace *space)
AtlasStateSampler.
void sampleUniformNear(State *state, const State *near, double distance) override
Sample a state uniformly from the ball with center near and radius distance. Return sample in state.
A state in an atlas represented as a real vector in ambient space and a chart that it belongs to.
AtlasChart * getChart() const
Get the chart this state is on.
StateType(const ConstrainedStateSpace *space)
Construct state of size n.
void setChart(AtlasChart *c) const
Set the chart c for the state.
ConstrainedStateSpace encapsulating a planner-agnostic atlas algorithm for planning on a constraint m...
bool isSeparated() const
Returns whether the atlas is separating charts or not.
void clear() override
Reset the space (except for anchor charts).
std::vector< StateType * > anchors_
Set of states on which there are anchored charts.
~AtlasStateSpace() override
Destructor.
unsigned int maxChartsPerExtension_
Maximum number of charts that can be created in one manifold traversal.
StateSamplerPtr allocStateSampler() const override
Allocate the previously set state sampler for this space.
AtlasChart * sampleChart() const
Pick a chart at random.
double estimateFrontierPercent() const
Estimate what percentage of atlas charts do not have fully formed polytope boundaries,...
double cos_alpha_
Cosine of the maximum angle between a chart and the manifold inside its validity region.
AtlasChart * owningChart(const StateType *state) const
Find the chart to which x belongs. Returns nullptr if no chart found. Assumes x is already on the man...
double getRho() const
Get rho.
PDF< AtlasChart * > chartPDF_
PDF of charts according to a bias function.
double getRho_s() const
Get the sampling radius.
double getExploration() const
Get the exploration parameter.
std::vector< AtlasChart * > charts_
Set of charts.
void copyState(State *destination, const State *source) const override
Copy a state to another. The memory of source and destination should NOT overlap.
void setRho(double rho)
Set rho, the maximum radius for which a chart is valid. Default 0.1.
double getAlpha() const
Get alpha.
double getBackoff() const
Returns the current backoff factor used in manifold traversal.
void printPLY(std::ostream &out) const
Write a mesh representation of the atlas to a stream.
bool discreteGeodesic(const State *from, const State *to, bool interpolate=false, std::vector< State * > *geodesic=nullptr) const override
Traverse the manifold from from toward to. Returns true if we reached to, and false if we stopped ear...
AtlasChart * anchorChart(const State *state) const
Wrapper for newChart(). Charts created this way will persist through calls to clear().
double epsilon_
Maximum distance between a chart and the manifold inside its validity region.
double rho_s_
Sampling radius within a chart. Inferred from rho and exploration parameters.
void setExploration(double exploration)
Set the exploration parameter, which tunes the balance of refinement (sampling within known regions) ...
std::size_t getChartCount() const
Return the number of charts currently in the atlas.
double backoff_
Step size reduction factor during manifold traversal.
NearestNeighborsGNAT< NNElement > chartNN_
Set of chart centers and indices, accessible by nearest-neighbor queries to the chart centers.
void setMaxChartsPerExtension(unsigned int charts)
Sometimes manifold traversal creates many charts. This parameter limits the number of charts that can...
void setBiasFunction(const AtlasChartBiasFunction &biasFunction)
Sets bias function for sampling.
RNG rng_
Random number generator.
double exploration_
Balance between explorationa and refinement.
AtlasChartBiasFunction biasFunction_
Function to bias chart sampling.
void setSeparated(bool separate)
Sets whether the atlas should separate charts or not.
AtlasStateSpace(const StateSpacePtr &ambientSpace, const ConstraintPtr &constraint, bool separate=true)
Construct an atlas with the specified dimensions.
void setAlpha(double alpha)
Set alpha, the maximum permissible angle between the chart and the manifold inside the validity regio...
void setEpsilon(double epsilon)
Set epsilon, the maximum permissible distance between a point in the validity region of a chart and i...
AtlasChart * newChart(const StateType *state) const
Create a new chart for the atlas, centered at xorigin, which should be on the manifold....
StateSamplerPtr allocDefaultStateSampler() const override
Allocate the default state sampler for this space.
double getEpsilon() const
Get epsilon.
unsigned int getMaxChartsPerExtension() const
Get the maximum number of charts to create in one pass.
bool separate_
Enable or disable halfspace separation of the charts.
double rho_
Maximum radius of chart validity region.
State * allocState() const override
Allocate a new state in this space.
void setBackoff(double backoff)
Sets the backoff factor in manifold traversal factor.
AtlasChart * getChart(const StateType *state, bool force=false, bool *created=nullptr) const
Wrapper to return chart state belongs to. Will attempt to initialize new chart if state does not belo...
A State in a ConstrainedStateSpace, represented as a dense real vector of values. For convenience and...
void interpolate(const State *from, const State *to, double t, State *state) const override
Find a state between from and to around time t, where t = 0 is from, and t = 1 is the final state rea...
ConstrainedStateSpace(const StateSpacePtr &ambientSpace, const ConstraintPtr &constraint)
Construct a constrained space from an ambientSpace and a constraint.
const unsigned int k_
Manifold dimension.
A shared pointer wrapper for ompl::base::Constraint.
A shared pointer wrapper for ompl::base::StateSampler.
A shared pointer wrapper for ompl::base::StateSpace.
ompl::base::State StateType
Define the type of state allocated by this space.
Definition StateSpace.h:78
Definition of an abstract state.
Definition State.h:50
const T * as() const
Cast this instance to a desired type.
Definition State.h:66
void copyState(State *destination, const State *source) const override
Copy a state to another. The memory of source and destination should NOT overlap.
This namespace contains sampling based planning routines shared by both planning under geometric cons...
This namespace includes magic constants used in various places in OMPL.
Definition Constraint.h:52
Main namespace. Contains everything in this library.