Program Listing for File AtlasStateSpace.h
↰ Return to documentation for file (src/ompl/base/spaces/constraint/AtlasStateSpace.h)
/*********************************************************************
* Software License Agreement (BSD License)
*
* Copyright (c) 2014, Rice University
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* * Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* * Redistributions in binary form must reproduce the above
* copyright notice, this list of conditions and the following
* disclaimer in the documentation and/or other materials provided
* with the distribution.
* * Neither the name of the Rice University nor the names of its
* contributors may be used to endorse or promote products derived
* from this software without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*********************************************************************/
/* Author: Zachary Kingston, Caleb Voss */
#ifndef OMPL_BASE_SPACES_ATLAS_STATE_SPACE_
#define OMPL_BASE_SPACES_ATLAS_STATE_SPACE_
#include "ompl/base/StateSampler.h"
#include "ompl/base/ValidStateSampler.h"
#include "ompl/base/Constraint.h"
#include "ompl/datastructures/NearestNeighborsGNAT.h"
#include "ompl/datastructures/PDF.h"
#include "ompl/base/spaces/constraint/ConstrainedStateSpace.h"
#include <boost/math/constants/constants.hpp>
namespace ompl
{
namespace magic
{
static const unsigned int ATLAS_STATE_SPACE_SAMPLES = 50;
static const double ATLAS_STATE_SPACE_EPSILON = 0.05;
static const double ATLAS_STATE_SPACE_RHO_MULTIPLIER = 5;
static const double ATLAS_STATE_SPACE_ALPHA = boost::math::constants::pi<double>() / 8.0;
static const double ATLAS_STATE_SPACE_EXPLORATION = 0.75;
static const unsigned int ATLAS_STATE_SPACE_MAX_CHARTS_PER_EXTENSION = 200;
static const double ATLAS_STATE_SPACE_BACKOFF = 0.75;
}
namespace base
{
OMPL_CLASS_FORWARD(AtlasChart);
OMPL_CLASS_FORWARD(AtlasStateSpace);
class AtlasStateSampler : public StateSampler
{
public:
AtlasStateSampler(const AtlasStateSpace *space);
void sampleUniform(State *state) override;
void sampleUniformNear(State *state, const State *near, double distance) override;
void sampleGaussian(State *state, const State *mean, double stdDev) override;
private:
const AtlasStateSpace *atlas_;
mutable RNG rng_;
};
class AtlasStateSpace : public ConstrainedStateSpace
{
public:
using AtlasChartBiasFunction = std::function<double(AtlasChart *)>;
using NNElement = std::pair<const StateType *, std::size_t>;
class StateType : public ConstrainedStateSpace::StateType
{
public:
StateType(const ConstrainedStateSpace *space) : ConstrainedStateSpace::StateType(space)
{
}
AtlasChart *getChart() const
{
return chart_;
}
void setChart(AtlasChart *c) const
{
chart_ = c;
}
private:
mutable AtlasChart *chart_{nullptr};
};
AtlasStateSpace(const StateSpacePtr &ambientSpace, const ConstraintPtr &constraint, bool separate = true);
~AtlasStateSpace() override;
void clear() override;
StateSamplerPtr allocDefaultStateSampler() const override
{
return std::make_shared<AtlasStateSampler>(this);
}
StateSamplerPtr allocStateSampler() const override
{
return std::make_shared<AtlasStateSampler>(this);
}
void copyState(State *destination, const State *source) const override
{
ConstrainedStateSpace::copyState(destination, source);
destination->as<StateType>()->setChart(source->as<StateType>()->getChart());
}
State *allocState() const override
{
return new StateType(this);
}
void setEpsilon(double epsilon)
{
if (epsilon <= 0)
throw ompl::Exception("ompl::base::AtlasStateSpace::setEpsilon(): "
"epsilon must be positive.");
epsilon_ = epsilon;
}
void setRho(double rho)
{
if (rho <= 0)
throw ompl::Exception("ompl::base::AtlasStateSpace::setRho(): "
"rho must be positive.");
rho_ = rho;
rho_s_ = rho_ / std::pow(1 - exploration_, 1.0 / k_);
}
void setAlpha(double alpha)
{
if (alpha <= 0 || alpha >= boost::math::constants::pi<double>() / 2.)
throw ompl::Exception("ompl::base::AtlasStateSpace::setAlpha(): "
"alpha must be in (0, pi/2).");
cos_alpha_ = std::cos(alpha);
}
void setExploration(double exploration)
{
if (exploration >= 1)
throw ompl::Exception("ompl::base::AtlasStateSpace::setExploration(): "
"exploration must be in [0, 1).");
exploration_ = exploration;
// Update sampling radius
setRho(rho_);
}
void setMaxChartsPerExtension(unsigned int charts)
{
maxChartsPerExtension_ = charts;
}
void setBiasFunction(const AtlasChartBiasFunction &biasFunction)
{
biasFunction_ = biasFunction;
}
void setSeparated(bool separate)
{
separate_ = separate;
}
void setBackoff(double backoff)
{
backoff_ = backoff;
}
double getEpsilon() const
{
return epsilon_;
}
double getRho() const
{
return rho_;
}
double getAlpha() const
{
return std::acos(cos_alpha_);
}
double getExploration() const
{
return exploration_;
}
double getRho_s() const
{
return rho_s_;
}
unsigned int getMaxChartsPerExtension() const
{
return maxChartsPerExtension_;
}
bool isSeparated() const
{
return separate_;
}
std::size_t getChartCount() const
{
return charts_.size();
}
double getBackoff() const
{
return backoff_;
}
AtlasChart *newChart(const StateType *state) const;
AtlasChart *sampleChart() const;
AtlasChart *owningChart(const StateType *state) const;
AtlasChart *getChart(const StateType *state, bool force = false, bool *created = nullptr) const;
AtlasChart *anchorChart(const State *state) const;
bool discreteGeodesic(const State *from, const State *to, bool interpolate = false,
std::vector<State *> *geodesic = nullptr) const override;
double estimateFrontierPercent() const;
void printPLY(std::ostream &out) const;
protected:
mutable std::vector<StateType *> anchors_;
mutable std::vector<AtlasChart *> charts_;
mutable PDF<AtlasChart *> chartPDF_;
mutable NearestNeighborsGNAT<NNElement> chartNN_;
double epsilon_{ompl::magic::ATLAS_STATE_SPACE_EPSILON};
double rho_;
double cos_alpha_;
double exploration_;
mutable double rho_s_;
double backoff_{ompl::magic::ATLAS_STATE_SPACE_BACKOFF};
unsigned int maxChartsPerExtension_{ompl::magic::ATLAS_STATE_SPACE_MAX_CHARTS_PER_EXTENSION};
AtlasChartBiasFunction biasFunction_;
bool separate_;
mutable RNG rng_;
};
}
}
#endif