37 #ifndef OMPL_BASE_SPACES_DUBINS_STATE_SPACE_
38 #define OMPL_BASE_SPACES_DUBINS_STATE_SPACE_
40 #include "ompl/base/spaces/SE2StateSpace.h"
41 #include "ompl/base/MotionValidator.h"
42 #include <boost/math/constants/constants.hpp>
78 double t=0.,
double p=std::numeric_limits<double>::max(),
double q=0.)
116 bool& firstTime, DubinsPath& path,
State *state)
const;
130 double zero = std::numeric_limits<double>::epsilon();
131 double eps = std::numeric_limits<float>::epsilon();
142 virtual void interpolate(
const State *from,
const DubinsPath& path,
const double t,
179 virtual bool checkMotion(
const State *s1,
const State *s2, std::pair<State*, double> &lastValid)
const;
182 void defaultSettings(
void);
virtual double distance(const State *state1, const State *state2) const
Computes distance between two states. This function satisfies the properties of a metric if isMetricS...
virtual bool isMetricSpace(void) const
Return true if the distance function associated with the space is a metric.
Check whether the StateSpace::distance() is bounded by StateSpace::getExtent()
An SE(2) state space where distance is measured by the length of Dubins curves.
DubinsPathSegmentType
The Dubins path segment type.
const DubinsPathSegmentType * type_
virtual bool hasSymmetricInterpolate(void) const
Check if the interpolation function on this state space is symmetric, i.e. interpolate(from, to, t, state) = interpolate(to, from, 1-t, state). Default implementation returns true.
Abstract definition for a class checking the validity of motions – path segments between states...
virtual void interpolate(const State *from, const State *to, const double t, State *state) const
Computes the state that lies at time t in [0, 1] on the segment that connects from state to to state...
A state space representing SE(2)
virtual bool checkMotion(const State *s1, const State *s2) const
Check if the path between two states (from s1 to s2) is valid. This function assumes s1 is valid...
bool isSymmetric_
Whether the distance is "symmetrized".
Definition of an abstract state.
Check whether the triangle inequality holds when using StateSpace::interpolate() and StateSpace::dist...
A Dubins motion validator that only uses the state validity checker. Motions are checked for validity...
virtual void sanityChecks(void) const
Convenience function that allows derived state spaces to choose which checks should pass (see SanityC...
MotionValidator(SpaceInformation *si)
Constructor.
virtual bool hasSymmetricDistance(void) const
Check if the distance function on this state space is symmetric, i.e. distance(s1,s2) = distance(s2,s1). Default implementation returns true.
virtual void sanityChecks(void) const
Convenience function that allows derived state spaces to choose which checks should pass (see SanityC...
Check whether the distance function is symmetric (StateSpace::distance())
Check whether calling StateSpace::interpolate() works as expected.
static const DubinsPathSegmentType dubinsPathType[6][3]
Dubins path types.
DubinsPath dubins(const State *state1, const State *state2) const
Return the shortest Dubins path from SE(2) state state1 to SE(2) state state2.
Complete description of a Dubins path.
double rho_
Turning radius.