hc_reeds_shepp_state_space.hpp
Go to the documentation of this file.
1 /*********************************************************************
2 * Copyright (c) 2017 Robert Bosch GmbH.
3 * All rights reserved.
4 *
5 * Licensed under the Apache License, Version 2.0 (the "License");
6 * you may not use this file except in compliance with the License.
7 * You may obtain a copy of the License at
8 *
9 * http://www.apache.org/licenses/LICENSE-2.0
10 *
11 * Unless required by applicable law or agreed to in writing, software
12 * distributed under the License is distributed on an "AS IS" BASIS,
13 * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
14 * See the License for the specific language governing permissions and
15 * limitations under the License.
16 * *********************************************************************/
17 
18 #ifndef HC_REEDS_SHEPP_STATE_SPACE_HPP
19 #define HC_REEDS_SHEPP_STATE_SPACE_HPP
20 
21 #include <vector>
22 
30 
31 namespace steering
32 {
33 
38 class HC_Reeds_Shepp_State_Space : public HC_CC_State_Space
39 {
40 public:
42  HC_Reeds_Shepp_State_Space(double kappa, double sigma, double discretization = 0.1);
43 
45  std::vector<std::pair<State, Control>> predict_state(const State& state) const;
46 
48  double get_distance(const State& state1, const State& state2) const;
49 
51  std::vector<Control> get_controls(const State& state1, const State& state2) const;
52 
53 private:
59 };
60 
61 } // namespace steering
62 
63 #endif
hc_cc_state_space.hpp
steering::HCpmpm_Reeds_Shepp_State_Space
An implementation of hybrid curvature (HC) steer with either positive (p) or negative (n) max....
Definition: hcpmpm_reeds_shepp_state_space.hpp:74
steering::HC_Reeds_Shepp_State_Space::hcpm0_reeds_shepp_state_space_
HCpm0_Reeds_Shepp_State_Space hcpm0_reeds_shepp_state_space_
Definition: hc_reeds_shepp_state_space.hpp:87
steering::HC00_Reeds_Shepp_State_Space
An implementation of hybrid curvature (HC) steer with zero curvature at the start and goal configurat...
Definition: hc00_reeds_shepp_state_space.hpp:73
steering::HC0pm_Reeds_Shepp_State_Space
An implementation of hybrid curvature (HC) steer with zero curvature at the start configuration and e...
Definition: hc0pm_reeds_shepp_state_space.hpp:74
hc0pm_reeds_shepp_state_space.hpp
steering::HC_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: hc_reeds_shepp_state_space.cpp:144
steering::HC_Reeds_Shepp_State_Space::hcpmpm_reeds_shepp_state_space_
HCpmpm_Reeds_Shepp_State_Space hcpmpm_reeds_shepp_state_space_
Definition: hc_reeds_shepp_state_space.hpp:88
paths.hpp
steering::HC_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: hc_reeds_shepp_state_space.cpp:92
hc00_reeds_shepp_state_space.hpp
hcpm0_reeds_shepp_state_space.hpp
steering::HCpm0_Reeds_Shepp_State_Space
An implementation of hybrid curvature (HC) steer with either positive (p) or negative (n) max....
Definition: hcpm0_reeds_shepp_state_space.hpp:74
steering::HC_Reeds_Shepp_State_Space::hc00_reeds_shepp_state_space_
HC00_Reeds_Shepp_State_Space hc00_reeds_shepp_state_space_
Required state spaces.
Definition: hc_reeds_shepp_state_space.hpp:85
steering_functions.hpp
plot_states.kappa
kappa
Definition: plot_states.py:106
steering::HC_Reeds_Shepp_State_Space::predict_state
std::vector< std::pair< State, Control > > predict_state(const State &state) const
Predicts a state forwards and backwards to zero and max. curvature.
Definition: hc_reeds_shepp_state_space.cpp:39
steering
Definition: dubins_state_space.hpp:70
hcpmpm_reeds_shepp_state_space.hpp
steering::HC_Reeds_Shepp_State_Space::hc0pm_reeds_shepp_state_space_
HC0pm_Reeds_Shepp_State_Space hc0pm_reeds_shepp_state_space_
Definition: hc_reeds_shepp_state_space.hpp:86
steering::HC_Reeds_Shepp_State_Space::HC_Reeds_Shepp_State_Space
HC_Reeds_Shepp_State_Space(double kappa, double sigma, double discretization=0.1)
Constructor.
Definition: hc_reeds_shepp_state_space.cpp:30


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