Program Listing for File ReedsSheppStateSpace.h
↰ Return to documentation for file (src/ompl/base/spaces/ReedsSheppStateSpace.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_REEDS_SHEPP_STATE_SPACE_
#define OMPL_BASE_SPACES_REEDS_SHEPP_STATE_SPACE_
#include "ompl/base/spaces/SE2StateSpace.h"
#include "ompl/base/MotionValidator.h"
#include <boost/math/constants/constants.hpp>
namespace ompl
{
namespace base
{
class ReedsSheppStateSpace : public SE2StateSpace
{
public:
enum ReedsSheppPathSegmentType
{
RS_NOP = 0,
RS_LEFT = 1,
RS_STRAIGHT = 2,
RS_RIGHT = 3
};
static const ReedsSheppPathSegmentType reedsSheppPathType[18][5];
class ReedsSheppPath
{
public:
ReedsSheppPath(const ReedsSheppPathSegmentType *type = reedsSheppPathType[0],
double t = std::numeric_limits<double>::max(), double u = 0., double v = 0.,
double w = 0., double x = 0.);
double length() const
{
return totalLength_;
}
const ReedsSheppPathSegmentType *type_;
double length_[5];
double totalLength_;
};
ReedsSheppStateSpace(double turningRadius = 1.0) : rho_(turningRadius)
{
setName("ReedsShepp" + getName());
type_ = STATE_SPACE_REEDS_SHEPP;
}
double distance(const State *state1, const State *state2) const override;
unsigned int validSegmentCount(const State *state1, const State *state2) const override
{
return longestValidSegmentCountFactor_ *
(unsigned int)ceil(distance(state1, state2) / longestValidSegment_);
}
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,
ReedsSheppPath &path, State *state) const;
void sanityChecks() const override
{
double zero = std::numeric_limits<double>::epsilon();
double eps = .1; // rarely such a large error will occur
StateSpace::sanityChecks(zero, eps, ~STATESPACE_INTERPOLATION);
}
ReedsSheppPath reedsShepp(const State *state1, const State *state2) const;
protected:
virtual void interpolate(const State *from, const ReedsSheppPath &path, double t, State *state) const;
double rho_;
};
class ReedsSheppMotionValidator : public MotionValidator
{
public:
ReedsSheppMotionValidator(SpaceInformation *si) : MotionValidator(si)
{
defaultSettings();
}
ReedsSheppMotionValidator(const SpaceInformationPtr &si) : MotionValidator(si)
{
defaultSettings();
}
~ReedsSheppMotionValidator() 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:
ReedsSheppStateSpace *stateSpace_;
void defaultSettings();
};
}
}
#endif