Loading...
Searching...
No Matches
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
45namespace 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();
75
77 class PathType
78 {
79 public:
80 PathType(const std::vector<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
96 friend std::ostream &operator<<(std::ostream &os, const PathType &path);
98 const std::vector<DubinsPathSegmentType> *type_;
100 double length_[3];
102 bool reverse_{false};
103 };
104
105 DubinsStateSpace(double turningRadius = 1.0, bool isSymmetric = false)
106 : rho_(turningRadius), isSymmetric_(isSymmetric)
107 {
108 setName("Dubins" + getName());
110 }
111
112 bool isMetricSpace() const override
113 {
114 return false;
115 }
116
117 double distance(const State *state1, const State *state2) const override;
118 static double distance(const State *state1, const State *state2, double radius);
119 static double symmetricDistance(const State *state1, const State *state2, double radius);
120
121 void interpolate(const State *from, const State *to, double t, State *state) const override;
122 virtual void interpolate(const State *from, const State *to, double t, bool &firstTime, PathType &path,
123 State *state) const;
124 virtual void interpolate(const State *from, const PathType &path, double t, State *state,
125 double radius) const;
126
127 bool hasSymmetricDistance() const override
128 {
129 return isSymmetric_;
130 }
131
132 bool hasSymmetricInterpolate() const override
133 {
134 return isSymmetric_;
135 }
136
137 unsigned int validSegmentCount(const State *state1, const State *state2) const override;
138
139 void sanityChecks() const override
140 {
141 double zero = std::numeric_limits<double>::epsilon();
142 double eps = std::numeric_limits<float>::epsilon();
144 if (!isSymmetric_)
146 StateSpace::sanityChecks(zero, eps, flags);
147 }
148
150 PathType getPath(const State *state1, const State *state2) const;
152 static PathType getPath(const State *state1, const State *state2, double radius);
153
154 protected:
156 double rho_;
157
166 };
167 } // namespace base
168} // namespace ompl
169
170#endif
const std::vector< DubinsPathSegmentType > * type_
An SE(2) state space where distance is measured by the length of Dubins curves.
static const std::vector< std::vector< DubinsPathSegmentType > > & dubinsPathType()
Dubins path types.
DubinsPathSegmentType
The Dubins path segment type.
bool isMetricSpace() const override
Return true if the distance function associated with the space is a metric.
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,...
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...
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....
PathType getPath(const State *state1, const State *state2) const
Return a shortest Dubins path from SE(2) state state1 to SE(2) state state2.
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,...
bool isSymmetric_
Whether the distance is "symmetrized".
@ STATESPACE_DISTANCE_BOUND
Check whether the StateSpace::distance() is bounded by StateSpace::getExtent().
Definition StateSpace.h:152
@ STATESPACE_INTERPOLATION
Check whether calling StateSpace::interpolate() works as expected.
Definition StateSpace.h:145
@ STATESPACE_TRIANGLE_INEQUALITY
Check whether the triangle inequality holds when using StateSpace::interpolate() and StateSpace::dist...
Definition StateSpace.h:149
@ STATESPACE_DISTANCE_SYMMETRIC
Check whether the distance function is symmetric (StateSpace::distance()).
Definition StateSpace.h:142
int type_
A type assigned for this state space.
Definition StateSpace.h:531
virtual void sanityChecks() const
Convenience function that allows derived state spaces to choose which checks should pass (see SanityC...
void setName(const std::string &name)
Set the name of the state space.
const std::string & getName() const
Get the name of the state space.
Definition of an abstract state.
Definition State.h:50
This namespace contains sampling based planning routines shared by both planning under geometric cons...
@ STATE_SPACE_DUBINS
ompl::base::DubinsStateSpace
Main namespace. Contains everything in this library.