hc_cc_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_CC_STATE_SPACE_HPP
19 #define HC_CC_STATE_SPACE_HPP
20 
21 #include <vector>
22 
26 
27 namespace steering
28 {
29 
30 class HC_CC_State_Space
31 {
32 public:
34  HC_CC_State_Space(double kappa, double sigma, double discretization);
35 
37  void set_filter_parameters(const Motion_Noise& motion_noise, const Measurement_Noise& measurement_noise,
38  const Controller& controller);
39 
41  virtual std::vector<Control> get_controls(const State& state1, const State& state2) const = 0;
42 
44  std::vector<State> get_path(const State& state1, const State& state2) const;
45 
47  std::vector<State_With_Covariance> get_path_with_covariance(const State_With_Covariance& state1,
48  const State& state2) const;
49 
51  std::vector<State> integrate(const State& state, const std::vector<Control>& controls) const;
52 
54  std::vector<State_With_Covariance> integrate_with_covariance(const State_With_Covariance& state,
55  const std::vector<Control>& controls) const;
56 
58  State interpolate(const State& state, const std::vector<Control>& controls, double t) const;
59 
61  inline State integrate_ODE(const State& state, const Control& control, double integration_step) const;
62 
63 protected:
65  double kappa_, sigma_;
66 
68  double discretization_;
69 
72 
74  EKF ekf_;
75 };
76 
77 } // namespace steering
78 
79 #endif
steering::HC_CC_State_Space::hc_cc_circle_param_
HC_CC_Circle_Param hc_cc_circle_param_
Parameters of a hc-/cc-circle.
Definition: hc_cc_state_space.hpp:101
steering::State
Description of a kinematic car's state.
Definition: steering_functions.hpp:44
steering::HC_CC_State_Space::get_path
std::vector< State > get_path(const State &state1, const State &state2) const
Returns path from state1 to state2.
Definition: hc_cc_state_space.cpp:68
steering::HC_CC_Circle_Param
Definition: hc_cc_circle.hpp:57
steering::HC_CC_State_Space::sigma_
double sigma_
Definition: hc_cc_state_space.hpp:95
steering::HC_CC_State_Space::get_path_with_covariance
std::vector< State_With_Covariance > get_path_with_covariance(const State_With_Covariance &state1, const State &state2) const
Returns path including covariances from state1 to state2.
Definition: hc_cc_state_space.cpp:74
steering::HC_CC_State_Space::integrate
std::vector< State > integrate(const State &state, const std::vector< Control > &controls) const
Returns integrated states given a start state and controls.
Definition: hc_cc_state_space.cpp:81
steering::HC_CC_State_Space::HC_CC_State_Space
HC_CC_State_Space(double kappa, double sigma, double discretization)
Constructor.
Definition: hc_cc_state_space.cpp:28
ekf.hpp
steering::HC_CC_State_Space::ekf_
EKF ekf_
Extended Kalman Filter for uncertainty propagation.
Definition: hc_cc_state_space.hpp:104
steering::Control
Description of a path segment with its corresponding control inputs.
Definition: steering_functions.hpp:82
steering::HC_CC_State_Space::integrate_ODE
State integrate_ODE(const State &state, const Control &control, double integration_step) const
Returns integrated state given a start state, a control, and an integration step.
Definition: hc_cc_state_space.cpp:281
hc_cc_circle.hpp
steering::HC_CC_State_Space::set_filter_parameters
void set_filter_parameters(const Motion_Noise &motion_noise, const Measurement_Noise &measurement_noise, const Controller &controller)
Sets the parameters required by the filter.
Definition: hc_cc_state_space.cpp:62
steering::HC_CC_State_Space::kappa_
double kappa_
Curvature, sharpness of clothoid.
Definition: hc_cc_state_space.hpp:95
steering::HC_CC_State_Space::interpolate
State interpolate(const State &state, const std::vector< Control > &controls, double t) const
Returns interpolated state at distance t in [0,1] (percentage of total path length)
Definition: hc_cc_state_space.cpp:212
steering::EKF
Definition: ekf.hpp:48
steering::HC_CC_State_Space::get_controls
virtual std::vector< Control > get_controls(const State &state1, const State &state2) const =0
Virtual function that returns controls of the shortest path from state1 to state2.
steering::HC_CC_State_Space::discretization_
double discretization_
Discretization of path.
Definition: hc_cc_state_space.hpp:98
steering_functions.hpp
plot_states.kappa
kappa
Definition: plot_states.py:106
steering::State_With_Covariance
Description of a kinematic car's state with covariance.
Definition: steering_functions.hpp:63
steering
Definition: dubins_state_space.hpp:70
steering::HC_CC_State_Space::integrate_with_covariance
std::vector< State_With_Covariance > integrate_with_covariance(const State_With_Covariance &state, const std::vector< Control > &controls) const
Returns integrated states including covariance given a start state and controls.
Definition: hc_cc_state_space.cpp:137


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