DubinsStateSpace.h
1 /*********************************************************************
2 * Software License Agreement (BSD License)
3 *
4 * Copyright (c) 2010, Rice University
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 Rice University 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_DUBINS_STATE_SPACE_
38 #define OMPL_BASE_SPACES_DUBINS_STATE_SPACE_
39 
40 #include "ompl/base/spaces/SE2StateSpace.h"
41 #include "ompl/base/MotionValidator.h"
42 #include <boost/math/constants/constants.hpp>
43 
44 namespace ompl
45 {
46  namespace base
47  {
65  {
66  public:
69  {
70  DUBINS_LEFT = 0,
71  DUBINS_STRAIGHT = 1,
72  DUBINS_RIGHT = 2
73  };
77  class DubinsPath
78  {
79  public:
80  DubinsPath(const DubinsPathSegmentType *type = dubinsPathType[0], double t = 0.,
81  double p = std::numeric_limits<double>::max(), double q = 0.)
82  : type_(type), reverse_(false)
83  {
84  length_[0] = t;
85  length_[1] = p;
86  length_[2] = q;
87  assert(t >= 0.);
88  assert(p >= 0.);
89  assert(q >= 0.);
90  }
91  double length() const
92  {
93  return length_[0] + length_[1] + length_[2];
94  }
95 
99  double length_[3];
101  bool reverse_;
102  };
103 
104  DubinsStateSpace(double turningRadius = 1.0, bool isSymmetric = false)
105  : SE2StateSpace(), rho_(turningRadius), isSymmetric_(isSymmetric)
106  {
107  }
108 
109  bool isMetricSpace() const override
110  {
111  return false;
112  }
113 
114  double distance(const State *state1, const State *state2) const override;
115 
116  void interpolate(const State *from, const State *to, const double t, State *state) const override;
117  virtual void interpolate(const State *from, const State *to, const double t, bool &firstTime,
118  DubinsPath &path, State *state) const;
119 
120  bool hasSymmetricDistance() const override
121  {
122  return isSymmetric_;
123  }
124 
125  bool hasSymmetricInterpolate() const override
126  {
127  return isSymmetric_;
128  }
129 
130  void sanityChecks() const override
131  {
132  double zero = std::numeric_limits<double>::epsilon();
133  double eps = std::numeric_limits<float>::epsilon();
135  if (!isSymmetric_)
137  StateSpace::sanityChecks(zero, eps, flags);
138  }
139 
141  DubinsPath dubins(const State *state1, const State *state2) const;
142 
143  protected:
144  virtual void interpolate(const State *from, const DubinsPath &path, const double t, State *state) const;
145 
147  double rho_;
148 
157  };
158 
166  {
167  public:
169  {
170  defaultSettings();
171  }
173  {
174  defaultSettings();
175  }
176  ~DubinsMotionValidator() override = default;
177  bool checkMotion(const State *s1, const State *s2) const override;
178  bool checkMotion(const State *s1, const State *s2, std::pair<State *, double> &lastValid) const override;
179 
180  private:
181  DubinsStateSpace *stateSpace_;
182  void defaultSettings();
183  };
184  }
185 }
186 
187 #endif
bool isMetricSpace() const override
Return true if the distance function associated with the space is a metric.
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...
Check whether the StateSpace::distance() is bounded by StateSpace::getExtent()
Definition: StateSpace.h:152
An SE(2) state space where distance is measured by the length of Dubins curves.
DubinsPathSegmentType
The Dubins path segment type.
const DubinsPathSegmentType * type_
Abstract definition for a class checking the validity of motions – path segments between states...
Main namespace. Contains everything in this library.
Definition: AppBase.h:21
void sanityChecks() const override
Convenience function that allows derived state spaces to choose which checks should pass (see SanityC...
bool hasSymmetricInterpolate() const override
Check if the interpolation function on this state space is symmetric, i.e. interpolate(from, to, t, state) = interpolate(to, from, 1-t, state). Default implementation returns true.
A state space representing SE(2)
Definition: SE2StateSpace.h:49
bool isSymmetric_
Whether the distance is "symmetrized".
void interpolate(const State *from, const State *to, const 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...
A shared pointer wrapper for ompl::base::SpaceInformation.
The base class for space information. This contains all the information about the space planning is d...
Definition of an abstract state.
Definition: State.h:49
Check whether the triangle inequality holds when using StateSpace::interpolate() and StateSpace::dist...
Definition: StateSpace.h:149
A Dubins motion validator that only uses the state validity checker. Motions are checked for validity...
virtual void sanityChecks() const
Convenience function that allows derived state spaces to choose which checks should pass (see SanityC...
DubinsPath dubins(const State *state1, const State *state2) const
Return the shortest Dubins path from SE(2) state state1 to SE(2) state state2.
Check whether the distance function is symmetric (StateSpace::distance())
Definition: StateSpace.h:142
Check whether calling StateSpace::interpolate() works as expected.
Definition: StateSpace.h:145
static const DubinsPathSegmentType dubinsPathType[6][3]
Dubins path types.
Complete description of a Dubins path.
bool hasSymmetricDistance() const override
Check if the distance function on this state space is symmetric, i.e. distance(s1,s2) = distance(s2,s1). Default implementation returns true.
double rho_
Turning radius.