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  {
64  class DubinsStateSpace : public SE2StateSpace
65  {
66  public:
69  {
70  DUBINS_LEFT = 0,
71  DUBINS_STRAIGHT = 1,
72  DUBINS_RIGHT = 2
73  };
75  static const DubinsPathSegmentType dubinsPathType[6][3];
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)
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_{false};
102  };
103 
104  DubinsStateSpace(double turningRadius = 1.0, bool isSymmetric = false)
105  : rho_(turningRadius), isSymmetric_(isSymmetric)
106  {
108  }
109 
110  bool isMetricSpace() const override
111  {
112  return false;
113  }
114 
115  double distance(const State *state1, const State *state2) const override;
116 
117  void interpolate(const State *from, const State *to, double t, State *state) const override;
118  virtual void interpolate(const State *from, const State *to, double t, bool &firstTime,
119  DubinsPath &path, State *state) const;
120 
121  bool hasSymmetricDistance() const override
122  {
123  return isSymmetric_;
124  }
125 
126  bool hasSymmetricInterpolate() const override
127  {
128  return isSymmetric_;
129  }
130 
131  void sanityChecks() const override
132  {
133  double zero = std::numeric_limits<double>::epsilon();
134  double eps = std::numeric_limits<float>::epsilon();
136  if (!isSymmetric_)
138  StateSpace::sanityChecks(zero, eps, flags);
139  }
140 
142  DubinsPath dubins(const State *state1, const State *state2) const;
143 
144  protected:
145  virtual void interpolate(const State *from, const DubinsPath &path, double t, State *state) const;
146 
148  double rho_;
149 
157  bool isSymmetric_;
158  };
159 
166  class DubinsMotionValidator : public MotionValidator
167  {
168  public:
169  DubinsMotionValidator(SpaceInformation *si) : MotionValidator(si)
170  {
171  defaultSettings();
172  }
174  {
175  defaultSettings();
176  }
177  ~DubinsMotionValidator() override = default;
178  bool checkMotion(const State *s1, const State *s2) const override;
179  bool checkMotion(const State *s1, const State *s2, std::pair<State *, double> &lastValid) const override;
180 
181  private:
182  DubinsStateSpace *stateSpace_;
183  void defaultSettings();
184  };
185  }
186 }
187 
188 #endif
@ STATESPACE_DISTANCE_SYMMETRIC
Check whether the distance function is symmetric (StateSpace::distance())
Definition: StateSpace.h:206
bool hasSymmetricInterpolate() const override
Check if the interpolation function on this state space is symmetric, i.e. interpolate(from,...
A shared pointer wrapper for ompl::base::SpaceInformation.
void sanityChecks() const override
Convenience function that allows derived state spaces to choose which checks should pass (see SanityC...
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 hasSymmetricDistance() const override
Check if the distance function on this state space is symmetric, i.e. distance(s1,...
Definition of an abstract state.
Definition: State.h:113
virtual void sanityChecks() const
Convenience function that allows derived state spaces to choose which checks should pass (see SanityC...
Definition: StateSpace.cpp:603
DubinsPath dubins(const State *state1, const State *state2) const
Return a shortest Dubins path from SE(2) state state1 to SE(2) state state2.
@ STATESPACE_DISTANCE_BOUND
Check whether the StateSpace::distance() is bounded by StateSpace::getExtent()
Definition: StateSpace.h:216
MotionValidator(SpaceInformation *si)
Constructor.
static const DubinsPathSegmentType dubinsPathType[6][3]
Dubins path types.
Abstract definition for a class checking the validity of motions – path segments between states....
bool checkMotion(const State *s1, const State *s2) const override
Check if the path between two states (from s1 to s2) is valid. This function assumes s1 is valid.
@ STATE_SPACE_DUBINS
ompl::base::DubinsStateSpace
@ STATESPACE_TRIANGLE_INEQUALITY
Check whether the triangle inequality holds when using StateSpace::interpolate() and StateSpace::dist...
Definition: StateSpace.h:213
double rho_
Turning radius.
const DubinsPathSegmentType * type_
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...
int type_
A type assigned for this state space.
Definition: StateSpace.h:595
A Dubins motion validator that only uses the state validity checker. Motions are checked for validity...
bool isMetricSpace() const override
Return true if the distance function associated with the space is a metric.
bool isSymmetric_
Whether the distance is "symmetrized".
@ STATESPACE_INTERPOLATION
Check whether calling StateSpace::interpolate() works as expected.
Definition: StateSpace.h:209
DubinsPathSegmentType
The Dubins path segment type.
Main namespace. Contains everything in this library.
Definition: AppBase.h:21