scenario_simulator_v2 C++ API
sim_model_ideal_steer_acc_geared.hpp
Go to the documentation of this file.
1 // Copyright 2021 The Autoware Foundation.
2 //
3 // Licensed under the Apache License, Version 2.0 (the "License");
4 // you may not use this file except in compliance with the License.
5 // You may obtain a copy of the License at
6 //
7 // http://www.apache.org/licenses/LICENSE-2.0
8 //
9 // Unless required by applicable law or agreed to in writing, software
10 // distributed under the License is distributed on an "AS IS" BASIS,
11 // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12 // See the License for the specific language governing permissions and
13 // limitations under the License.
14 
15 #ifndef SIMPLE_PLANNING_SIMULATOR__VEHICLE_MODEL__SIM_MODEL_IDEAL_STEER_ACC_GEARED_HPP_
16 #define SIMPLE_PLANNING_SIMULATOR__VEHICLE_MODEL__SIM_MODEL_IDEAL_STEER_ACC_GEARED_HPP_
17 
18 #include <eigen3/Eigen/Core>
19 #include <eigen3/Eigen/LU>
20 #include <iostream>
22 
28 {
29 public:
34  explicit SimModelIdealSteerAccGeared(double wheelbase);
35 
40 
41 private:
42  enum IDX { X = 0, Y, YAW, VX };
43  enum IDX_U {
44  AX_DES = 0,
45  STEER_DES,
46  };
47 
48  const double wheelbase_;
49  double current_acc_;
50 
54  double getX() override;
55 
59  double getY() override;
60 
64  double getYaw() override;
65 
69  double getVx() override;
70 
74  double getVy() override;
75 
79  double getAx() override;
80 
84  double getWz() override;
85 
89  double getSteer() override;
90 
95  void update(const double & dt) override;
96 
102  Eigen::VectorXd calcModel(const Eigen::VectorXd & state, const Eigen::VectorXd & input) override;
103 
111  void updateStateWithGear(
112  Eigen::VectorXd & state, const Eigen::VectorXd & prev_state, const uint8_t gear,
113  const double dt);
114 };
115 
116 #endif // SIMPLE_PLANNING_SIMULATOR__VEHICLE_MODEL__SIM_MODEL_IDEAL_STEER_ACC_GEARED_HPP_
calculate ideal steering dynamics
Definition: sim_model_ideal_steer_acc_geared.hpp:28
SimModelIdealSteerAccGeared(double wheelbase)
constructor
Definition: sim_model_ideal_steer_acc_geared.cpp:19
~SimModelIdealSteerAccGeared()=default
destructor
simple_planning_simulator vehicle model class to calculate vehicle dynamics
Definition: sim_model_interface.hpp:26