hcpmpm_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 Continuous Curvature (CC) Steer.
20 * Copyright (c) 2016, Thierry Fraichard and Institut national de
21 * recherche en informatique et en automatique (Inria), licensed under
22 * the BSD license, cf. 3rd-party-licenses.txt file in the root
23 * directory of this source tree.
24 **********************************************************************/
25 
26 #ifndef HCPMPM_REEDS_SHEPP_STATE_SPACE_HPP
27 #define HCPMPM_REEDS_SHEPP_STATE_SPACE_HPP
28 
29 #include <memory>
30 #include <vector>
31 
36 
37 namespace steering
38 {
39 
51 class HCpmpm_Reeds_Shepp_State_Space : public HC_CC_State_Space
52 {
53 public:
55  HCpmpm_Reeds_Shepp_State_Space(double kappa, double sigma, double discretization = 0.1);
56 
59 
61  HC_CC_RS_Path* hcpmpm_circles_rs_path(const HC_CC_Circle& c1, const HC_CC_Circle& c2) const;
62 
64  HC_CC_RS_Path* hcpmpm_reeds_shepp(const State& state1, const State& state2) const;
65 
67  double get_distance(const State& state1, const State& state2) const;
68 
70  std::vector<Control> get_controls(const State& state1, const State& state2) const;
71 
72 private:
75 
77  std::unique_ptr<HCpmpm_Reeds_Shepp> hcpmpm_reeds_shepp_;
78 
81 
83  double radius_;
84 
86  double mu_;
87 
89  double sin_mu_, cos_mu_;
90 };
91 
92 } // namespace steering
93 
94 #endif
steering::HCpmpm_Reeds_Shepp_State_Space::HCpmpm_Reeds_Shepp
Definition: hcpmpm_reeds_shepp_state_space.cpp:41
hc_cc_state_space.hpp
steering::HC_CC_Circle_Param
Definition: hc_cc_circle.hpp:57
steering::HCpmpm_Reeds_Shepp_State_Space::rs_circle_param_
HC_CC_Circle_Param rs_circle_param_
Parameter of a rs-circle.
Definition: hcpmpm_reeds_shepp_state_space.hpp:126
paths.hpp
steering::HCpmpm_Reeds_Shepp_State_Space::sin_mu_
double sin_mu_
Sine and cosine of mu.
Definition: hcpmpm_reeds_shepp_state_space.hpp:135
hc_cc_circle.hpp
steering::HCpmpm_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.
Definition: hcpmpm_reeds_shepp_state_space.cpp:1839
steering::HCpmpm_Reeds_Shepp_State_Space::hcpmpm_reeds_shepp
HC_CC_RS_Path * hcpmpm_reeds_shepp(const State &state1, const State &state2) const
Returns a sequence of turns and straight lines connecting a start and an end configuration.
Definition: hcpmpm_reeds_shepp_state_space.cpp:1738
steering::HCpmpm_Reeds_Shepp_State_Space::hcpmpm_circles_rs_path
HC_CC_RS_Path * hcpmpm_circles_rs_path(const HC_CC_Circle &c1, const HC_CC_Circle &c2) const
Returns a sequence of turns and straight lines connecting the two circles c1 and c2.
Definition: hcpmpm_reeds_shepp_state_space.cpp:1568
steering::HCpmpm_Reeds_Shepp_State_Space::mu_
double mu_
Angle between a configuration on the hc-/cc-circle and the tangent to the circle at that position.
Definition: hcpmpm_reeds_shepp_state_space.hpp:132
steering::HCpmpm_Reeds_Shepp_State_Space::get_distance
double get_distance(const State &state1, const State &state2) const
Returns shortest path length from state1 to state2.
Definition: hcpmpm_reeds_shepp_state_space.cpp:1831
steering_functions.hpp
plot_states.kappa
kappa
Definition: plot_states.py:106
steering::HCpmpm_Reeds_Shepp_State_Space::HCpmpm_Reeds_Shepp_State_Space
HCpmpm_Reeds_Shepp_State_Space(double kappa, double sigma, double discretization=0.1)
Constructor.
Definition: hcpmpm_reeds_shepp_state_space.cpp:1555
steering::HCpmpm_Reeds_Shepp_State_Space::radius_
double radius_
Outer radius of a hc-/cc-circle.
Definition: hcpmpm_reeds_shepp_state_space.hpp:129
steering
Definition: dubins_state_space.hpp:70
steering::HCpmpm_Reeds_Shepp_State_Space::hcpmpm_reeds_shepp_
std::unique_ptr< HCpmpm_Reeds_Shepp > hcpmpm_reeds_shepp_
Pimpl Idiom: unique pointer on class with families
Definition: hcpmpm_reeds_shepp_state_space.hpp:120
steering::HCpmpm_Reeds_Shepp_State_Space::cos_mu_
double cos_mu_
Definition: hcpmpm_reeds_shepp_state_space.hpp:135
steering::HCpmpm_Reeds_Shepp_State_Space::~HCpmpm_Reeds_Shepp_State_Space
~HCpmpm_Reeds_Shepp_State_Space()
Destructor.


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