Loading...
Searching...
No Matches
OwenStateSpace.cpp
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#include "ompl/base/spaces/OwenStateSpace.h"
38#include "ompl/base/spaces/Dubins3DMotionValidator.h"
39#include "ompl/base/SpaceInformation.h"
40#include "ompl/tools/config/MagicConstants.h"
41#include "ompl/util/Exception.h"
42#include <boost/math/tools/toms748_solve.hpp>
43
44using namespace ompl::base;
45
46namespace
47{
48 constexpr double twopi = 2. * boost::math::constants::pi<double>();
49
50 // tolerance for boost root finding algorithm
51 const boost::math::tools::eps_tolerance<double> TOLERANCE(20);
52
53 // max # iterations for searching for roots
54 constexpr std::uintmax_t MAX_ITER = 32;
55} // namespace
56
57OwenStateSpace::OwenStateSpace(double turningRadius, double maxPitch)
58 : rho_(turningRadius), tanMaxPitch_(std::tan(maxPitch)), dubinsSpace_(turningRadius)
59{
60 setName("Owen" + getName());
61 type_ = STATE_SPACE_OWEN;
62 addSubspace(std::make_shared<RealVectorStateSpace>(3), 1.0);
63 addSubspace(std::make_shared<SO2StateSpace>(), 0.5);
64 lock();
65}
66
68{
69 auto *state = new StateType();
71 return state;
72}
73
75{
76 class OwenDefaultProjection : public ProjectionEvaluator
77 {
78 public:
79 OwenDefaultProjection(const StateSpace *space) : ProjectionEvaluator(space)
80 {
81 }
82
83 unsigned int getDimension() const override
84 {
85 return 3;
86 }
87
88 void defaultCellSizes() override
89 {
90 cellSizes_.resize(3);
91 bounds_ = space_->as<OwenStateSpace>()->getBounds();
92 cellSizes_[0] = (bounds_.high[0] - bounds_.low[0]) / magic::PROJECTION_DIMENSION_SPLITS;
93 cellSizes_[1] = (bounds_.high[1] - bounds_.low[1]) / magic::PROJECTION_DIMENSION_SPLITS;
94 cellSizes_[2] = (bounds_.high[2] - bounds_.low[2]) / magic::PROJECTION_DIMENSION_SPLITS;
95 }
96
97 void project(const State *state, Eigen::Ref<Eigen::VectorXd> projection) const override
98 {
99 projection = Eigen::Map<const Eigen::VectorXd>(
101 }
102 };
103
104 registerDefaultProjection(std::make_shared<OwenDefaultProjection>(this));
105}
106
107std::optional<OwenStateSpace::PathType> OwenStateSpace::getPath(const State *state1, const State *state2) const
108{
109 auto s1 = state1->as<StateType>();
110 auto s2 = state2->as<StateType>();
111 auto path = dubinsSpace_.getPath(state1, state2, rho_);
112 double dz = (*s2)[2] - (*s1)[2], len = rho_ * path.length();
113 if (std::abs(dz) <= len * tanMaxPitch_)
114 {
115 // low altitude path
116 return PathType{path, rho_, dz};
117 }
118 else if (std::abs(dz) > (len + twopi * rho_) * tanMaxPitch_)
119 {
120 // high altitude path
121 unsigned int k = std::floor((std::abs(dz) / tanMaxPitch_ - len) / (twopi * rho_));
122 auto radius = rho_;
123 auto radiusFun = [&, this](double r)
124 { return (dubinsSpace_.getPath(state1, state2, r).length() + twopi * k) * r * tanMaxPitch_ - std::abs(dz); };
125 std::uintmax_t iter = MAX_ITER;
126 auto result = boost::math::tools::bracket_and_solve_root(radiusFun, radius, 2., true, TOLERANCE, iter);
127 radius = .5 * (result.first + result.second);
128 // Discontinuities in the Dubins distance and, by extension, radiusFun can cause bracket_and_solve_root to fail.
129 if (std::abs(radiusFun(radius)) > 1e-5)
130 return {};
131 path = dubinsSpace_.getPath(state1, state2, radius);
132 return PathType{path, radius, dz, k};
133 }
134
135 // medium altitude path
136 {
137 auto zi = dubinsSpace_.allocState()->as<DubinsStateSpace::StateType>();
138 auto phi = 0.1;
139 auto phiFun = [&, this](double phi)
140 {
141 turn(state1, rho_, phi, zi);
142 return (std::abs(phi) + dubinsSpace_.getPath(zi, state2).length()) * rho_ * tanMaxPitch_ - std::abs(dz);
143 };
144
145 try
146 {
147 std::uintmax_t iter = MAX_ITER;
148 auto result = boost::math::tools::bracket_and_solve_root(phiFun, phi, 2., true, TOLERANCE, iter);
149 phi = .5 * (result.first + result.second);
150 if (std::abs(phiFun(phi)) > 1e-5)
151 throw std::domain_error("fail");
152 }
153 catch (...)
154 {
155 try
156 {
157 std::uintmax_t iter = MAX_ITER;
158 phi = -.1;
159 auto result = boost::math::tools::bracket_and_solve_root(phiFun, phi, 2., true, TOLERANCE, iter);
160 phi = .5 * (result.first + result.second);
161 }
162 catch (...)
163 {
164 // OMPL_ERROR("this shouldn't be happening!");
165 return {};
166 }
167 }
168 assert(std::abs(phiFun(phi)) < 1e-5);
169 turn(state1, rho_, phi, zi);
170 path = dubinsSpace_.getPath(zi, state2, rho_);
171 dubinsSpace_.freeState(zi);
172 return PathType{path, rho_, dz, phi};
173 }
174}
175
176void OwenStateSpace::turn(const State *from, double turnRadius, double angle, State *state) const
177{
178 auto s0 = from->as<DubinsStateSpace::StateType>();
179 auto s1 = state->as<DubinsStateSpace::StateType>();
180 double theta = s0->getYaw(), phi = theta + angle, r = (angle > 0 ? turnRadius : -turnRadius);
181 s1->setXY(s0->getX() + r * (std::sin(phi) - std::sin(theta)), s0->getY() + r * (-std::cos(phi) + std::cos(theta)));
182 s1->setYaw(phi);
183}
184
185double OwenStateSpace::distance(const State *state1, const State *state2) const
186{
187 if (auto path = getPath(state1, state2))
188 return path->length();
189 return getMaximumExtent();
190}
191
192unsigned int OwenStateSpace::validSegmentCount(const State *state1, const State *state2) const
193{
194 return StateSpace::validSegmentCount(state1, state2);
195}
196
197void OwenStateSpace::interpolate(const State *from, const State *to, double t, State *state) const
198{
199 if (auto path = getPath(from, to))
200 interpolate(from, to, t, *path, state);
201 else if (from != state)
202 copyState(state, from);
203}
204
205void OwenStateSpace::interpolate(const State *from, const State *to, double t, PathType &path, State *state) const
206{
207 if (t >= 1.)
208 {
209 if (to != state)
210 copyState(state, to);
211 return;
212 }
213 if (t <= 0.)
214 {
215 if (from != state)
216 copyState(state, from);
217 return;
218 }
219
220 auto f = from->as<StateType>();
221 auto s = state->as<StateType>();
222 (*s)[2] = (*f)[2] + t * path.deltaZ_;
223 if (path.phi_ == 0.)
224 {
225 if (path.numTurns_ == 0)
226 {
227 // low altitude path
228 dubinsSpace_.interpolate(from, path.path_, t, state, path.turnRadius_);
229 }
230 else
231 {
232 // high altitude path
233 auto lengthSpiral = twopi * path.turnRadius_ * path.numTurns_;
234 auto lengthPath = path.turnRadius_ * path.path_.length();
235 auto length = lengthSpiral + lengthPath, dist = t * length;
236 if (dist > lengthSpiral)
237 dubinsSpace_.interpolate(from, path.path_, (dist - lengthSpiral) / lengthPath, state, path.turnRadius_);
238 else
239 turn(from, path.turnRadius_, dist / path.turnRadius_, state);
240 }
241 }
242 else
243 {
244 // medium altitude path
245 auto lengthTurn = std::abs(path.phi_) * path.turnRadius_;
246 auto lengthPath = path.turnRadius_ * path.path_.length();
247 auto length = lengthTurn + lengthPath, dist = t * length;
248 if (dist > lengthTurn)
249 {
250 State *s = (state == to) ? dubinsSpace_.allocState() : state;
251 turn(from, path.turnRadius_, path.phi_, s);
252 dubinsSpace_.interpolate(s, path.path_, (dist - lengthTurn) / lengthPath, state, path.turnRadius_);
253 if (state == to)
254 dubinsSpace_.freeState(s);
255 }
256 else
257 {
258 auto angle = dist / path.turnRadius_;
259 if (path.phi_ < 0)
260 angle = -angle;
261 turn(from, path.turnRadius_, angle, state);
262 }
263 }
264
265 getSubspace(1)->enforceBounds(state->as<CompoundStateSpace::StateType>()->as<SO2StateSpace::StateType>(1));
266}
267
268double OwenStateSpace::PathType::length() const
269{
270 double hlen = turnRadius_ * (path_.length() + twopi * numTurns_ + phi_);
271 return std::sqrt(hlen * hlen + deltaZ_ * deltaZ_);
272}
273
274OwenStateSpace::PathCategory OwenStateSpace::PathType::category() const
275{
276 if (phi_ == 0.)
277 {
278 if (numTurns_ == 0)
279 return PathCategory::LOW_ALTITUDE;
280 else
281 return PathCategory::HIGH_ALTITUDE;
282 }
283 else
284 {
285 if (numTurns_ == 0)
286 return PathCategory::MEDIUM_ALTITUDE;
287 else
288 return PathCategory::UNKNOWN;
289 }
290}
291
292namespace ompl::base
293{
294 std::ostream &operator<<(std::ostream &os, const OwenStateSpace::PathType &path)
295 {
296 static const DubinsStateSpace dubinsStateSpace;
297
298 os << "OwenPath[ category = " << (char)path.category() << "\n\tlength = " << path.length()
299 << "\n\tturnRadius=" << path.turnRadius_ << "\n\tdeltaZ=" << path.deltaZ_ << "\n\tphi=" << path.phi_
300 << "\n\tnumTurns=" << path.numTurns_ << "\n\tpath=" << path.path_;
301 os << "]";
302 return os;
303 }
304} // namespace ompl::base
ompl::base::CompoundState StateType
Define the type of state allocated by this state space.
Definition StateSpace.h:577
unsigned int getDimension() const override
Get the dimension of the space (not the dimension of the surrounding ambient space).
const StateSpacePtr & getSubspace(unsigned int index) const
Get a specific subspace from the compound state space.
void allocStateComponents(CompoundState *state) const
Allocate the state components. Called by allocState(). Usually called by derived state spaces.
double getMaximumExtent() const override
Get the maximum value a call to distance() can return (or an upper bound). For unbounded state spaces...
void copyState(State *destination, const State *source) const override
Copy a state to another. The memory of source and destination should NOT overlap.
const T * as(unsigned int index) const
Cast a component of this instance to a desired type.
Definition State.h:95
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_
const RealVectorBounds & getBounds() const
Get the bounds for this state space.
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.
State * allocState() const override
Allocate a state that can store a point in the described space.
void turn(const State *from, double turnRadius, double angle, State *state) const
Compute the SE(2) state after making a turn.
Abstract definition for a class computing projections to Rn. Implicit integer grids are imposed on th...
double * values
The value of the actual vector in Rn.
A state in SE(2): (x, y, yaw).
void setXY(double x, double y)
Set the X and Y components of the state.
double getYaw() const
Get the yaw component of the state. This is the rotation in plane, with respect to the Z axis.
void setYaw(double yaw)
Set the yaw component of the state. This is the rotation in plane, with respect to the Z axis.
The definition of a state in SO(2).
Representation of a space in which planning can be performed. Topology specific sampling,...
Definition StateSpace.h:71
virtual unsigned int validSegmentCount(const State *state1, const State *state2) const
Count how many segments of the "longest valid length" fit on the motion from state1 to state2.
void registerDefaultProjection(const ProjectionEvaluatorPtr &projection)
Register the default projection for this state space.
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...
@ STATE_SPACE_OWEN
ompl::base::OwenStateSpace
std::ostream & operator<<(std::ostream &stream, Cost c)
Output operator for Cost.
Definition Cost.cpp:39
static const double PROJECTION_DIMENSION_SPLITS
When the cell sizes for a projection are automatically computed, this value defines the number of par...
STL namespace.