cc0pm_dubins_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 CC0PM_DUBINS_STATE_SPACE_HPP
27 #define CC0PM_DUBINS_STATE_SPACE_HPP
28 
29 #include <memory>
30 #include <vector>
31 
36 
37 namespace steering
38 {
39 
46 class CC0pm_Dubins_State_Space : public HC_CC_State_Space
47 {
48 public:
50  CC0pm_Dubins_State_Space(double kappa, double sigma, double discretization = 0.1, bool forwards = true);
51 
54 
56  CC_Dubins_Path* cc0pm_circles_dubins_path(const HC_CC_Circle& c1, const HC_CC_Circle& c2) const;
57 
59  CC_Dubins_Path* cc0pm_dubins(const State& state1, const State& state2) const;
60 
62  double get_distance(const State& state1, const State& state2) const;
63 
65  std::vector<Control> get_controls(const State& state1, const State& state2) const;
66 
67 private:
69  bool forwards_;
70 
72  class CC0pm_Dubins;
73 
75  std::unique_ptr<CC0pm_Dubins> cc0pm_dubins_;
76 
79 
81  double radius_;
82 
84  double mu_;
85 };
86 
87 } // namespace steering
88 
89 #endif
hc_cc_state_space.hpp
steering::CC0pm_Dubins_State_Space::get_distance
double get_distance(const State &state1, const State &state2) const
Returns shortest path length from state1 to state2.
Definition: cc0pm_dubins_state_space.cpp:508
steering::HC_CC_Circle_Param
Definition: hc_cc_circle.hpp:57
steering::CC0pm_Dubins_State_Space::rs_circle_param_
HC_CC_Circle_Param rs_circle_param_
Parameter of a rs-circle.
Definition: cc0pm_dubins_state_space.hpp:124
steering::CC0pm_Dubins_State_Space::CC0pm_Dubins_State_Space
CC0pm_Dubins_State_Space(double kappa, double sigma, double discretization=0.1, bool forwards=true)
Constructor.
Definition: cc0pm_dubins_state_space.cpp:336
steering::CC0pm_Dubins_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: cc0pm_dubins_state_space.cpp:516
steering::CC0pm_Dubins_State_Space::cc0pm_dubins
CC_Dubins_Path * cc0pm_dubins(const State &state1, const State &state2) const
Returns a sequence of turns and straight lines connecting a start and an end configuration.
Definition: cc0pm_dubins_state_space.cpp:428
steering::CC0pm_Dubins_State_Space::forwards_
bool forwards_
Driving direction.
Definition: cc0pm_dubins_state_space.hpp:115
steering::CC0pm_Dubins_State_Space::CC0pm_Dubins
Definition: cc0pm_dubins_state_space.cpp:38
paths.hpp
steering::CC0pm_Dubins_State_Space::cc0pm_circles_dubins_path
CC_Dubins_Path * cc0pm_circles_dubins_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: cc0pm_dubins_state_space.cpp:348
hc_cc_circle.hpp
steering::CC0pm_Dubins_State_Space::cc0pm_dubins_
std::unique_ptr< CC0pm_Dubins > cc0pm_dubins_
Pimpl Idiom: unique pointer on class with families
Definition: cc0pm_dubins_state_space.hpp:118
steering::CC0pm_Dubins_State_Space::mu_
double mu_
Angle between a configuration on the hc-/cc-circle and the tangent to the circle at that position.
Definition: cc0pm_dubins_state_space.hpp:130
steering_functions.hpp
plot_states.kappa
kappa
Definition: plot_states.py:106
steering::CC0pm_Dubins_State_Space::radius_
double radius_
Outer radius of a hc-/cc-circle.
Definition: cc0pm_dubins_state_space.hpp:127
steering
Definition: dubins_state_space.hpp:70
steering::CC0pm_Dubins_State_Space::~CC0pm_Dubins_State_Space
~CC0pm_Dubins_State_Space()
Destructor.


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