Loading...
Searching...
No Matches
OwenStateSpace.h
1/*********************************************************************
2 * Software License Agreement (BSD License)
3 *
4 * Copyright (c) 2024, Metron, Inc.
5 * All rights reserved.
6 *
7 * Redistribution and use in source and binary forms, with or without
8 * modification, are permitted provided that the following conditions
9 * are met:
10 *
11 * * Redistributions of source code must retain the above copyright
12 * notice, this list of conditions and the following disclaimer.
13 * * Redistributions in binary form must reproduce the above
14 * copyright notice, this list of conditions and the following
15 * disclaimer in the documentation and/or other materials provided
16 * with the distribution.
17 * * Neither the name of the Metron, Inc. nor the names of its
18 * contributors may be used to endorse or promote products derived
19 * from this software without specific prior written permission.
20 *
21 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22 * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23 * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24 * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25 * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26 * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27 * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28 * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30 * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31 * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32 * POSSIBILITY OF SUCH DAMAGE.
33 *********************************************************************/
34
35/* Author: Mark Moll */
36
37#ifndef OMPL_BASE_SPACES_OWEN_STATE_SPACE_
38#define OMPL_BASE_SPACES_OWEN_STATE_SPACE_
39
40#include "ompl/base/spaces/DubinsStateSpace.h"
41#include <optional>
42
43namespace ompl::base
44{
60 class OwenStateSpace : public CompoundStateSpace
61 {
62 public:
63 enum PathCategory : char
64 {
65 LOW_ALTITUDE = 'L',
66 MEDIUM_ALTITUDE = 'M',
67 HIGH_ALTITUDE = 'H',
68 UNKNOWN = '?'
69 };
70
71 class PathType
72 {
73 public:
74 PathType(DubinsStateSpace::PathType const &path, double turnRadius, double deltaZ,
75 unsigned int numTurns = 0)
76 : path_(path), turnRadius_(turnRadius), deltaZ_(deltaZ), numTurns_(numTurns)
77 {
78 }
79 PathType(DubinsStateSpace::PathType const &path, double turnRadius, double deltaZ, double phi)
80 : path_(path), turnRadius_(turnRadius), deltaZ_(deltaZ), phi_(phi)
81 {
82 }
83 double length() const;
84
85 PathCategory category() const;
86
87 friend std::ostream &operator<<(std::ostream &os, const PathType &path);
88
90 double turnRadius_{1.};
91 double deltaZ_;
92 double phi_{0.};
93 unsigned int numTurns_{0};
94 };
95
97 class StateType : public CompoundStateSpace::StateType
98 {
99 public:
100 StateType() = default;
101 double operator[](unsigned index) const
102 {
103 return as<RealVectorStateSpace::StateType>(0)->values[index];
104 }
105 double &operator[](unsigned index)
106 {
107 return as<RealVectorStateSpace::StateType>(0)->values[index];
108 }
109 double yaw() const
110 {
111 return as<SO2StateSpace::StateType>(1)->value;
112 }
113 double &yaw()
114 {
115 return as<SO2StateSpace::StateType>(1)->value;
116 }
117 };
118
119 OwenStateSpace(double turningRadius = 1.0, double maxPitch = boost::math::double_constants::sixth_pi);
120 ~OwenStateSpace() override = default;
121
122 bool isMetricSpace() const override
123 {
124 return false;
125 }
126 bool hasSymmetricDistance() const override
127 {
128 return false;
129 }
130
131 bool hasSymmetricInterpolate() const override
132 {
133 return false;
134 }
135
136 void sanityChecks() const override
137 {
138 double zero = std::numeric_limits<double>::epsilon();
139 double eps = std::numeric_limits<float>::epsilon();
142 StateSpace::sanityChecks(zero, eps, flags);
143 }
144
146 void setBounds(const RealVectorBounds &bounds)
147 {
148 as<RealVectorStateSpace>(0)->setBounds(bounds);
149 }
150
153 {
154 return as<RealVectorStateSpace>(0)->getBounds();
155 }
156
158 void setTolerance(double tolerance)
159 {
160 tolerance_ = tolerance;
161 }
162
164 {
165 return tolerance_;
166 }
167
168 State *allocState() const override;
169 void registerProjections() override;
170
171 double distance(const State *state1, const State *state2) const override;
172
173 unsigned int validSegmentCount(const State *state1, const State *state2) const override;
174
175 void interpolate(const State *from, const State *to, double t, State *state) const override;
188 virtual void interpolate(const State *from, const State *to, double t, PathType &path, State *state) const;
189
197 std::optional<PathType> getPath(const State *state1, const State *state2) const;
198
199 double getMinTurnRadius() const
200 {
201 return rho_;
202 };
203
204 double getMaxPitch() const
205 {
206 return atan(tanMaxPitch_);
207 };
208
209 protected:
213 void turn(const State *from, double turnRadius, double angle, State *state) const;
214
216 double rho_;
220 double tolerance_{1e-8};
223 };
224} // namespace ompl::base
225
226#endif
ompl::base::CompoundState StateType
Define the type of state allocated by this state space.
Definition StateSpace.h:577
CompoundStateSpace()
Construct an empty compound state space.
Complete description of a Dubins path.
An SE(2) state space where distance is measured by the length of Dubins curves.
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....
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...
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....
void registerProjections() override
Register the projections for this state space. Usually, this is at least the default projection....
DubinsStateSpace dubinsSpace_
void setTolerance(double tolerance)
const RealVectorBounds & getBounds() const
Get the bounds for this state space.
bool hasSymmetricDistance() const override
Check if the distance function on this state space is symmetric, i.e. distance(s1,...
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.
void setBounds(const RealVectorBounds &bounds)
Set the bounds of this state space. This defines the range of the space in which sampling is performe...
State * allocState() const override
Allocate a state that can store a point in the described space.
bool hasSymmetricInterpolate() const override
Check if the interpolation function on this state space is symmetric, i.e. interpolate(from,...
void sanityChecks() const override
Convenience function that allows derived state spaces to choose which checks should pass (see SanityC...
void turn(const State *from, double turnRadius, double angle, State *state) const
Compute the SE(2) state after making a turn.
bool isMetricSpace() const override
Return true if the distance function associated with the space is a metric.
The lower and upper bounds for an Rn space.
@ 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
T * as()
Cast this instance to a desired type.
Definition StateSpace.h:87
virtual void sanityChecks() const
Convenience function that allows derived state spaces to choose which checks should pass (see SanityC...
Definition of an abstract state.
Definition State.h:50
const T * as() const
Cast this instance to a desired type.
Definition State.h:66
This namespace contains sampling based planning routines shared by both planning under geometric cons...