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 <vector>
41 #include "ompl/base/spaces/SE2StateSpace.h"
42 #include "ompl/base/MotionValidator.h"
43 #include <boost/math/constants/constants.hpp>
44 
45 namespace ompl
46 {
47  namespace base
48  {
62  class DubinsStateSpace : public SE2StateSpace
63  {
64  public:
67  {
68  DUBINS_LEFT = 0,
69  DUBINS_STRAIGHT = 1,
70  DUBINS_RIGHT = 2
71  };
72 
74  static const std::vector<std::vector<DubinsPathSegmentType>> dubinsPathType;
76  class DubinsPath
77  {
78  public:
79  DubinsPath(const std::vector<DubinsPathSegmentType> *type = &dubinsPathType[0],
80  double t = 0., double p = std::numeric_limits<double>::max(), double q = 0.)
81  : type_(type)
82  {
83  length_[0] = t;
84  length_[1] = p;
85  length_[2] = q;
86  assert(t >= 0.);
87  assert(p >= 0.);
88  assert(q >= 0.);
89  }
90  double length() const
91  {
92  return length_[0] + length_[1] + length_[2];
93  }
94 
95  friend std::ostream& operator<<(std::ostream& os, const DubinsPath& path);
97  const std::vector<DubinsPathSegmentType> *type_;
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  {
107  setName("Dubins" + getName());
109  }
110 
111  bool isMetricSpace() const override
112  {
113  return false;
114  }
115 
116  double distance(const State *state1, const State *state2) const override;
117  static double distance(const State *state1, const State *state2, double radius);
118  static double symmetricDistance(const State *state1, const State *state2, double radius);
119 
120  void interpolate(const State *from, const State *to, double t, State *state) const override;
121  virtual void interpolate(const State *from, const State *to, double t, bool &firstTime,
122  DubinsPath &path, State *state) const;
123  virtual void interpolate(const State *from, const DubinsPath &path, double t, State *state, double radius) const;
124 
125  bool hasSymmetricDistance() const override
126  {
127  return isSymmetric_;
128  }
129 
130  bool hasSymmetricInterpolate() const override
131  {
132  return isSymmetric_;
133  }
134 
135  unsigned int validSegmentCount(const State *state1, const State *state2) const override;
136 
137  void sanityChecks() const override
138  {
139  double zero = std::numeric_limits<double>::epsilon();
140  double eps = std::numeric_limits<float>::epsilon();
142  if (!isSymmetric_)
144  StateSpace::sanityChecks(zero, eps, flags);
145  }
146 
148  DubinsPath dubins(const State *state1, const State *state2) const;
150  static DubinsPath dubins(const State *state1, const State *state2, double radius);
151 
152  protected:
154  double rho_;
155 
163  bool isSymmetric_;
164  };
165 
173  {
174  public:
176  {
177  defaultSettings();
178  }
180  {
181  defaultSettings();
182  }
183  ~DubinsMotionValidator() override = default;
184  bool checkMotion(const State *s1, const State *s2) const override;
185  bool checkMotion(const State *s1, const State *s2, std::pair<State *, double> &lastValid) const override;
186 
187  private:
188  DubinsStateSpace *stateSpace_;
189  void defaultSettings();
190  };
191  }
192 }
193 
194 #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,...
The base class for space information. This contains all the information about the space planning is d...
A shared pointer wrapper for ompl::base::SpaceInformation.
static const std::vector< std::vector< DubinsPathSegmentType > > dubinsPathType
Dubins path types.
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...
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
@ STATESPACE_DISTANCE_BOUND
Check whether the StateSpace::distance() is bounded by StateSpace::getExtent()
Definition: StateSpace.h:216
MotionValidator(SpaceInformation *si)
Constructor.
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.
An SE(2) state space where distance is measured by the length of Dubins curves.
const std::string & getName() const
Get the name of the state space.
Definition: StateSpace.cpp:196
void setName(const std::string &name)
Set the name of the state space.
Definition: StateSpace.cpp:201
int type_
A type assigned for this state space.
Definition: StateSpace.h:595
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...
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.
DubinsPath dubins(const State *state1, const State *state2) const
Return a shortest Dubins path from SE(2) state state1 to SE(2) state state2.
const std::vector< DubinsPathSegmentType > * type_
bool isSymmetric_
Whether the distance is "symmetrized".
@ STATESPACE_INTERPOLATION
Check whether calling StateSpace::interpolate() works as expected.
Definition: StateSpace.h:209
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.
DubinsPathSegmentType
The Dubins path segment type.
Main namespace. Contains everything in this library.
Definition: AppBase.h:21