Loading...
Searching...
No Matches
VanaStateSpace.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/VanaStateSpace.h"
38#include "ompl/base/SpaceInformation.h"
39#include "ompl/tools/config/MagicConstants.h"
40#include "ompl/util/Exception.h"
41#include <queue>
42
43using namespace ompl::base;
44
45namespace
46{
47 // max # iterations for doubling turning radius for initial solution path
48 constexpr unsigned int MAX_ITER = 32;
49} // namespace
50
51VanaStateSpace::VanaStateSpace(double turningRadius, double maxPitch)
52 : VanaStateSpace(turningRadius, {-maxPitch, maxPitch})
53{
54}
55VanaStateSpace::VanaStateSpace(double turningRadius, std::pair<double, double> pitchRange)
56 : rho_(turningRadius), minPitch_(pitchRange.first), maxPitch_(pitchRange.second), dubinsSpace_(turningRadius)
57{
58 setName("Vana" + getName());
59 type_ = STATE_SPACE_VANA;
60 auto space = std::make_shared<RealVectorStateSpace>(4);
61 ompl::base::RealVectorBounds pitchBounds(4);
62 pitchBounds.setLow(3, minPitch_);
63 pitchBounds.setHigh(3, maxPitch_);
64 space->setBounds(pitchBounds);
65 addSubspace(space, 1.0);
66 addSubspace(std::make_shared<SO2StateSpace>(), 0.5);
67 lock();
68}
69
71{
72 auto *state = new StateType();
74 return state;
75}
76
78{
79 class VanaDefaultProjection : public ProjectionEvaluator
80 {
81 public:
82 VanaDefaultProjection(const StateSpace *space) : ProjectionEvaluator(space)
83 {
84 }
85
86 unsigned int getDimension() const override
87 {
88 return 3;
89 }
90
91 void defaultCellSizes() override
92 {
93 cellSizes_.resize(3);
94 bounds_ = space_->as<VanaStateSpace>()->getBounds();
95 bounds_.resize(3);
96 cellSizes_[0] = (bounds_.high[0] - bounds_.low[0]) / magic::PROJECTION_DIMENSION_SPLITS;
97 cellSizes_[1] = (bounds_.high[1] - bounds_.low[1]) / magic::PROJECTION_DIMENSION_SPLITS;
98 cellSizes_[2] = (bounds_.high[2] - bounds_.low[2]) / magic::PROJECTION_DIMENSION_SPLITS;
99 }
100
101 void project(const State *state, Eigen::Ref<Eigen::VectorXd> projection) const override
102 {
103 projection = Eigen::Map<const Eigen::VectorXd>(
105 }
106 };
107
108 registerDefaultProjection(std::make_shared<VanaDefaultProjection>(this));
109}
110
111DubinsStateSpace::StateType *VanaStateSpace::get2DPose(double x, double y, double yaw) const
112{
113 auto state = dubinsSpace_.allocState()->as<DubinsStateSpace::StateType>();
114 state->setXY(x, y);
115 state->setYaw(yaw);
116 return state;
117}
118
119bool VanaStateSpace::decoupled(const State *state1, const State *state2, double radius, PathType &result,
120 DubinsStateSpace::StateType *endSZ) const
121{
122 result.verticalRadius_ = 1. / std::sqrt(1. / (rho_ * rho_) - 1. / (radius * radius));
123 if (!std::isfinite(result.verticalRadius_))
124 {
125 return false;
126 }
127
128 auto s1 = state1->as<StateType>();
129 auto s2 = state2->as<StateType>();
130
131 result.horizontalRadius_ = radius;
132 // note that we are exploiting properties of the memory layout of state types
133 result.pathXY_ = dubinsSpace_.getPath(state1, state2, radius);
134
135 result.startSZ_->setXY(0., (*s1)[2]);
136 result.startSZ_->setYaw(s1->pitch());
137 endSZ->setXY(radius * result.pathXY_.length(), (*s2)[2]);
138 endSZ->setYaw(s2->pitch());
139 result.pathSZ_ = dubinsSpace_.getPath(result.startSZ_, endSZ, result.verticalRadius_);
140
141 // in three cases the result is invalid:
142 // 1. path of type CCC (i.e., RLR or LRL)
143 // 2. pitch smaller than minPitch_
144 // 3. pitch greater than maxPitch_
145 if ((result.pathSZ_.type_->at(1) != DubinsStateSpace::DUBINS_STRAIGHT) ||
146 (result.pathSZ_.type_->at(0) == DubinsStateSpace::DUBINS_RIGHT &&
147 s1->pitch() - result.pathSZ_.length_[0] < minPitch_) ||
148 (result.pathSZ_.type_->at(0) == DubinsStateSpace::DUBINS_LEFT &&
149 s1->pitch() + result.pathSZ_.length_[0] > maxPitch_))
150 {
151 return false;
152 }
153
154 return true;
155}
156
157std::optional<VanaStateSpace::PathType> VanaStateSpace::getPath(const State *state1, const State *state2) const
158{
159 double radiusMultiplier = 2.;
160 auto scratch = dubinsSpace_.allocState()->as<DubinsStateSpace::StateType>();
161 PathType path;
162
163 unsigned int iter = 0;
164 while (!decoupled(state1, state2, rho_ * radiusMultiplier, path, scratch) && iter++ < MAX_ITER)
165 {
166 radiusMultiplier *= 2.;
167 }
168 if (iter >= MAX_ITER)
169 {
170 OMPL_ERROR("Maximum number of iterations exceeded in VanaStateSpace::PathType");
171 dubinsSpace_.freeState(scratch);
172 return {};
173 }
174
175 // Local optimalization between horizontal and vertical radii
176 double step = .1, radiusMultiplier2;
177 PathType path2;
178 while (std::abs(step) > tolerance_)
179 {
180 radiusMultiplier2 = std::max(1., radiusMultiplier + step);
181 if (decoupled(state1, state2, rho_ * radiusMultiplier2, path2, scratch) && path2.length() < path.length())
182 {
183 radiusMultiplier = radiusMultiplier2;
184 path = path2;
185 step *= 2.;
186 }
187 else
188 step *= -.1;
189 }
190
191 dubinsSpace_.freeState(scratch);
192 return path;
193}
194
195double VanaStateSpace::distance(const State *state1, const State *state2) const
196{
197 if (auto path = getPath(state1, state2))
198 return path->length();
199 return getMaximumExtent();
200}
201
202unsigned int VanaStateSpace::validSegmentCount(const State *state1, const State *state2) const
203{
204 return StateSpace::validSegmentCount(state1, state2);
205}
206
207void VanaStateSpace::interpolate(const State *from, const State *to, const double t, State *state) const
208{
209 if (auto path = getPath(from, to))
210 interpolate(from, to, t, *path, state);
211 else if (from != state)
212 copyState(state, from);
213}
214
215void VanaStateSpace::interpolate(const State *from, const State *to, const double t, PathType &path, State *state) const
216{
217 if (t >= 1.)
218 {
219 if (to != state)
220 copyState(state, to);
221 return;
222 }
223 if (t <= 0.)
224 {
225 if (from != state)
226 copyState(state, from);
227 return;
228 }
229
230 interpolate(from, path, t, state);
231}
232
233void VanaStateSpace::interpolate(const State *from, const PathType &path, double t, State *state) const
234{
235 auto intermediate = (from == state) ? dubinsSpace_.allocState() : state;
236 auto s = state->as<StateType>();
237 auto i = intermediate->as<DubinsStateSpace::StateType>();
238 // This is exploiting internal properties of compound state spaces like DubinsStateSpace
239 // and VanaStateSpace
240 dubinsSpace_.interpolate(path.startSZ_, path.pathSZ_, t, intermediate, path.verticalRadius_);
241 (*s)[2] = i->getY();
242 s->pitch() = i->getYaw();
243 dubinsSpace_.interpolate(from, path.pathXY_, t, state, path.horizontalRadius_);
244 if (from == state)
245 dubinsSpace_.freeState(intermediate);
246}
247
248VanaStateSpace::PathType::~PathType()
249{
250 static const DubinsStateSpace dubinsStateSpace_;
251 dubinsStateSpace_.freeState(startSZ_);
252}
253
254VanaStateSpace::PathType::PathType()
255{
256 static const DubinsStateSpace dubinsStateSpace_;
257 startSZ_ = dubinsStateSpace_.allocState()->as<DubinsStateSpace::StateType>();
258}
259
260VanaStateSpace::PathType::PathType(const VanaStateSpace::PathType &path)
261 : horizontalRadius_(path.horizontalRadius_)
262 , verticalRadius_(path.verticalRadius_)
263 , pathXY_(path.pathXY_)
264 , pathSZ_(path.pathSZ_)
265{
266 static const DubinsStateSpace dubinsStateSpace_;
267 startSZ_ = dubinsStateSpace_.allocState()->as<DubinsStateSpace::StateType>();
268 dubinsStateSpace_.copyState(startSZ_, path.startSZ_);
269}
270
271VanaStateSpace::PathType &VanaStateSpace::PathType::operator=(const VanaStateSpace::PathType &path)
272{
273 static const DubinsStateSpace dubinsStateSpace_;
274 horizontalRadius_ = path.horizontalRadius_;
275 verticalRadius_ = path.verticalRadius_;
276 pathXY_ = path.pathXY_;
277 pathSZ_ = path.pathSZ_;
278 dubinsStateSpace_.copyState(startSZ_, path.startSZ_);
279 return *this;
280}
281
282double VanaStateSpace::PathType::length() const
283{
284 return verticalRadius_ * pathSZ_.length();
285}
286
287namespace ompl::base
288{
289 std::ostream &operator<<(std::ostream &os, const VanaStateSpace::PathType &path)
290 {
291 static const DubinsStateSpace dubinsStateSpace;
292
293 os << "VanaPath[\n\tlength = " << path.length() << "\n\tXY=" << path.pathXY_ << "\n\tSZ=" << path.pathSZ_
294 << "\n\trh = " << path.horizontalRadius_ << "\n\trv = " << path.verticalRadius_ << "\n\tstartSZ=";
295 dubinsStateSpace.printState(path.startSZ_, os);
296 os << "]";
297 return os;
298 }
299} // 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).
void allocStateComponents(CompoundState *state) const
Allocate the state components. Called by allocState(). Usually called by derived state spaces.
void printState(const State *state, std::ostream &out) const override
Print a state to a stream.
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
const std::vector< DubinsPathSegmentType > * type_
An SE(2) state space where distance is measured by the length of Dubins curves.
Abstract definition for a class computing projections to Rn. Implicit integer grids are imposed on th...
The lower and upper bounds for an Rn space.
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.
void setYaw(double yaw)
Set the yaw component of the state. This is the rotation in plane, with respect to the Z axis.
State * allocState() const override
Allocate a state that can store a point in the described space.
void freeState(State *state) const override
Free the memory of the allocated state.
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.
T * as()
Cast this instance to a desired type.
Definition StateSpace.h:87
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
An R^4 x SO(2) state space where distance is measured by the length of a type Dubins airplane 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....
std::optional< PathType > getPath(const State *state1, const State *state2) const
Compute a 3D Dubins path using the model and algorithm proposed by Vana et al.
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...
DubinsStateSpace dubinsSpace_
const RealVectorBounds & getBounds() const
Get the bounds for this state space.
void registerProjections() override
Register the projections for this state space. Usually, this is at least the default projection....
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....
State * allocState() const override
Allocate a state that can store a point in the described space.
DubinsStateSpace::StateType * get2DPose(double x, double y, double yaw) const
Allocate a DubinsSpace state and initialize it.
bool decoupled(const State *state1, const State *state2, double radius, PathType &path, DubinsStateSpace::StateType *endSZ) const
Helper function used by getPath.
#define OMPL_ERROR(fmt,...)
Log a formatted error string.
Definition Console.h:64
This namespace contains sampling based planning routines shared by both planning under geometric cons...
@ STATE_SPACE_VANA
ompl::base::VanaStateSpace
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...