Loading...
Searching...
No Matches
VanaOwenStateSpace.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/VanaOwenStateSpace.h"
38#include "ompl/tools/config/MagicConstants.h"
39#include <boost/math/tools/toms748_solve.hpp>
40
41using namespace ompl::base;
42
43namespace
44{
45 constexpr double onepi = boost::math::constants::pi<double>();
46 constexpr double twopi = 2. * boost::math::constants::pi<double>();
47
48 // tolerance for boost root finding algorithm
49 boost::math::tools::eps_tolerance<double> TOLERANCE(10);
50
51 // max # iterations for doubling turning radius for initial solution path
52 constexpr unsigned int MAX_ITER = 64;
53
54 void turn(const State *from, double turnRadius, double angle, State *state)
55 {
56 auto s0 = from->as<DubinsStateSpace::StateType>();
57 auto s1 = state->as<DubinsStateSpace::StateType>();
58 double theta = s0->getYaw(), phi = theta + angle, r = (angle > 0 ? turnRadius : -turnRadius);
59 s1->setXY(s0->getX() + r * (std::sin(phi) - std::sin(theta)),
60 s0->getY() + r * (-std::cos(phi) + std::cos(theta)));
61 s1->setYaw(phi);
62 }
63
64} // namespace
65
66VanaOwenStateSpace::VanaOwenStateSpace(double turningRadius, double maxPitch)
67 : VanaOwenStateSpace(turningRadius, {-maxPitch, maxPitch})
68{
69}
70VanaOwenStateSpace::VanaOwenStateSpace(double turningRadius, std::pair<double, double> pitchRange)
71 : rho_(turningRadius), minPitch_(pitchRange.first), maxPitch_(pitchRange.second), dubinsSpace_(turningRadius)
72{
73 setName("VanaOwen" + getName());
75 auto space = std::make_shared<RealVectorStateSpace>(4);
76 ompl::base::RealVectorBounds pitchBounds(4);
77 pitchBounds.setLow(3, minPitch_);
78 pitchBounds.setHigh(3, maxPitch_);
79 space->setBounds(pitchBounds);
80 addSubspace(space, 1.0);
81 addSubspace(std::make_shared<SO2StateSpace>(), 0.5);
82 lock();
83}
84
86{
87 auto *state = new StateType();
89 return state;
90}
91
93{
94 class VanaOwenDefaultProjection : public ProjectionEvaluator
95 {
96 public:
97 VanaOwenDefaultProjection(const StateSpace *space) : ProjectionEvaluator(space)
98 {
99 }
100
101 unsigned int getDimension() const override
102 {
103 return 3;
104 }
105
106 void defaultCellSizes() override
107 {
108 cellSizes_.resize(3);
109 bounds_ = space_->as<VanaOwenStateSpace>()->getBounds();
110 bounds_.resize(3);
111 cellSizes_[0] = (bounds_.high[0] - bounds_.low[0]) / magic::PROJECTION_DIMENSION_SPLITS;
112 cellSizes_[1] = (bounds_.high[1] - bounds_.low[1]) / magic::PROJECTION_DIMENSION_SPLITS;
113 cellSizes_[2] = (bounds_.high[2] - bounds_.low[2]) / magic::PROJECTION_DIMENSION_SPLITS;
114 }
115
116 void project(const State *state, Eigen::Ref<Eigen::VectorXd> projection) const override
117 {
118 projection = Eigen::Map<const Eigen::VectorXd>(
120 }
121 };
122
123 registerDefaultProjection(std::make_shared<VanaOwenDefaultProjection>(this));
124}
125
126DubinsStateSpace::StateType *VanaOwenStateSpace::get2DPose(double x, double y, double yaw) const
127{
128 auto state = dubinsSpace_.allocState()->as<DubinsStateSpace::StateType>();
129 state->setXY(x, y);
130 state->setYaw(yaw);
131 return state;
132}
133
135{
136 // in three cases the result is invalid:
137 // 1. path of type CCC (i.e., RLR or LRL)
138 // 2. pitch smaller than minPitch_
139 // 3. pitch greater than maxPitch_
140 if ((path.type_->at(1) != DubinsStateSpace::DUBINS_STRAIGHT) ||
141 (path.type_->at(0) == DubinsStateSpace::DUBINS_RIGHT && state->pitch() - path.length_[0] < minPitch_) ||
142 (path.type_->at(0) == DubinsStateSpace::DUBINS_LEFT && state->pitch() + path.length_[0] > maxPitch_))
143 {
144 return false;
145 }
146
147 return true;
148}
149
150bool VanaOwenStateSpace::decoupled(const StateType *from, const StateType *to, double radius, PathType &result,
151 std::array<DubinsStateSpace::StateType *, 3> &scratch) const
152{
153 result.horizontalRadius_ = radius;
154 result.verticalRadius_ = 1. / std::sqrt(1. / (rho_ * rho_) - 1. / (radius * radius));
155 result.deltaZ_ = (*to)[2] - (*from)[2];
156 // note that we are exploiting properties of the memory layout of state types
157 result.pathXY_ = dubinsSpace_.getPath(from, to, radius);
158 result.phi_ = 0.;
159 result.numTurns_ = 0;
160
161 // can't change altitude if vertical turning radius is infinite, but that's ok if we don't need a vertical turn
162 if (!std::isfinite(result.verticalRadius_))
163 {
164 if (std::abs(result.deltaZ_) < 1e-8 && std::abs(to->pitch() - from->pitch()) < 1e-8)
165 {
166 result.pathSZ_.type_ = &DubinsStateSpace::dubinsPathType()[0]; // LSL type
167 result.pathSZ_.length_[0] = result.pathSZ_.length_[2] = 0.;
168 result.pathSZ_.length_[1] = result.deltaZ_;
169 // don't break length() and interpolation()
170 result.verticalRadius_ = 0.;
171 return true;
172 }
173 else
174 return false;
175 }
176
177 double len = radius * result.pathXY_.length();
178 auto startSZ = result.startSZ_, endSZ = scratch[0];
179
180 startSZ->setXY(0., (*from)[2]);
181 startSZ->setYaw(from->pitch());
182 endSZ->setXY(len, (*to)[2]);
183 endSZ->setYaw(to->pitch());
184 result.pathSZ_ = dubinsSpace_.getPath(startSZ, endSZ, result.verticalRadius_);
185 if (isValid(result.pathSZ_, from))
186 {
187 // low altitude path
188 return true;
189 }
190
191 double pitch = (result.deltaZ_ < 0) ? minPitch_ : maxPitch_, tanPitch = tan(pitch);
192 auto s1b = scratch[1], s2b = scratch[2];
193 double turnS, turnZ;
194 auto update = [&, this](double r, bool skipInit = false)
195 {
196 if (!skipInit)
197 {
198 result.horizontalRadius_ = r;
199 result.verticalRadius_ = 1. / std::sqrt(1. / (rho_ * rho_) - 1. / (r * r));
200 result.pathXY_ = dubinsSpace_.getPath(from, to, result.horizontalRadius_);
201 }
202 endSZ->setX((result.pathXY_.length() + twopi * result.numTurns_) * r);
203 turn(startSZ, result.verticalRadius_, pitch - from->pitch(), s1b);
204 assert(std::abs(s1b->getYaw() - pitch) < 1e-8);
205 dubinsSpace_.copyState(s2b, endSZ);
206 s2b->setYaw(s2b->getYaw() + onepi);
207 turn(s2b, result.verticalRadius_, pitch - to->pitch(), s2b);
208 assert(std::abs(s2b->getYaw() - pitch - onepi) < 1e-8);
209 turnS = (s1b->getX() - startSZ->getX()) + (endSZ->getX() - s2b->getX());
210 turnZ = (s1b->getY() - startSZ->getY()) + (endSZ->getY() - s2b->getY());
211 };
212 update(radius, true);
213
214 double highAltitudeS = len + twopi * radius;
215 double highAltitudeZ = turnZ + (highAltitudeS - turnS) * tanPitch;
216 if (std::abs(result.deltaZ_) > std::abs(highAltitudeZ))
217 {
218 // high altitude path
219 result.numTurns_ = std::floor((std::abs((result.deltaZ_ - turnZ) / tanPitch) - len + turnS) / (twopi * radius));
220 auto radiusFun = [&, this](double r)
221 {
222 update(r);
223 result.pathSZ_ = dubinsSpace_.getPath(startSZ, endSZ, result.verticalRadius_);
224 return ((result.pathXY_.length() + twopi * result.numTurns_) * r - turnS) * tanPitch + turnZ -
225 result.deltaZ_;
226 };
227 std::uintmax_t iter = MAX_ITER;
228 try
229 {
230 auto root = boost::math::tools::toms748_solve(radiusFun, radius, 3. * radius, TOLERANCE, iter);
231 auto rval = radiusFun(.5 * (root.first + root.second));
232 if (iter >= MAX_ITER)
233 OMPL_WARN("Maximum number of iterations exceeded for high altitude Vana-Owen path");
234 return std::abs(rval) < 1e-4;
235 }
236 catch (std::domain_error &e)
237 {
238 return false;
239 }
240 }
241 else
242 {
243 // medium altitude path
244 auto zi = scratch[1];
245 auto phiFun = [&, this](double phi)
246 {
247 if (std::abs(phi) > twopi)
248 throw std::domain_error("phi too large");
249 turn(from, radius, phi, zi);
250 return (std::abs(phi) + dubinsSpace_.getPath(zi, to).length()) * radius * std::abs(tanPitch) -
251 std::abs(result.deltaZ_);
252 };
253
254 try
255 {
256 std::uintmax_t iter = MAX_ITER;
257 result.phi_ = 0.1;
258 auto root = boost::math::tools::bracket_and_solve_root(phiFun, result.phi_, 2., true, TOLERANCE, iter);
259 result.phi_ = .5 * (root.first + root.second);
260 if (std::abs(phiFun(result.phi_)) > .01)
261 throw std::domain_error("fail");
262 }
263 catch (...)
264 {
265 try
266 {
267 std::uintmax_t iter = MAX_ITER;
268 result.phi_ = -.1;
269 auto root = boost::math::tools::bracket_and_solve_root(phiFun, result.phi_, 2., true, TOLERANCE, iter);
270 result.phi_ = .5 * (root.first + root.second);
271 }
272 catch (...)
273 {
274 // OMPL_ERROR("this shouldn't be happening!");
275 return false;
276 }
277 }
278 result.pathXY_ = dubinsSpace_.getPath(zi, to, radius);
279 endSZ->setX((result.pathXY_.length() + result.phi_) * radius);
280 result.pathSZ_ = dubinsSpace_.getPath(startSZ, endSZ, result.verticalRadius_);
281 return std::abs(phiFun(result.phi_)) < .01 && isValid(result.pathSZ_, from);
282 }
283 return true;
284}
285
286std::optional<VanaOwenStateSpace::PathType> VanaOwenStateSpace::getPath(const State *state1, const State *state2) const
287{
288 auto from = state1->as<StateType>(), to = state2->as<StateType>();
289 double radiusMultiplier = 1.5;
290 std::array<DubinsStateSpace::StateType *, 3> scratch;
291 PathType path;
292
293 unsigned int iter = 0;
294 std::generate(scratch.begin(), scratch.end(),
295 [this]() { return dubinsSpace_.allocState()->as<DubinsStateSpace::StateType>(); });
296
297 while (!decoupled(from, to, rho_ * radiusMultiplier, path, scratch) && iter++ < MAX_ITER)
298 {
299 radiusMultiplier *= 2.;
300 }
301 if (iter >= MAX_ITER)
302 {
303 OMPL_ERROR("Maximum number of iterations exceeded in VanaOwenStateSpace::PathType");
304 for (auto s : scratch)
305 dubinsSpace_.freeState(s);
306 return {};
307 }
308
309 // Local optimalization between horizontal and vertical radii
310 double step = .1, radiusMultiplier2, minLength = path.length(), length;
311 PathType path2;
312 while (std::abs(step) > tolerance_)
313 {
314 radiusMultiplier2 = std::max(1., radiusMultiplier + step);
315 if (decoupled(from, to, rho_ * radiusMultiplier2, path2, scratch) && (length = path2.length()) < minLength)
316 {
317 radiusMultiplier = radiusMultiplier2;
318 path = path2;
319 minLength = length;
320 step *= 2.;
321 }
322 else
323 step *= -.1;
324 }
325
326 for (auto s : scratch)
327 dubinsSpace_.freeState(s);
328 return path;
329}
330
331double VanaOwenStateSpace::distance(const State *state1, const State *state2) const
332{
333 if (auto path = getPath(state1, state2))
334 return path->length();
335 return getMaximumExtent();
336}
337
338unsigned int VanaOwenStateSpace::validSegmentCount(const State *state1, const State *state2) const
339{
340 return StateSpace::validSegmentCount(state1, state2);
341}
342
343void VanaOwenStateSpace::interpolate(const State *from, const State *to, const double t, State *state) const
344{
345 if (auto path = getPath(from, to))
346 interpolate(from, to, t, *path, state);
347 else if (from != state)
348 copyState(state, from);
349}
350
351void VanaOwenStateSpace::interpolate(const State *from, const State *to, const double t, PathType &path,
352 State *state) const
353{
354 if (t >= 1.)
355 {
356 if (to != state)
357 copyState(state, to);
358 return;
359 }
360 if (t <= 0.)
361 {
362 if (from != state)
363 copyState(state, from);
364 return;
365 }
366
367 auto intermediate = (from == state) ? dubinsSpace_.allocState() : state;
368 auto s = state->as<StateType>();
369 auto i = intermediate->as<DubinsStateSpace::StateType>();
370
371 // This is exploiting internal properties of compound state spaces like DubinsStateSpace
372 // and VanaOwenStateSpace
373 dubinsSpace_.interpolate(path.startSZ_, path.pathSZ_, t, intermediate, path.verticalRadius_);
374 (*s)[2] = i->getY();
375 s->pitch() = i->getYaw();
376
377 if (path.phi_ == 0.)
378 {
379 if (path.numTurns_ == 0)
380 {
381 // low altitude path
382 dubinsSpace_.interpolate(from, path.pathXY_, t, state, path.horizontalRadius_);
383 }
384 else
385 {
386 // high altitude path
387 auto lengthSpiral = twopi * path.horizontalRadius_ * path.numTurns_;
388 auto lengthPath = path.horizontalRadius_ * path.pathXY_.length();
389 auto length = lengthSpiral + lengthPath, dist = t * length;
390 if (dist > lengthSpiral)
391 dubinsSpace_.interpolate(from, path.pathXY_, (dist - lengthSpiral) / lengthPath, state,
392 path.horizontalRadius_);
393 else
394 turn(from, path.horizontalRadius_, dist / path.horizontalRadius_, state);
395 }
396 }
397 else
398 {
399 // medium altitude path
400 auto lengthTurn = std::abs(path.phi_) * path.horizontalRadius_;
401 auto lengthPath = path.horizontalRadius_ * path.pathXY_.length();
402 auto length = lengthTurn + lengthPath, dist = t * length;
403 if (dist > lengthTurn)
404 {
405 State *s = (state == to) ? dubinsSpace_.allocState() : state;
406 turn(from, path.horizontalRadius_, path.phi_, s);
407 dubinsSpace_.interpolate(s, path.pathXY_, (dist - lengthTurn) / lengthPath, state, path.horizontalRadius_);
408 if (state == to)
409 dubinsSpace_.freeState(s);
410 }
411 else
412 {
413 auto angle = dist / path.horizontalRadius_;
414 if (path.phi_ < 0)
415 angle = -angle;
416 turn(from, path.horizontalRadius_, angle, state);
417 }
418 }
419
420 if (from == state)
421 dubinsSpace_.freeState(intermediate);
422 getSubspace(1)->enforceBounds(state->as<CompoundStateSpace::StateType>()->as<SO2StateSpace::StateType>(1));
423}
424
425VanaOwenStateSpace::PathType::~PathType()
426{
427 static const DubinsStateSpace dubinsStateSpace_;
428 dubinsStateSpace_.freeState(startSZ_);
429}
430
431VanaOwenStateSpace::PathType::PathType()
432{
433 static const DubinsStateSpace dubinsStateSpace_;
434 startSZ_ = dubinsStateSpace_.allocState()->as<DubinsStateSpace::StateType>();
435}
436
437VanaOwenStateSpace::PathType::PathType(const VanaOwenStateSpace::PathType &path)
438 : pathXY_(path.pathXY_)
439 , pathSZ_(path.pathSZ_)
440 , horizontalRadius_(path.horizontalRadius_)
441 , verticalRadius_(path.verticalRadius_)
442 , deltaZ_(path.deltaZ_)
443 , phi_(path.phi_)
444 , numTurns_(path.numTurns_)
445{
446 static const DubinsStateSpace dubinsStateSpace_;
447 startSZ_ = dubinsStateSpace_.allocState()->as<DubinsStateSpace::StateType>();
448 dubinsStateSpace_.copyState(startSZ_, path.startSZ_);
449}
450
451VanaOwenStateSpace::PathType &VanaOwenStateSpace::PathType::operator=(const VanaOwenStateSpace::PathType &path)
452{
453 static const DubinsStateSpace dubinsStateSpace_;
454 pathXY_ = path.pathXY_;
455 pathSZ_ = path.pathSZ_;
456 horizontalRadius_ = path.horizontalRadius_;
457 verticalRadius_ = path.verticalRadius_;
458 deltaZ_ = path.deltaZ_;
459 phi_ = path.phi_;
460 numTurns_ = path.numTurns_;
461 dubinsStateSpace_.copyState(startSZ_, path.startSZ_);
462 return *this;
463}
464
465double VanaOwenStateSpace::PathType::length() const
466{
467 return verticalRadius_ > 0. ? verticalRadius_ * pathSZ_.length() : horizontalRadius_ * pathXY_.length();
468}
469
470VanaOwenStateSpace::PathCategory VanaOwenStateSpace::PathType::category() const
471{
472 if (phi_ == 0.)
473 {
474 if (numTurns_ == 0)
475 return PathCategory::LOW_ALTITUDE;
476 else
477 return PathCategory::HIGH_ALTITUDE;
478 }
479 else
480 {
481 if (numTurns_ == 0)
482 return PathCategory::MEDIUM_ALTITUDE;
483 else
484 return PathCategory::UNKNOWN;
485 }
486}
487
488namespace ompl::base
489{
490 std::ostream &operator<<(std::ostream &os, const VanaOwenStateSpace::PathType &path)
491 {
492 static const DubinsStateSpace dubinsStateSpace;
493
494 os << "VanaOwenPath[ category = " << (char)path.category() << "\n\tlength = " << path.length()
495 << "\n\tXY = " << path.pathXY_ << "\n\tSZ = " << path.pathSZ_ << "\n\trh = " << path.horizontalRadius_
496 << "\n\trv = " << path.verticalRadius_ << "\n\tdeltaZ = " << path.deltaZ_ << "\n\tphi = " << path.phi_
497 << "\n\tnumTurns = " << path.numTurns_ << "\n\tstartSZ = ";
498 dubinsStateSpace.printState(path.startSZ_, os);
499 os << "]";
500 return os;
501 }
502} // 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.
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
Complete description of a Dubins path.
const std::vector< DubinsPathSegmentType > * type_
An SE(2) state space where distance is measured by the length of Dubins curves.
static const std::vector< std::vector< DubinsPathSegmentType > > & dubinsPathType()
Dubins path types.
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.
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.
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.
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.
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 of Dubins airplane curv...
const RealVectorBounds & getBounds() const
Get the bounds for this state space.
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.
void registerProjections() override
Register the projections for this state space. Usually, this is at least the default projection....
std::optional< PathType > getPath(const State *state1, const State *state2) const
Compute a 3D Dubins path using the model and algorithm proposed by VanaOwen et al.
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....
bool isValid(DubinsStateSpace::PathType const &path, StateType const *state) const
Whether a path in SZ space satisfies Dubins path type and pitch constraints.
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...
bool decoupled(const StateType *state1, const StateType *state2, double radius, PathType &path, std::array< DubinsStateSpace::StateType *, 3 > &scratch) const
Helper function used by getPath.
DubinsStateSpace::StateType * get2DPose(double x, double y, double yaw) const
Allocate a DubinsSpace state and initialize it.
#define OMPL_ERROR(fmt,...)
Log a formatted error string.
Definition Console.h:64
#define OMPL_WARN(fmt,...)
Log a formatted warning string.
Definition Console.h:66
This namespace contains sampling based planning routines shared by both planning under geometric cons...
@ STATE_SPACE_VANA_OWEN
ompl::base::VanaOwenStateSpace
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...