VanaStateSpace.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_VANA_STATE_SPACE_
38 #define OMPL_BASE_SPACES_VANA_STATE_SPACE_
39 
40 #include "ompl/base/spaces/DubinsStateSpace.h"
41 #include <optional>
42 
43 namespace ompl::base
44 {
60  class VanaStateSpace : public CompoundStateSpace
61  {
62  public:
63  class PathType
64  {
65  public:
66  PathType();
67  PathType(const PathType &path);
68  ~PathType();
69  double length() const;
70  PathType &operator=(const PathType &path);
71 
72  friend std::ostream &operator<<(std::ostream &os, const PathType &path);
73 
74  double horizontalRadius_{1.};
75  double verticalRadius_{1.};
76 
77  DubinsStateSpace::DubinsPath pathXY_;
78  DubinsStateSpace::DubinsPath pathSZ_;
79  DubinsStateSpace::StateType *startSZ_{nullptr};
80  };
81 
84  {
85  public:
86  StateType() = default;
87  double operator[](unsigned index) const
88  {
89  return as<RealVectorStateSpace::StateType>(0)->values[index];
90  }
91  double &operator[](unsigned index)
92  {
93  return as<RealVectorStateSpace::StateType>(0)->values[index];
94  }
95  double yaw() const
96  {
97  return as<SO2StateSpace::StateType>(1)->value;
98  }
99  double &yaw()
100  {
101  return as<SO2StateSpace::StateType>(1)->value;
102  }
103  double pitch() const
104  {
105  return as<RealVectorStateSpace::StateType>(0)->values[3];
106  }
107  double &pitch()
108  {
109  return as<RealVectorStateSpace::StateType>(0)->values[3];
110  }
111  };
112 
113  VanaStateSpace(double turningRadius = 1.0, double maxPitch = boost::math::double_constants::sixth_pi);
114  VanaStateSpace(double turningRadius, std::pair<double, double> pitchRange);
115  ~VanaStateSpace() override = default;
116 
117  bool isMetricSpace() const override
118  {
119  return false;
120  }
121  bool hasSymmetricDistance() const override
122  {
123  return false;
124  }
125 
126  bool hasSymmetricInterpolate() const override
127  {
128  return false;
129  }
130 
131  void sanityChecks() const override
132  {
133  double zero = std::numeric_limits<double>::epsilon();
134  double eps = std::numeric_limits<float>::epsilon();
137  StateSpace::sanityChecks(zero, eps, flags);
138  }
139 
141  void setBounds(const RealVectorBounds &bounds)
142  {
143  RealVectorBounds b(bounds);
144  if (bounds.low.size() < 4)
145  {
146  b.resize(4);
147  b.low[3] = minPitch_;
148  b.high[3] = maxPitch_;
149  }
150  as<RealVectorStateSpace>(0)->setBounds(b);
151  }
152 
154  const RealVectorBounds &getBounds() const
155  {
156  return as<RealVectorStateSpace>(0)->getBounds();
157  }
158 
160  void setTolerance(double tolerance)
161  {
162  tolerance_ = tolerance;
163  }
165  double getTolerance()
166  {
167  return tolerance_;
168  }
169 
170  State *allocState() const override;
171  void registerProjections() override;
172 
173  double distance(const State *state1, const State *state2) const override;
174 
175  unsigned int validSegmentCount(const State *state1, const State *state2) const override;
176 
177  void interpolate(const State *from, const State *to, double t, State *state) const override;
190  virtual void interpolate(const State *from, const State *to, double t, PathType &path, State *state) const;
200  virtual void interpolate(const State *from, const PathType &path, double t, State *state) const;
201 
209  std::optional<PathType> getPath(const State *state1, const State *state2) const;
210 
221  bool decoupled(const State *state1, const State *state2, double radius, PathType &path,
222  DubinsStateSpace::StateType *endSZ) const;
223 
224  protected:
233  DubinsStateSpace::StateType *get2DPose(double x, double y, double yaw) const;
234 
236  double rho_;
238  double minPitch_;
240  double maxPitch_;
242  double tolerance_{1e-8};
245  };
246 } // namespace ompl::base
247 
248 #endif
@ STATESPACE_DISTANCE_SYMMETRIC
Check whether the distance function is symmetric (StateSpace::distance())
Definition: StateSpace.h:206
bool hasSymmetricDistance() const override
Check if the distance function on this state space is symmetric, i.e. distance(s1,...
bool isMetricSpace() const override
Return true if the distance function associated with the space is a metric.
void registerProjections() override
Register the projections for this state space. Usually, this is at least the default projection....
Definition of an abstract state.
Definition: State.h:113
bool decoupled(const State *state1, const State *state2, double radius, PathType &path, DubinsStateSpace::StateType *endSZ) const
Helper function used by getPath.
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.
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
@ STATESPACE_DISTANCE_BOUND
Check whether the StateSpace::distance() is bounded by StateSpace::getExtent()
Definition: StateSpace.h:216
void setBounds(const RealVectorBounds &bounds)
Set the bounds of this state space. This defines the range of the space in which sampling is performe...
DubinsStateSpace dubinsSpace_
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.
DubinsStateSpace::StateType * get2DPose(double x, double y, double yaw) const
Allocate a DubinsSpace state and initialize it.
ompl::base::CompoundState StateType
Define the type of state allocated by this state space.
Definition: StateSpace.h:641
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....
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.
A state in SE(2): (x, y, yaw)
void sanityChecks() const override
Convenience function that allows derived state spaces to choose which checks should pass (see SanityC...
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...
@ STATESPACE_INTERPOLATION
Check whether calling StateSpace::interpolate() works as expected.
Definition: StateSpace.h:209
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.