Program Listing for File VanaOwenStateSpace.h
↰ Return to documentation for file (src/ompl/base/spaces/VanaOwenStateSpace.h)
/*********************************************************************
* Software License Agreement (BSD License)
*
* Copyright (c) 2024, Metron, Inc.
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* * Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* * Redistributions in binary form must reproduce the above
* copyright notice, this list of conditions and the following
* disclaimer in the documentation and/or other materials provided
* with the distribution.
* * Neither the name of the Metron, Inc. nor the names of its
* contributors may be used to endorse or promote products derived
* from this software without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*********************************************************************/
/* Author: Mark Moll */
#ifndef OMPL_BASE_SPACES_VANAOWEN_STATE_SPACE_
#define OMPL_BASE_SPACES_VANAOWEN_STATE_SPACE_
#include "ompl/base/spaces/DubinsStateSpace.h"
#include <optional>
namespace ompl::base
{
class VanaOwenStateSpace : public CompoundStateSpace
{
public:
enum PathCategory : char
{
LOW_ALTITUDE = 'L',
MEDIUM_ALTITUDE = 'M',
HIGH_ALTITUDE = 'H',
UNKNOWN = '?'
};
class PathType
{
public:
PathType();
PathType(const PathType &path);
~PathType();
double length() const;
PathType &operator=(const PathType &path);
PathCategory category() const;
friend std::ostream &operator<<(std::ostream &os, const PathType &path);
DubinsStateSpace::DubinsPath pathXY_;
DubinsStateSpace::DubinsPath pathSZ_;
DubinsStateSpace::StateType *startSZ_{nullptr};
double horizontalRadius_{1.};
double verticalRadius_{1.};
double deltaZ_{0.};
double phi_{0.};
unsigned int numTurns_{0};
};
class StateType : public CompoundStateSpace::StateType
{
public:
StateType() = default;
double operator[](unsigned index) const
{
return as<RealVectorStateSpace::StateType>(0)->values[index];
}
double &operator[](unsigned index)
{
return as<RealVectorStateSpace::StateType>(0)->values[index];
}
double yaw() const
{
return as<SO2StateSpace::StateType>(1)->value;
}
double &yaw()
{
return as<SO2StateSpace::StateType>(1)->value;
}
double pitch() const
{
return as<RealVectorStateSpace::StateType>(0)->values[3];
}
double &pitch()
{
return as<RealVectorStateSpace::StateType>(0)->values[3];
}
};
VanaOwenStateSpace(double turningRadius = 1.0, double maxPitch = boost::math::double_constants::sixth_pi);
VanaOwenStateSpace(double turningRadius, std::pair<double, double> pitchRange);
~VanaOwenStateSpace() override = default;
bool isMetricSpace() const override
{
return false;
}
bool hasSymmetricDistance() const override
{
return false;
}
bool hasSymmetricInterpolate() const override
{
return false;
}
void sanityChecks() const override
{
double zero = std::numeric_limits<double>::epsilon();
double eps = std::numeric_limits<float>::epsilon();
int flags = ~(STATESPACE_INTERPOLATION | STATESPACE_TRIANGLE_INEQUALITY | STATESPACE_DISTANCE_BOUND |
STATESPACE_DISTANCE_SYMMETRIC);
StateSpace::sanityChecks(zero, eps, flags);
}
void setBounds(const RealVectorBounds &bounds)
{
RealVectorBounds b(bounds);
if (bounds.low.size() < 4)
{
b.resize(4);
b.low[3] = minPitch_;
b.high[3] = maxPitch_;
}
as<RealVectorStateSpace>(0)->setBounds(b);
}
const RealVectorBounds &getBounds() const
{
return as<RealVectorStateSpace>(0)->getBounds();
}
void setTolerance(double tolerance)
{
tolerance_ = tolerance;
}
double getTolerance()
{
return tolerance_;
}
State *allocState() const override;
void registerProjections() override;
double distance(const State *state1, const State *state2) const override;
unsigned int validSegmentCount(const State *state1, const State *state2) const override;
void interpolate(const State *from, const State *to, double t, State *state) const override;
virtual void interpolate(const State *from, const State *to, double t, PathType &path, State *state) const;
std::optional<PathType> getPath(const State *state1, const State *state2) const;
bool decoupled(const StateType *state1, const StateType *state2, double radius, PathType &path,
std::array<DubinsStateSpace::StateType *, 3> &scratch) const;
protected:
DubinsStateSpace::StateType *get2DPose(double x, double y, double yaw) const;
bool isValid(DubinsStateSpace::DubinsPath const &path, StateType const *state) const;
double rho_;
double minPitch_;
double maxPitch_;
double tolerance_{1e-8};
DubinsStateSpace dubinsSpace_;
};
} // namespace ompl::base
#endif