OwenStateSpace.h
119 OwenStateSpace(double turningRadius = 1.0, double maxPitch = boost::math::double_constants::sixth_pi);
140 int flags = ~(STATESPACE_INTERPOLATION | STATESPACE_TRIANGLE_INEQUALITY | STATESPACE_DISTANCE_BOUND |
161 }
188 virtual void interpolate(const State *from, const State *to, double t, PathType &path, State *state) const;
@ STATESPACE_DISTANCE_SYMMETRIC
Check whether the distance function is symmetric (StateSpace::distance())
Definition: StateSpace.h:206
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: OwenStateSpace.cpp:192
State * allocState() const override
Allocate a state that can store a point in the described space.
Definition: OwenStateSpace.cpp:67
void setBounds(const RealVectorBounds &bounds)
Set the bounds of this state space. This defines the range of the space in which sampling is performe...
Definition: OwenStateSpace.h:210
bool hasSymmetricDistance() const override
Check if the distance function on this state space is symmetric, i.e. distance(s1,...
Definition: OwenStateSpace.h:190
const RealVectorBounds & getBounds() const
Get the bounds for this state space.
Definition: OwenStateSpace.h:216
This namespace contains sampling based planning routines shared by both planning under geometric cons...
Definition: ConstrainedSpaceInformation.h:86
virtual void sanityChecks() const
Convenience function that allows derived state spaces to choose which checks should pass (see SanityC...
Definition: StateSpace.cpp:603
@ STATESPACE_DISTANCE_BOUND
Check whether the StateSpace::distance() is bounded by StateSpace::getExtent()
Definition: StateSpace.h:216
void registerProjections() override
Register the projections for this state space. Usually, this is at least the default projection....
Definition: OwenStateSpace.cpp:74
@ STATESPACE_TRIANGLE_INEQUALITY
Check whether the triangle inequality holds when using StateSpace::interpolate() and StateSpace::dist...
Definition: StateSpace.h:213
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: OwenStateSpace.cpp:197
void setTolerance(double tolerance)
Definition: OwenStateSpace.h:222
An SE(2) state space where distance is measured by the length of Dubins curves.
Definition: DubinsStateSpace.h:126
DubinsStateSpace dubinsSpace_
Definition: OwenStateSpace.h:276
bool isMetricSpace() const override
Return true if the distance function associated with the space is a metric.
Definition: OwenStateSpace.h:186
void turn(const State *from, double turnRadius, double angle, State *state) const
Compute the SE(2) state after making a turn.
Definition: OwenStateSpace.cpp:176
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: OwenStateSpace.cpp:185
std::optional< PathType > getPath(const State *state1, const State *state2) const
Compute a 3D Dubins path using the model and algorithm proposed by Owen et al.
Definition: OwenStateSpace.cpp:107
ompl::base::CompoundState StateType
Define the type of state allocated by this state space.
Definition: StateSpace.h:641
bool hasSymmetricInterpolate() const override
Check if the interpolation function on this state space is symmetric, i.e. interpolate(from,...
Definition: OwenStateSpace.h:195
@ STATESPACE_INTERPOLATION
Check whether calling StateSpace::interpolate() works as expected.
Definition: StateSpace.h:209
void sanityChecks() const override
Convenience function that allows derived state spaces to choose which checks should pass (see SanityC...
Definition: OwenStateSpace.h:200
The lower and upper bounds for an Rn space.
Definition: RealVectorBounds.h:111