reeds_shepp_state_space.hpp
Go to the documentation of this file.
1 /*********************************************************************
2 * Copyright (c) 2017 - for information on the respective copyright
3 * owner see the NOTICE file and/or the repository
4 *
5 * https://github.com/hbanzhaf/steering_functions.git
6 *
7 * Licensed under the Apache License, Version 2.0 (the "License");
8 * you may not use this file except in compliance with the License.
9 * You may obtain a copy of the License at
10 *
11 * http://www.apache.org/licenses/LICENSE-2.0
12 *
13 * Unless required by applicable law or agreed to in writing, software
14 * distributed under the License is distributed on an "AS IS" BASIS,
15 * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or
16 * implied. See the License for the specific language governing
17 * permissions and limitations under the License.
18 
19 * This source code is derived from the Open Motion Planning Library
20 * (OMPL) V 1.3.1 (https://github.com/ompl/ompl).
21 * Copyright (c) 2010, Rice University, licensed under the BSD license,
22 * cf. 3rd-party-licenses.txt file in the root directory of this source
23 * tree.
24 **********************************************************************/
25 
26 /*********************************************************************
27 * Software License Agreement (BSD License)
28 *
29 * Copyright (c) 2010, Rice University
30 * All rights reserved.
31 *
32 * Redistribution and use in source and binary forms, with or without
33 * modification, are permitted provided that the following conditions
34 * are met:
35 *
36 * * Redistributions of source code must retain the above copyright
37 * notice, this list of conditions and the following disclaimer.
38 * * Redistributions in binary form must reproduce the above
39 * copyright notice, this list of conditions and the following
40 * disclaimer in the documentation and/or other materials provided
41 * with the distribution.
42 * * Neither the name of the Rice University nor the names of its
43 * contributors may be used to endorse or promote products derived
44 * from this software without specific prior written permission.
45 *
46 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
47 * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
48 * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
49 * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
50 * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
51 * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
52 * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
53 * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
54 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
55 * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
56 * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
57 * POSSIBILITY OF SUCH DAMAGE.
58 *********************************************************************/
59 
60 #ifndef __REEDS_SHEPP_STATE_SPACE_HPP_
61 #define __REEDS_SHEPP_STATE_SPACE_HPP_
62 
63 #include <cassert>
64 #include <limits>
65 #include <vector>
66 
69 
70 namespace steering
71 {
72 
86 class Reeds_Shepp_State_Space
87 {
88 public:
91  {
92  RS_NOP = 0,
93  RS_LEFT = 1,
94  RS_STRAIGHT = 2,
95  RS_RIGHT = 3
96  };
97 
100 
102  class Reeds_Shepp_Path
103  {
104  public:
107  double t = std::numeric_limits<double>::max(), double u = 0., double v = 0., double w = 0.,
108  double x = 0.);
109 
110  double length() const
111  {
112  return total_length_;
113  }
114 
115  private:
118 
120  double length_[5];
121 
123  double total_length_;
124 
125  friend class Reeds_Shepp_State_Space;
126  };
127 
129  Reeds_Shepp_State_Space(double kappa, double discretization = 0.1) : kappa_(kappa), discretization_(discretization)
130  {
131  assert(kappa > 0.0 && discretization > 0.0);
132  kappa_inv_ = 1 / kappa;
133  }
134 
136  void set_filter_parameters(const Motion_Noise &motion_noise, const Measurement_Noise &measurement_noise,
137  const Controller &controller);
138 
140  Reeds_Shepp_Path reeds_shepp(const State &state1, const State &state2) const;
141 
143  double get_distance(const State &state1, const State &state2) const;
144 
146  std::vector<Control> get_controls(const State &state1, const State &state2) const;
147 
149  std::vector<State> get_path(const State &state1, const State &state2) const;
150 
152  std::vector<State_With_Covariance> get_path_with_covariance(const State_With_Covariance &state1,
153  const State &state2) const;
154 
156  std::vector<State> integrate(const State &state, const std::vector<Control> &controls) const;
157 
159  std::vector<State_With_Covariance> integrate_with_covariance(const State_With_Covariance &state,
160  const std::vector<Control> &controls) const;
161 
163  State interpolate(const State &state, const std::vector<Control> &controls, double t) const;
164 
166  inline State integrate_ODE(const State &state, const Control &control, double integration_step) const;
167 
168 private:
170  double kappa_;
171 
173  double kappa_inv_;
174 
176  double discretization_;
177 
179  EKF ekf_;
180 };
181 
182 } // namespace steering
183 
184 #endif
steering::Reeds_Shepp_State_Space::kappa_
double kappa_
Curvature.
Definition: reeds_shepp_state_space.hpp:280
steering::Reeds_Shepp_State_Space::kappa_inv_
double kappa_inv_
Inverse of curvature.
Definition: reeds_shepp_state_space.hpp:283
steering::Reeds_Shepp_State_Space::set_filter_parameters
void set_filter_parameters(const Motion_Noise &motion_noise, const Measurement_Noise &measurement_noise, const Controller &controller)
Sets the parameters required by the filter.
Definition: reeds_shepp_state_space.cpp:535
steering::State
Description of a kinematic car's state.
Definition: steering_functions.hpp:44
steering::Reeds_Shepp_State_Space::Reeds_Shepp_Path::length
double length() const
Definition: reeds_shepp_state_space.hpp:220
steering::Reeds_Shepp_State_Space::discretization_
double discretization_
Discretization of path.
Definition: reeds_shepp_state_space.hpp:286
steering::Reeds_Shepp_State_Space::ekf_
EKF ekf_
Extended Kalman Filter for uncertainty propagation.
Definition: reeds_shepp_state_space.hpp:289
steering::Reeds_Shepp_State_Space::get_path_with_covariance
std::vector< State_With_Covariance > get_path_with_covariance(const State_With_Covariance &state1, const State &state2) const
Returns shortest path including covariances from state1 to state2 with curvature = kappa_.
Definition: reeds_shepp_state_space.cpp:586
steering::Reeds_Shepp_State_Space::RS_NOP
@ RS_NOP
Definition: reeds_shepp_state_space.hpp:257
ekf.hpp
steering::Reeds_Shepp_State_Space::RS_LEFT
@ RS_LEFT
Definition: reeds_shepp_state_space.hpp:258
steering::Reeds_Shepp_State_Space::Reeds_Shepp_Path_Segment_Type
Reeds_Shepp_Path_Segment_Type
The Reeds-Shepp path segment types.
Definition: reeds_shepp_state_space.hpp:200
steering::Reeds_Shepp_State_Space::reeds_shepp_path_type
static const Reeds_Shepp_Path_Segment_Type reeds_shepp_path_type[18][5]
Reeds-Shepp path types.
Definition: reeds_shepp_state_space.hpp:209
steering::Reeds_Shepp_State_Space::Reeds_Shepp_Path::type_
const Reeds_Shepp_Path_Segment_Type * type_
Definition: reeds_shepp_state_space.hpp:227
steering::Control
Description of a path segment with its corresponding control inputs.
Definition: steering_functions.hpp:82
steering::Reeds_Shepp_State_Space::get_path
std::vector< State > get_path(const State &state1, const State &state2) const
Returns shortest path from state1 to state2 with curvature = kappa_.
Definition: reeds_shepp_state_space.cpp:580
steering::Reeds_Shepp_State_Space::interpolate
State interpolate(const State &state, const std::vector< Control > &controls, double t) const
Returns interpolated state at distance t in [0,1] (percent of total path length with curvature = kapp...
Definition: reeds_shepp_state_space.cpp:710
steering::Reeds_Shepp_State_Space::Reeds_Shepp_Path::Reeds_Shepp_Path
Reeds_Shepp_Path(const Reeds_Shepp_Path_Segment_Type *type=reeds_shepp_path_type[0], double t=std::numeric_limits< double >::max(), double u=0., double v=0., double w=0., double x=0.)
Constructor of the Reeds_Shepp_Path.
Definition: reeds_shepp_state_space.cpp:514
steering::Reeds_Shepp_State_Space::Reeds_Shepp_Path::length_
double length_[5]
Definition: reeds_shepp_state_space.hpp:230
steering::EKF
Definition: ekf.hpp:48
steering::Reeds_Shepp_State_Space::get_controls
std::vector< Control > get_controls(const State &state1, const State &state2) const
Returns controls of the shortest path from state1 to state2 with curvature = kappa_.
Definition: reeds_shepp_state_space.cpp:547
steering::Reeds_Shepp_State_Space::integrate_ODE
State integrate_ODE(const State &state, const Control &control, double integration_step) const
Returns integrated state given a start state, a control, and an integration step.
Definition: reeds_shepp_state_space.cpp:773
steering::Reeds_Shepp_State_Space::Reeds_Shepp_State_Space
Reeds_Shepp_State_Space(double kappa, double discretization=0.1)
Constructor of the Reeds_Shepp_State_Space.
Definition: reeds_shepp_state_space.hpp:239
steering_functions.hpp
plot_states.kappa
kappa
Definition: plot_states.py:106
steering::Reeds_Shepp_State_Space::Reeds_Shepp_Path::total_length_
double total_length_
Definition: reeds_shepp_state_space.hpp:233
steering::State_With_Covariance
Description of a kinematic car's state with covariance.
Definition: steering_functions.hpp:63
steering::Reeds_Shepp_State_Space::Reeds_Shepp_Path::Reeds_Shepp_State_Space
friend class Reeds_Shepp_State_Space
Definition: reeds_shepp_state_space.hpp:235
steering
Definition: dubins_state_space.hpp:70
steering::Reeds_Shepp_State_Space::RS_STRAIGHT
@ RS_STRAIGHT
Definition: reeds_shepp_state_space.hpp:259
steering::Reeds_Shepp_State_Space::RS_RIGHT
@ RS_RIGHT
Definition: reeds_shepp_state_space.hpp:260
steering::Reeds_Shepp_State_Space::integrate_with_covariance
std::vector< State_With_Covariance > integrate_with_covariance(const State_With_Covariance &state, const std::vector< Control > &controls) const
Returns integrated states including covariance given a start state and controls with curvature = kapp...
Definition: reeds_shepp_state_space.cpp:642
steering::Reeds_Shepp_State_Space::reeds_shepp
Reeds_Shepp_Path reeds_shepp(const State &state1, const State &state2) const
Returns type and length of segments of path from state1 to state2 with curvature = 1....
Definition: reeds_shepp_state_space.cpp:526
steering::Reeds_Shepp_State_Space::get_distance
double get_distance(const State &state1, const State &state2) const
Returns shortest path length from state1 to state2 with curvature = kappa_.
Definition: reeds_shepp_state_space.cpp:542
steering::Reeds_Shepp_State_Space::integrate
std::vector< State > integrate(const State &state, const std::vector< Control > &controls) const
Returns integrated states given a start state and controls with curvature = kappa_.
Definition: reeds_shepp_state_space.cpp:593


steering_functions
Author(s): Holger Banzhaf
autogenerated on Mon Dec 11 2023 03:27:43