Loading...
Searching...
No Matches
TrochoidStateSpace.h
101 TrochoidStateSpace(double turningRadius = 1.0, double windRatio = 0.0, double windDirection = 0.0,
115 static double distance(const State *state1, const State *state2, double radius, double wind_ratio,
117 static double symmetricDistance(const State *state1, const State *state2, double radius, double wind_ratio,
121 virtual void interpolate(const State *from, const State *to, double t, bool &firstTime, PathType &path,
123 virtual void interpolate(const State *from, const PathType &path, double t, State *state, double radius,
142 int flags = ~(STATESPACE_INTERPOLATION | STATESPACE_TRIANGLE_INEQUALITY | STATESPACE_DISTANCE_BOUND);
@ STATESPACE_DISTANCE_BOUND
Check whether the StateSpace::distance() is bounded by StateSpace::getExtent().
Definition StateSpace.h:152
@ STATESPACE_INTERPOLATION
Check whether calling StateSpace::interpolate() works as expected.
Definition StateSpace.h:145
@ STATESPACE_TRIANGLE_INEQUALITY
Check whether the triangle inequality holds when using StateSpace::interpolate() and StateSpace::dist...
Definition StateSpace.h:149
@ STATESPACE_DISTANCE_SYMMETRIC
Check whether the distance function is symmetric (StateSpace::distance()).
Definition StateSpace.h:142
virtual void sanityChecks() const
Convenience function that allows derived state spaces to choose which checks should pass (see SanityC...
Definition StateSpace.cpp:603
double length_[3]
Definition TrochoidStateSpace.h:96
const std::vector< TrochoidPathSegmentType > * type_
Definition TrochoidStateSpace.h:94
An SE(2) state space where distance is measured by the length of Trochoid shortest paths curves.
Definition TrochoidStateSpace.h:60
double distance(const State *state1, const State *state2) const override
Computes distance between two states. This function satisfies the properties of a metric if isMetricS...
Definition TrochoidStateSpace.cpp:795
bool hasSymmetricDistance() const override
Check if the distance function on this state space is symmetric, i.e. distance(s1,...
Definition TrochoidStateSpace.h:126
bool hasSymmetricInterpolate() const override
Check if the interpolation function on this state space is symmetric, i.e. interpolate(from,...
Definition TrochoidStateSpace.h:131
static const std::vector< std::vector< TrochoidPathSegmentType > > & dubinsPathType()
Dubins path types.
Definition TrochoidStateSpace.cpp:782
void sanityChecks() const override
Convenience function that allows derived state spaces to choose which checks should pass (see SanityC...
Definition TrochoidStateSpace.h:138
PathType getPath(const State *state1, const State *state2, bool periodic=false) const
Return a shortest Dubins path from SE(2) state state1 to SE(2) state state2.
Definition TrochoidStateSpace.cpp:911
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....
Definition TrochoidStateSpace.cpp:906
bool isMetricSpace() const override
Return true if the distance function associated with the space is a metric.
Definition TrochoidStateSpace.h:109
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....
Definition TrochoidStateSpace.cpp:812
This namespace contains sampling based planning routines shared by both planning under geometric cons...
Definition ConstrainedSpaceInformation.h:55
Main namespace. Contains everything in this library.
Definition MultiLevelPlanarManipulatorDemo.cpp:66