Program Listing for File ConstrainedStateSpace.h
↰ Return to documentation for file (src/ompl/base/spaces/constraint/ConstrainedStateSpace.h)
/*********************************************************************
* Software License Agreement (BSD License)
*
* Copyright (c) 2017, 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 */
#ifndef OMPL_BASE_SPACES_CONSTRAINED_STATE_SPACE_
#define OMPL_BASE_SPACES_CONSTRAINED_STATE_SPACE_
#include "ompl/base/Constraint.h"
#include "ompl/base/StateSampler.h"
#include "ompl/base/ValidStateSampler.h"
#include "ompl/base/MotionValidator.h"
#include "ompl/base/spaces/WrapperStateSpace.h"
#include "ompl/base/SpaceInformation.h"
#include <Eigen/Core>
namespace ompl
{
namespace magic
{
static const double CONSTRAINED_STATE_SPACE_DELTA = 0.05;
static const double CONSTRAINED_STATE_SPACE_LAMBDA = 2.0;
}
namespace base
{
OMPL_CLASS_FORWARD(ConstrainedStateSpace);
class ConstrainedMotionValidator : public MotionValidator
{
public:
ConstrainedMotionValidator(SpaceInformation *si);
ConstrainedMotionValidator(const SpaceInformationPtr &si);
bool checkMotion(const State *s1, const State *s2) const override;
bool checkMotion(const State *s1, const State *s2, std::pair<State *, double> &lastValid) const override;
protected:
const ConstrainedStateSpace &ss_;
};
class ConstrainedStateSpace : public WrapperStateSpace
{
public:
enum SanityChecks
{
CONSTRAINED_STATESPACE_SAMPLERS = (1 << 1),
CONSTRAINED_STATESPACE_GEODESIC_SATISFY = (1 << 2),
CONSTRAINED_STATESPACE_GEODESIC_CONTINUITY = (1 << 3),
CONSTRAINED_STATESPACE_GEODESIC_INTERPOLATE = (1 << 4),
CONSTRAINED_STATESPACE_JACOBIAN = (1 << 5)
};
class StateType : public WrapperStateSpace::StateType, public Eigen::Map<Eigen::VectorXd>
{
public:
StateType(const ConstrainedStateSpace *space)
: WrapperStateSpace::StateType(space->getSpace()->allocState())
, Eigen::Map<Eigen::VectorXd>(space->getValueAddressAtIndex(this, 0), space->getDimension())
{
}
void copy(const Eigen::Ref<const Eigen::VectorXd> &other)
{
// Explicitly cast and call `=` on the state as an
// Eigen::Map<...>. This copies the other.
static_cast<Eigen::Map<Eigen::VectorXd> *>(this)->operator=(other);
}
};
ConstrainedStateSpace(const StateSpacePtr &ambientSpace, const ConstraintPtr &constraint);
bool isMetricSpace() const override
{
return false;
}
void setSpaceInformation(SpaceInformation *si);
void setup() override;
virtual void clear();
State *allocState() const override;
void constrainedSanityChecks(unsigned int flags) const;
void sanityChecks() const override;
unsigned int validSegmentCount(const State* s1, const State* s2) const override
{
return distance(s1, s2) * (1. / delta_) * lambda_;
}
void interpolate(const State *from, const State *to, double t, State *state) const override;
virtual bool discreteGeodesic(const State *from, const State *to, bool interpolate = false,
std::vector<State *> *geodesic = nullptr) const = 0;
virtual State *geodesicInterpolate(const std::vector<State *> &geodesic, double t) const;
void setDelta(double delta);
void setLambda(double lambda)
{
if (lambda <= 1)
throw ompl::Exception("ompl::base::AtlasStateSpace::setLambda(): "
"lambda must be > 1.");
lambda_ = lambda;
}
double getDelta() const
{
return delta_;
}
double getLambda() const
{
return lambda_;
}
unsigned int getAmbientDimension() const
{
return n_;
}
unsigned int getManifoldDimension() const
{
return k_;
}
const ConstraintPtr getConstraint() const
{
return constraint_;
}
protected:
SpaceInformation *si_{nullptr};
const ConstraintPtr constraint_;
const unsigned int n_;
const unsigned int k_;
double delta_;
double lambda_{ompl::magic::CONSTRAINED_STATE_SPACE_LAMBDA};
bool setup_{false};
};
}
}
#endif