DubinsStateSpace.h
135 int flags = ~(STATESPACE_INTERPOLATION | STATESPACE_TRIANGLE_INEQUALITY | STATESPACE_DISTANCE_BOUND);
145 virtual void interpolate(const State *from, const DubinsPath &path, double t, State *state) const;
171 defaultSettings();
179 bool checkMotion(const State *s1, const State *s2, std::pair<State *, double> &lastValid) const override;
@ STATESPACE_DISTANCE_SYMMETRIC
Check whether the distance function is symmetric (StateSpace::distance())
Definition: StateSpace.h:206
bool hasSymmetricInterpolate() const override
Check if the interpolation function on this state space is symmetric, i.e. interpolate(from,...
Definition: DubinsStateSpace.h:222
double length_[3]
Definition: DubinsStateSpace.h:195
A shared pointer wrapper for ompl::base::SpaceInformation.
void sanityChecks() const override
Convenience function that allows derived state spaces to choose which checks should pass (see SanityC...
Definition: DubinsStateSpace.h:227
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: DubinsStateSpace.cpp:221
bool hasSymmetricDistance() const override
Check if the distance function on this state space is symmetric, i.e. distance(s1,...
Definition: DubinsStateSpace.h:217
virtual void sanityChecks() const
Convenience function that allows derived state spaces to choose which checks should pass (see SanityC...
Definition: StateSpace.cpp:603
DubinsPath dubins(const State *state1, const State *state2) const
Return a shortest Dubins path from SE(2) state state1 to SE(2) state state2.
Definition: DubinsStateSpace.cpp:321
@ STATESPACE_DISTANCE_BOUND
Check whether the StateSpace::distance() is bounded by StateSpace::getExtent()
Definition: StateSpace.h:216
static const DubinsPathSegmentType dubinsPathType[6][3]
Dubins path types.
Definition: DubinsStateSpace.h:171
Abstract definition for a class checking the validity of motions – path segments between states....
Definition: MotionValidator.h:128
bool checkMotion(const State *s1, const State *s2) const override
Check if the path between two states (from s1 to s2) is valid. This function assumes s1 is valid.
Definition: DubinsStateSpace.cpp:386
@ STATESPACE_TRIANGLE_INEQUALITY
Check whether the triangle inequality holds when using StateSpace::interpolate() and StateSpace::dist...
Definition: StateSpace.h:213
const DubinsPathSegmentType * type_
Definition: DubinsStateSpace.h:193
An SE(2) state space where distance is measured by the length of Dubins curves.
Definition: DubinsStateSpace.h:128
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: DubinsStateSpace.cpp:214
A Dubins motion validator that only uses the state validity checker. Motions are checked for validity...
Definition: DubinsStateSpace.h:230
bool isMetricSpace() const override
Return true if the distance function associated with the space is a metric.
Definition: DubinsStateSpace.h:206
@ STATESPACE_INTERPOLATION
Check whether calling StateSpace::interpolate() works as expected.
Definition: StateSpace.h:209
Main namespace. Contains everything in this library.
Definition: MultiLevelPlanarManipulatorDemo.cpp:65