simple_planning_simulator vehicle model class to calculate vehicle dynamics
More...
#include <sim_model_interface.hpp>
simple_planning_simulator vehicle model class to calculate vehicle dynamics
◆ SimModelInterface()
SimModelInterface::SimModelInterface |
( |
int |
dim_x, |
|
|
int |
dim_u |
|
) |
| |
constructor
- Parameters
-
[in] | dim_x | dimension of state x |
[in] | dim_u | dimension of input u |
◆ ~SimModelInterface()
SimModelInterface::~SimModelInterface |
( |
| ) |
|
|
default |
◆ calcModel()
virtual Eigen::VectorXd SimModelInterface::calcModel |
( |
const Eigen::VectorXd & |
state, |
|
|
const Eigen::VectorXd & |
input |
|
) |
| |
|
pure virtual |
calculate derivative of states with vehicle model
- Parameters
-
[in] | state | current model state |
[in] | input | input vector to model |
◆ getAx()
virtual double SimModelInterface::getAx |
( |
| ) |
|
|
pure virtual |
get vehicle longitudinal acceleration
◆ getDimU()
int SimModelInterface::getDimU |
( |
| ) |
|
|
inline |
get input vector dimension
◆ getDimX()
int SimModelInterface::getDimX |
( |
| ) |
|
|
inline |
get state vector dimension
◆ getGear()
uint8_t SimModelInterface::getGear |
( |
| ) |
const |
◆ getInput()
void SimModelInterface::getInput |
( |
Eigen::VectorXd & |
input | ) |
|
get input vector of model
- Parameters
-
◆ getState()
void SimModelInterface::getState |
( |
Eigen::VectorXd & |
state | ) |
|
get state vector of model
- Parameters
-
◆ getSteer()
virtual double SimModelInterface::getSteer |
( |
| ) |
|
|
pure virtual |
get vehicle steering angle
◆ getVx()
virtual double SimModelInterface::getVx |
( |
| ) |
|
|
pure virtual |
◆ getVy()
virtual double SimModelInterface::getVy |
( |
| ) |
|
|
pure virtual |
get vehicle lateral velocity
◆ getWz()
virtual double SimModelInterface::getWz |
( |
| ) |
|
|
pure virtual |
get vehicle angular-velocity wz
◆ getX()
virtual double SimModelInterface::getX |
( |
| ) |
|
|
pure virtual |
◆ getY()
virtual double SimModelInterface::getY |
( |
| ) |
|
|
pure virtual |
◆ getYaw()
virtual double SimModelInterface::getYaw |
( |
| ) |
|
|
pure virtual |
◆ setGear()
void SimModelInterface::setGear |
( |
const uint8_t |
gear | ) |
|
set gear
- Parameters
-
[in] | gear | gear command defined in autoware_auto_msgs/GearCommand |
◆ setInput()
void SimModelInterface::setInput |
( |
const Eigen::VectorXd & |
input | ) |
|
set input vector of model
- Parameters
-
◆ setState()
void SimModelInterface::setState |
( |
const Eigen::VectorXd & |
state | ) |
|
set state vector of model
- Parameters
-
◆ update()
virtual void SimModelInterface::update |
( |
const double & |
dt | ) |
|
|
pure virtual |
update vehicle states
- Parameters
-
◆ updateEuler()
void SimModelInterface::updateEuler |
( |
const double & |
dt, |
|
|
const Eigen::VectorXd & |
input |
|
) |
| |
update vehicle states with Euler methods
- Parameters
-
[in] | dt | delta time [s] |
[in] | input | vehicle input |
◆ updateRungeKutta()
void SimModelInterface::updateRungeKutta |
( |
const double & |
dt, |
|
|
const Eigen::VectorXd & |
input |
|
) |
| |
update vehicle states with Runge-Kutta methods
- Parameters
-
[in] | dt | delta time [s] |
[in] | input | vehicle input |
◆ dim_u_
const int SimModelInterface::dim_u_ |
|
protected |
◆ dim_x_
const int SimModelInterface::dim_x_ |
|
protected |
◆ gear_
uint8_t SimModelInterface::gear_ = autoware_auto_vehicle_msgs::msg::GearCommand::DRIVE |
|
protected |
◆ input_
Eigen::VectorXd SimModelInterface::input_ |
|
protected |
vehicle input vector
gear command defined in autoware_auto_msgs/GearCommand
◆ state_
Eigen::VectorXd SimModelInterface::state_ |
|
protected |
The documentation for this class was generated from the following files: