Program Listing for File DubinsStateSpace.h
↰ Return to documentation for file (src/ompl/base/spaces/DubinsStateSpace.h)
/*********************************************************************
* Software License Agreement (BSD License)
*
* Copyright (c) 2010, 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: Mark Moll */
#ifndef OMPL_BASE_SPACES_DUBINS_STATE_SPACE_
#define OMPL_BASE_SPACES_DUBINS_STATE_SPACE_
#include <vector>
#include "ompl/base/spaces/SE2StateSpace.h"
#include "ompl/base/MotionValidator.h"
#include <boost/math/constants/constants.hpp>
namespace ompl
{
namespace base
{
class DubinsStateSpace : public SE2StateSpace
{
public:
enum DubinsPathSegmentType
{
DUBINS_LEFT = 0,
DUBINS_STRAIGHT = 1,
DUBINS_RIGHT = 2
};
static const std::vector<std::vector<DubinsPathSegmentType>>& dubinsPathType();
class DubinsPath
{
public:
DubinsPath(const std::vector<DubinsPathSegmentType>& type = dubinsPathType()[0],
double t = 0., double p = std::numeric_limits<double>::max(), double q = 0.)
: type_(&type)
{
length_[0] = t;
length_[1] = p;
length_[2] = q;
assert(t >= 0.);
assert(p >= 0.);
assert(q >= 0.);
}
double length() const
{
return length_[0] + length_[1] + length_[2];
}
friend std::ostream& operator<<(std::ostream& os, const DubinsPath& path);
const std::vector<DubinsPathSegmentType> *type_;
double length_[3];
bool reverse_{false};
};
DubinsStateSpace(double turningRadius = 1.0, bool isSymmetric = false)
: rho_(turningRadius), isSymmetric_(isSymmetric)
{
setName("Dubins" + getName());
type_ = STATE_SPACE_DUBINS;
}
bool isMetricSpace() const override
{
return false;
}
double distance(const State *state1, const State *state2) const override;
static double distance(const State *state1, const State *state2, double radius);
static double symmetricDistance(const State *state1, const State *state2, double radius);
void interpolate(const State *from, const State *to, double t, State *state) const override;
virtual void interpolate(const State *from, const State *to, double t, bool &firstTime,
DubinsPath &path, State *state) const;
virtual void interpolate(const State *from, const DubinsPath &path, double t, State *state, double radius) const;
bool hasSymmetricDistance() const override
{
return isSymmetric_;
}
bool hasSymmetricInterpolate() const override
{
return isSymmetric_;
}
unsigned int validSegmentCount(const State *state1, const State *state2) const override;
void sanityChecks() const override
{
double zero = std::numeric_limits<double>::epsilon();
double eps = std::numeric_limits<float>::epsilon();
int flags = ~(STATESPACE_INTERPOLATION | STATESPACE_TRIANGLE_INEQUALITY | STATESPACE_DISTANCE_BOUND);
if (!isSymmetric_)
flags &= ~STATESPACE_DISTANCE_SYMMETRIC;
StateSpace::sanityChecks(zero, eps, flags);
}
DubinsPath dubins(const State *state1, const State *state2) const;
static DubinsPath dubins(const State *state1, const State *state2, double radius);
protected:
double rho_;
bool isSymmetric_;
};
class DubinsMotionValidator : public MotionValidator
{
public:
DubinsMotionValidator(SpaceInformation *si) : MotionValidator(si)
{
defaultSettings();
}
DubinsMotionValidator(const SpaceInformationPtr &si) : MotionValidator(si)
{
defaultSettings();
}
~DubinsMotionValidator() override = default;
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;
private:
DubinsStateSpace *stateSpace_;
void defaultSettings();
};
}
}
#endif