Class TrochoidStateSpace
Defined in File TrochoidStateSpace.h
Nested Relationships
Nested Types
Inheritance Relationships
Base Type
public ompl::base::SE2StateSpace
(Class SE2StateSpace)
Class Documentation
-
class TrochoidStateSpace : public ompl::base::SE2StateSpace
An SE(2) state space where distance is measured by the length of Trochoid shortest paths curves.
The notation and solutions in the code are taken from:
Techy, Laszlo, and Craig A. Woolsey. “Minimum-time path planning for unmanned aerial vehicles
in steady uniform winds.” Journal of guidance, control, and dynamics 32.6 (2009): 1736-1746.
The implementation is from adapted from https://github.com/robotics-uncc/ConvectedDubins written by Artur Wolek.
Public Types
Public Functions
-
inline TrochoidStateSpace(double turningRadius = 1.0, double windRatio = 0.0, double windDirection = 0.0, bool isSymmetric = false)
-
inline virtual bool isMetricSpace() const override
Return true if the distance function associated with the space is a metric.
-
virtual double distance(const State *state1, const State *state2) const override
Computes distance between two states. This function satisfies the properties of a metric if isMetricSpace() is true, and its return value will always be between 0 and getMaximumExtent()
-
virtual void interpolate(const State *from, const State *to, double t, State *state) const override
Computes the state that lies at time t in [0, 1] on the segment that connects from state to to state. The memory location of state is not required to be different from the memory of either from or to.
-
virtual void interpolate(const State *from, const State *to, double t, bool &firstTime, PathType &path, State *state) const
-
virtual void interpolate(const State *from, const PathType &path, double t, State *state, double radius, double wind_ratio, double wind_heading) const
-
inline virtual bool hasSymmetricDistance() const override
Check if the distance function on this state space is symmetric, i.e. distance(s1,s2) = distance(s2,s1). Default implementation returns true.
-
inline virtual bool hasSymmetricInterpolate() const override
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.
-
virtual unsigned int validSegmentCount(const State *state1, const State *state2) const override
Count how many segments of the “longest valid length” fit on the motion from state1 to state2. This is the max() of the counts returned by contained subspaces.
-
inline virtual void sanityChecks() const override
Convenience function that allows derived state spaces to choose which checks should pass (see SanityChecks flags) and how strict the checks are. This just calls sanityChecks() with some default arguments.
Public Static Functions
-
static const std::vector<std::vector<TrochoidPathSegmentType>> &dubinsPathType()
Dubins path types.
-
static double distance(const State *state1, const State *state2, double radius, double wind_ratio, double wind_heading)
Protected Attributes
-
double rho_
Turning radius.
-
double eta_
Wind ratio.
-
double psi_w_
Wind direction [0, 2pi].
-
bool isSymmetric_
Whether the distance is “symmetrized”.
If true the distance from state s1 to state s2 is the same as the distance from s2 to s1. This is done by taking the minimum length of the Dubins curves that connect s1 to s2 and s2 to s1. If isSymmetric_ is true, then the distance no longer satisfies the triangle inequality.
-
class PathType
Complete description of a Dubins path.
Public Functions
-
inline PathType(const std::vector<TrochoidPathSegmentType> &type = dubinsPathType()[0], double tA = 0., double p = std::numeric_limits<double>::max(), double tB = 0., double t_2pi = 0.)
-
inline double length() const
Public Members
-
const std::vector<TrochoidPathSegmentType> *type_
Path segment types
-
bool reverse_ = {false}
Whether the path should be followed “in reverse”
-
inline PathType(const std::vector<TrochoidPathSegmentType> &type = dubinsPathType()[0], double tA = 0., double p = std::numeric_limits<double>::max(), double tB = 0., double t_2pi = 0.)
-
inline TrochoidStateSpace(double turningRadius = 1.0, double windRatio = 0.0, double windDirection = 0.0, bool isSymmetric = false)