hc00_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 HC00_REEDS_SHEPP_STATE_SPACE_HPP
27 #define HC00_REEDS_SHEPP_STATE_SPACE_HPP
28 
29 #include <memory>
30 #include <vector>
31 
36 
37 namespace steering
38 {
39 
51 {
52 public:
54  HC00_Reeds_Shepp_State_Space(double kappa, double sigma, double discretization = 0.1);
55 
58 
60  HC_CC_RS_Path* hc00_circles_rs_path(const HC_CC_Circle& c1, const HC_CC_Circle& c2) const;
61 
63  HC_CC_RS_Path* hc00_reeds_shepp(const State& state1, const State& state2) const;
64 
66  double get_distance(const State& state1, const State& state2) const;
67 
69  std::vector<Control> get_controls(const State& state1, const State& state2) const;
70 
71 private:
74 
76  std::unique_ptr<HC00_Reeds_Shepp> hc00_reeds_shepp_;
77 
80 };
81 
82 } // namespace steering
83 
84 #endif
HC_CC_RS_Path * hc00_reeds_shepp(const State &state1, const State &state2) const
Returns a sequence of turns and straight lines connecting a start and an end configuration.
An implementation of hybrid curvature (HC) steer with zero curvature at the start and goal configurat...
HC_CC_RS_Path * hc00_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.
double get_distance(const State &state1, const State &state2) const
Returns shortest path length from state1 to state2.
std::vector< Control > get_controls(const State &state1, const State &state2) const
Returns controls of the shortest path from state1 to state2.
std::unique_ptr< HC00_Reeds_Shepp > hc00_reeds_shepp_
Pimpl Idiom: unique pointer on class with families.
HC00_Reeds_Shepp_State_Space(double kappa, double sigma, double discretization=0.1)
Constructor.
Description of a kinematic car&#39;s state.
HC_CC_Circle_Param rs_circle_param_
Parameter of a rs-circle.


steering_functions
Author(s): Holger Banzhaf
autogenerated on Thu Aug 18 2022 02:09:46