VanaOwenStateSpace.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_VANAOWEN_STATE_SPACE_
38 #define OMPL_BASE_SPACES_VANAOWEN_STATE_SPACE_
39 
40 #include "ompl/base/spaces/DubinsStateSpace.h"
41 #include <optional>
42 
43 namespace ompl::base
44 {
58  class VanaOwenStateSpace : public CompoundStateSpace
59  {
60  public:
61  enum PathCategory : char
62  {
63  LOW_ALTITUDE = 'L',
64  MEDIUM_ALTITUDE = 'M',
65  HIGH_ALTITUDE = 'H',
66  UNKNOWN = '?'
67  };
68 
69  class PathType
70  {
71  public:
72  PathType();
73  PathType(const PathType &path);
74  ~PathType();
75  double length() const;
76  PathType &operator=(const PathType &path);
77 
78  PathCategory category() const;
79 
80  friend std::ostream &operator<<(std::ostream &os, const PathType &path);
81 
82  DubinsStateSpace::DubinsPath pathXY_;
83  DubinsStateSpace::DubinsPath pathSZ_;
84  DubinsStateSpace::StateType *startSZ_{nullptr};
85  double horizontalRadius_{1.};
86  double verticalRadius_{1.};
87  double deltaZ_{0.};
88  double phi_{0.};
89  unsigned int numTurns_{0};
90  };
91 
94  {
95  public:
96  StateType() = default;
97  double operator[](unsigned index) const
98  {
99  return as<RealVectorStateSpace::StateType>(0)->values[index];
100  }
101  double &operator[](unsigned index)
102  {
103  return as<RealVectorStateSpace::StateType>(0)->values[index];
104  }
105  double yaw() const
106  {
107  return as<SO2StateSpace::StateType>(1)->value;
108  }
109  double &yaw()
110  {
111  return as<SO2StateSpace::StateType>(1)->value;
112  }
113  double pitch() const
114  {
115  return as<RealVectorStateSpace::StateType>(0)->values[3];
116  }
117  double &pitch()
118  {
119  return as<RealVectorStateSpace::StateType>(0)->values[3];
120  }
121  };
122 
123  VanaOwenStateSpace(double turningRadius = 1.0, double maxPitch = boost::math::double_constants::sixth_pi);
124  VanaOwenStateSpace(double turningRadius, std::pair<double, double> pitchRange);
125  ~VanaOwenStateSpace() override = default;
126 
127  bool isMetricSpace() const override
128  {
129  return false;
130  }
131  bool hasSymmetricDistance() const override
132  {
133  return false;
134  }
135 
136  bool hasSymmetricInterpolate() const override
137  {
138  return false;
139  }
140 
141  void sanityChecks() const override
142  {
143  double zero = std::numeric_limits<double>::epsilon();
144  double eps = std::numeric_limits<float>::epsilon();
147  StateSpace::sanityChecks(zero, eps, flags);
148  }
149 
151  void setBounds(const RealVectorBounds &bounds)
152  {
153  RealVectorBounds b(bounds);
154  if (bounds.low.size() < 4)
155  {
156  b.resize(4);
157  b.low[3] = minPitch_;
158  b.high[3] = maxPitch_;
159  }
160  as<RealVectorStateSpace>(0)->setBounds(b);
161  }
162 
164  const RealVectorBounds &getBounds() const
165  {
166  return as<RealVectorStateSpace>(0)->getBounds();
167  }
168 
170  void setTolerance(double tolerance)
171  {
172  tolerance_ = tolerance;
173  }
175  double getTolerance()
176  {
177  return tolerance_;
178  }
179 
180  State *allocState() const override;
181  void registerProjections() override;
182 
183  double distance(const State *state1, const State *state2) const override;
184 
185  unsigned int validSegmentCount(const State *state1, const State *state2) const override;
186 
187  void interpolate(const State *from, const State *to, double t, State *state) const override;
200  virtual void interpolate(const State *from, const State *to, double t, PathType &path, State *state) const;
201 
209  std::optional<PathType> getPath(const State *state1, const State *state2) const;
210 
221  bool decoupled(const StateType *state1, const StateType *state2, double radius, PathType &path,
222  std::array<DubinsStateSpace::StateType *, 3> &scratch) const;
223 
224  protected:
233  DubinsStateSpace::StateType *get2DPose(double x, double y, double yaw) const;
234 
239  bool isValid(DubinsStateSpace::DubinsPath const &path, StateType const *state) const;
240 
242  double rho_;
244  double minPitch_;
246  double maxPitch_;
248  double tolerance_{1e-8};
251  };
252 } // namespace ompl::base
253 
254 #endif
@ STATESPACE_DISTANCE_SYMMETRIC
Check whether the distance function is symmetric (StateSpace::distance())
Definition: StateSpace.h:206
Definition of a compound state.
Definition: State.h:150
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 VanaOwen 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...
Definition of an abstract state.
Definition: State.h:113
This namespace contains sampling based planning routines shared by both planning under geometric cons...
virtual void sanityChecks() const
Convenience function that allows derived state spaces to choose which checks should pass (see SanityC...
Definition: StateSpace.cpp:603
bool isValid(DubinsStateSpace::DubinsPath const &path, StateType const *state) const
Whether a path in SZ space satisfies Dubins path type and pitch constraints.
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.
@ STATESPACE_DISTANCE_BOUND
Check whether the StateSpace::distance() is bounded by StateSpace::getExtent()
Definition: StateSpace.h:216
bool decoupled(const StateType *state1, const StateType *state2, double radius, PathType &path, std::array< DubinsStateSpace::StateType *, 3 > &scratch) const
Helper function used by getPath.
bool hasSymmetricInterpolate() const override
Check if the interpolation function on this state space is symmetric, i.e. interpolate(from,...
const RealVectorBounds & getBounds() const
Get the bounds for this state space.
void setTolerance(double tolerance)
@ STATESPACE_TRIANGLE_INEQUALITY
Check whether the triangle inequality holds when using StateSpace::interpolate() and StateSpace::dist...
Definition: StateSpace.h:213
An SE(2) state space where distance is measured by the length of Dubins curves.
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 registerProjections() override
Register the projections for this state space. Usually, this is at least the default projection....
ompl::base::CompoundState StateType
Define the type of state allocated by this state space.
Definition: StateSpace.h:641
Complete description of a Dubins path.
DubinsStateSpace::StateType * get2DPose(double x, double y, double yaw) const
Allocate a DubinsSpace state and initialize it.
A state in SE(2): (x, y, yaw)
bool isMetricSpace() const override
Return true if the distance function associated with the space is a metric.
@ STATESPACE_INTERPOLATION
Check whether calling StateSpace::interpolate() works as expected.
Definition: StateSpace.h:209
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 sanityChecks() const override
Convenience function that allows derived state spaces to choose which checks should pass (see SanityC...
State * allocState() const override
Allocate a state that can store a point in the described space.
The lower and upper bounds for an Rn space.