Loading...
Searching...
No Matches
TrochoidStateSpace.h
1/*********************************************************************
2 * Software License Agreement (BSD License)
3 *
4 * Copyright (c) 2025, Autonomous Systems Laboratory, ETH Zurich
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 ETH Zurich 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: Jaeyoung Lim */
36
37#ifndef OMPL_BASE_SPACES_TROCHOID_STATE_SPACE_
38#define OMPL_BASE_SPACES_TROCHOID_STATE_SPACE_
39
40#include "ompl/base/spaces/SE2StateSpace.h"
41#include "ompl/base/MotionValidator.h"
42#include <boost/math/constants/constants.hpp>
43#include <optional>
44
45namespace ompl
46{
47 namespace base
48 {
59 class TrochoidStateSpace : public SE2StateSpace
60 {
61 public:
64 {
65 TROCHOID_LEFT = 0,
66 TROCHOID_STRAIGHT = 1,
67 TROCHOID_RIGHT = 2
68 };
69
71 static const std::vector<std::vector<TrochoidPathSegmentType>> &dubinsPathType();
73 class PathType
74 {
75 public:
76 PathType(const std::vector<TrochoidPathSegmentType> &type = dubinsPathType()[0], double tA = 0.,
77 double p = std::numeric_limits<double>::max(), double tB = 0., double t_2pi = 0.)
78 : type_(&type)
79 {
80 length_[0] = tA;
81 length_[1] = p;
82 length_[2] = t_2pi - tB;
83 assert(tA >= 0.);
84 assert(p >= 0.);
85 assert(t_2pi - tB >= 0.);
86 }
87 double length() const
88 {
89 return length_[0] + length_[1] + length_[2];
90 }
91
92 friend std::ostream &operator<<(std::ostream &os, const PathType &path);
94 const std::vector<TrochoidPathSegmentType> *type_;
96 double length_[3];
98 bool reverse_{false};
99 };
100
101 TrochoidStateSpace(double turningRadius = 1.0, double windRatio = 0.0, double windDirection = 0.0,
102 bool isSymmetric = false)
103 : rho_(turningRadius), eta_(windRatio), psi_w_(windDirection), isSymmetric_(isSymmetric)
104 {
105 setName("Trochoid" + getName());
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 static double distance(const State *state1, const State *state2, double radius, double wind_ratio,
116 double wind_heading);
117 static double symmetricDistance(const State *state1, const State *state2, double radius, double wind_ratio,
118 double wind_heading);
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, PathType &path,
122 State *state) const;
123 virtual void interpolate(const State *from, const PathType &path, double t, State *state, double radius,
124 double wind_ratio, double wind_heading) const;
125
126 bool hasSymmetricDistance() const override
127 {
128 return isSymmetric_;
129 }
130
131 bool hasSymmetricInterpolate() const override
132 {
133 return isSymmetric_;
134 }
135
136 unsigned int validSegmentCount(const State *state1, const State *state2) const override;
137
138 void sanityChecks() const override
139 {
140 double zero = std::numeric_limits<double>::epsilon();
141 double eps = std::numeric_limits<float>::epsilon();
143 if (!isSymmetric_)
145 StateSpace::sanityChecks(zero, eps, flags);
146 }
147
149 PathType getPath(const State *state1, const State *state2, bool periodic = false) const;
151 static PathType getPath(const State *state1, const State *state2, double radius, double wind_ratio,
152 double wind_heading, bool periodic = false);
153
154 protected:
156 double rho_;
157
159 double eta_;
160
162 double psi_w_;
163
172 };
173 } // namespace base
174} // namespace ompl
175
176#endif
@ 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
const std::vector< TrochoidPathSegmentType > * type_
An SE(2) state space where distance is measured by the length of Trochoid shortest paths 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...
bool hasSymmetricDistance() const override
Check if the distance function on this state space is symmetric, i.e. distance(s1,...
bool hasSymmetricInterpolate() const override
Check if the interpolation function on this state space is symmetric, i.e. interpolate(from,...
static const std::vector< std::vector< TrochoidPathSegmentType > > & dubinsPathType()
Dubins path types.
TrochoidPathSegmentType
The Dubins path segment type.
bool isSymmetric_
Whether the distance is "symmetrized".
double psi_w_
Wind direction [0, 2pi].
void sanityChecks() const override
Convenience function that allows derived state spaces to choose which checks should pass (see SanityC...
PathType getPath(const State *state1, const State *state2, bool periodic=false) const
Return a shortest Dubins path from SE(2) state state1 to SE(2) state state2.
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....
bool isMetricSpace() const override
Return true if the distance function associated with the space is a metric.
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....
This namespace contains sampling based planning routines shared by both planning under geometric cons...
@ STATE_SPACE_TROCHOID
ompl::base::TrochoidStateSpace
Main namespace. Contains everything in this library.