ccpmpm_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 CCPMPM_DUBINS_STATE_SPACE_HPP
27 #define CCPMPM_DUBINS_STATE_SPACE_HPP
28 
29 #include <memory>
30 #include <vector>
31 
36 
37 namespace steering
38 {
39 
47 class CCpmpm_Dubins_State_Space : public HC_CC_State_Space
48 {
49 public:
51  CCpmpm_Dubins_State_Space(double kappa, double sigma, double discretization = 0.1, bool forwards = true);
52 
55 
57  CC_Dubins_Path* ccpmpm_circles_dubins_path(const HC_CC_Circle& c1, const HC_CC_Circle& c2) const;
58 
60  CC_Dubins_Path* ccpmpm_dubins(const State& state1, const State& state2) const;
61 
63  double get_distance(const State& state1, const State& state2) const;
64 
66  std::vector<Control> get_controls(const State& state1, const State& state2) const;
67 
68 private:
70  bool forwards_;
71 
73  class CCpmpm_Dubins;
74 
76  std::unique_ptr<CCpmpm_Dubins> ccpmpm_dubins_;
77 
80 
82  double radius_;
83 
85  double mu_;
86 
88  double sin_mu_, cos_mu_;
89 };
90 
91 } // namespace steering
92 
93 #endif
hc_cc_state_space.hpp
steering::HC_CC_Circle_Param
Definition: hc_cc_circle.hpp:57
steering::CCpmpm_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: ccpmpm_dubins_state_space.hpp:131
steering::CCpmpm_Dubins_State_Space::get_distance
double get_distance(const State &state1, const State &state2) const
Returns shortest path length from state1 to state2.
Definition: ccpmpm_dubins_state_space.cpp:653
steering::CCpmpm_Dubins_State_Space::ccpmpm_dubins
CC_Dubins_Path * ccpmpm_dubins(const State &state1, const State &state2) const
Returns a sequence of turns and straight lines connecting a start and an end configuration.
Definition: ccpmpm_dubins_state_space.cpp:567
steering::CCpmpm_Dubins_State_Space::cos_mu_
double cos_mu_
Definition: ccpmpm_dubins_state_space.hpp:134
steering::CCpmpm_Dubins_State_Space::sin_mu_
double sin_mu_
Sine and cosine of mu.
Definition: ccpmpm_dubins_state_space.hpp:134
paths.hpp
steering::CCpmpm_Dubins_State_Space::rs_circle_param_
HC_CC_Circle_Param rs_circle_param_
Parameter of a rs-circle.
Definition: ccpmpm_dubins_state_space.hpp:125
steering::CCpmpm_Dubins_State_Space::forwards_
bool forwards_
Driving direction.
Definition: ccpmpm_dubins_state_space.hpp:116
hc_cc_circle.hpp
steering::CCpmpm_Dubins_State_Space::ccpmpm_dubins_
std::unique_ptr< CCpmpm_Dubins > ccpmpm_dubins_
Pimpl Idiom: unique pointer on class with families
Definition: ccpmpm_dubins_state_space.hpp:119
steering::CCpmpm_Dubins_State_Space::radius_
double radius_
Outer radius of a hc-/cc-circle.
Definition: ccpmpm_dubins_state_space.hpp:128
steering::CCpmpm_Dubins_State_Space::CCpmpm_Dubins
Definition: ccpmpm_dubins_state_space.cpp:38
steering::CCpmpm_Dubins_State_Space::CCpmpm_Dubins_State_Space
CCpmpm_Dubins_State_Space(double kappa, double sigma, double discretization=0.1, bool forwards=true)
Constructor.
Definition: ccpmpm_dubins_state_space.cpp:458
steering::CCpmpm_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: ccpmpm_dubins_state_space.cpp:661
steering::CCpmpm_Dubins_State_Space::ccpmpm_circles_dubins_path
CC_Dubins_Path * ccpmpm_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: ccpmpm_dubins_state_space.cpp:472
steering_functions.hpp
plot_states.kappa
kappa
Definition: plot_states.py:106
steering
Definition: dubins_state_space.hpp:70
steering::CCpmpm_Dubins_State_Space::~CCpmpm_Dubins_State_Space
~CCpmpm_Dubins_State_Space()
Destructor.


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