scenario_simulator_v2 C++ API
sim_model_interface.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_INTERFACE_HPP_
16 #define SIMPLE_PLANNING_SIMULATOR__VEHICLE_MODEL__SIM_MODEL_INTERFACE_HPP_
17 
18 #include <autoware_auto_vehicle_msgs/msg/gear_command.hpp>
19 #include <eigen3/Eigen/Core>
20 
26 {
27 protected:
28  const int dim_x_;
29  const int dim_u_;
30  Eigen::VectorXd state_;
31  Eigen::VectorXd input_;
32 
34  uint8_t gear_ = autoware_auto_vehicle_msgs::msg::GearCommand::DRIVE;
35 
36 public:
42  SimModelInterface(int dim_x, int dim_u);
43 
47  ~SimModelInterface() = default;
48 
53  void getState(Eigen::VectorXd & state);
54 
59  void getInput(Eigen::VectorXd & input);
60 
65  void setState(const Eigen::VectorXd & state);
66 
71  void setInput(const Eigen::VectorXd & input);
72 
77  void setGear(const uint8_t gear);
78 
84  void updateRungeKutta(const double & dt, const Eigen::VectorXd & input);
85 
91  void updateEuler(const double & dt, const Eigen::VectorXd & input);
92 
97  virtual void update(const double & dt) = 0;
98 
102  virtual double getX() = 0;
103 
107  virtual double getY() = 0;
108 
112  virtual double getYaw() = 0;
113 
117  virtual double getVx() = 0;
118 
122  virtual double getVy() = 0;
123 
127  virtual double getAx() = 0;
128 
132  virtual double getWz() = 0;
133 
137  virtual double getSteer() = 0;
138 
142  uint8_t getGear() const;
143 
147  inline int getDimX() { return dim_x_; }
148 
152  inline int getDimU() { return dim_u_; }
153 
159  virtual Eigen::VectorXd calcModel(
160  const Eigen::VectorXd & state, const Eigen::VectorXd & input) = 0;
161 };
162 
163 #endif // SIMPLE_PLANNING_SIMULATOR__VEHICLE_MODEL__SIM_MODEL_INTERFACE_HPP_
simple_planning_simulator vehicle model class to calculate vehicle dynamics
Definition: sim_model_interface.hpp:26
void setGear(const uint8_t gear)
set gear
Definition: sim_model_interface.cpp:40
virtual double getWz()=0
get vehicle angular-velocity wz
const int dim_u_
dimension of input u
Definition: sim_model_interface.hpp:29
virtual double getAx()=0
get vehicle longitudinal acceleration
virtual double getSteer()=0
get vehicle steering angle
~SimModelInterface()=default
destructor
virtual double getYaw()=0
get vehicle angle yaw
void setState(const Eigen::VectorXd &state)
set state vector of model
Definition: sim_model_interface.cpp:38
int getDimU()
get input vector dimension
Definition: sim_model_interface.hpp:152
uint8_t gear_
Definition: sim_model_interface.hpp:34
virtual double getY()=0
get vehicle position y
void setInput(const Eigen::VectorXd &input)
set input vector of model
Definition: sim_model_interface.cpp:39
Eigen::VectorXd input_
vehicle input vector
Definition: sim_model_interface.hpp:31
virtual double getVx()=0
get vehicle velocity vx
virtual Eigen::VectorXd calcModel(const Eigen::VectorXd &state, const Eigen::VectorXd &input)=0
calculate derivative of states with vehicle model
virtual double getX()=0
get vehicle position x
SimModelInterface(int dim_x, int dim_u)
constructor
Definition: sim_model_interface.cpp:17
void updateRungeKutta(const double &dt, const Eigen::VectorXd &input)
update vehicle states with Runge-Kutta methods
Definition: sim_model_interface.cpp:23
void updateEuler(const double &dt, const Eigen::VectorXd &input)
update vehicle states with Euler methods
Definition: sim_model_interface.cpp:32
void getState(Eigen::VectorXd &state)
get state vector of model
Definition: sim_model_interface.cpp:36
int getDimX()
get state vector dimension
Definition: sim_model_interface.hpp:147
uint8_t getGear() const
get vehicle gear
Definition: sim_model_interface.cpp:41
Eigen::VectorXd state_
vehicle state vector
Definition: sim_model_interface.hpp:30
const int dim_x_
dimension of state x
Definition: sim_model_interface.hpp:28
virtual double getVy()=0
get vehicle lateral velocity
void getInput(Eigen::VectorXd &input)
get input vector of model
Definition: sim_model_interface.cpp:37
virtual void update(const double &dt)=0
update vehicle states