scenario_simulator_v2 C++ API
Public Member Functions | Protected Attributes | List of all members
SimModelInterface Class Referenceabstract

simple_planning_simulator vehicle model class to calculate vehicle dynamics More...

#include <sim_model_interface.hpp>

Inheritance diagram for SimModelInterface:
Inheritance graph
[legend]

Public Member Functions

 SimModelInterface (int dim_x, int dim_u)
 constructor More...
 
 ~SimModelInterface ()=default
 destructor More...
 
void getState (Eigen::VectorXd &state)
 get state vector of model More...
 
void getInput (Eigen::VectorXd &input)
 get input vector of model More...
 
void setState (const Eigen::VectorXd &state)
 set state vector of model More...
 
void setInput (const Eigen::VectorXd &input)
 set input vector of model More...
 
void setGear (const uint8_t gear)
 set gear More...
 
void updateRungeKutta (const double &dt, const Eigen::VectorXd &input)
 update vehicle states with Runge-Kutta methods More...
 
void updateEuler (const double &dt, const Eigen::VectorXd &input)
 update vehicle states with Euler methods More...
 
virtual void update (const double &dt)=0
 update vehicle states More...
 
virtual double getX ()=0
 get vehicle position x More...
 
virtual double getY ()=0
 get vehicle position y More...
 
virtual double getYaw ()=0
 get vehicle angle yaw More...
 
virtual double getVx ()=0
 get vehicle velocity vx More...
 
virtual double getVy ()=0
 get vehicle lateral velocity More...
 
virtual double getAx ()=0
 get vehicle longitudinal acceleration More...
 
virtual double getWz ()=0
 get vehicle angular-velocity wz More...
 
virtual double getSteer ()=0
 get vehicle steering angle More...
 
uint8_t getGear () const
 get vehicle gear More...
 
int getDimX ()
 get state vector dimension More...
 
int getDimU ()
 get input vector dimension More...
 
virtual Eigen::VectorXd calcModel (const Eigen::VectorXd &state, const Eigen::VectorXd &input)=0
 calculate derivative of states with vehicle model More...
 

Protected Attributes

const int dim_x_
 dimension of state x More...
 
const int dim_u_
 dimension of input u More...
 
Eigen::VectorXd state_
 vehicle state vector More...
 
Eigen::VectorXd input_
 vehicle input vector More...
 
uint8_t gear_ = autoware_auto_vehicle_msgs::msg::GearCommand::DRIVE
 

Detailed Description

simple_planning_simulator vehicle model class to calculate vehicle dynamics

Constructor & Destructor Documentation

◆ SimModelInterface()

SimModelInterface::SimModelInterface ( int  dim_x,
int  dim_u 
)

constructor

Parameters
[in]dim_xdimension of state x
[in]dim_udimension of input u

◆ ~SimModelInterface()

SimModelInterface::~SimModelInterface ( )
default

destructor

Member Function Documentation

◆ 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]statecurrent model state
[in]inputinput 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

get vehicle gear

◆ getInput()

void SimModelInterface::getInput ( Eigen::VectorXd &  input)

get input vector of model

Parameters
[out]inputinput vector

◆ getState()

void SimModelInterface::getState ( Eigen::VectorXd &  state)

get state vector of model

Parameters
[out]statestate vector

◆ getSteer()

virtual double SimModelInterface::getSteer ( )
pure virtual

get vehicle steering angle

◆ getVx()

virtual double SimModelInterface::getVx ( )
pure virtual

get vehicle velocity vx

◆ 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

get vehicle position x

◆ getY()

virtual double SimModelInterface::getY ( )
pure virtual

get vehicle position y

◆ getYaw()

virtual double SimModelInterface::getYaw ( )
pure virtual

get vehicle angle yaw

◆ setGear()

void SimModelInterface::setGear ( const uint8_t  gear)

set gear

Parameters
[in]geargear command defined in autoware_auto_msgs/GearCommand

◆ setInput()

void SimModelInterface::setInput ( const Eigen::VectorXd &  input)

set input vector of model

Parameters
[in]inputinput vector

◆ setState()

void SimModelInterface::setState ( const Eigen::VectorXd &  state)

set state vector of model

Parameters
[in]statestate vector

◆ update()

virtual void SimModelInterface::update ( const double &  dt)
pure virtual

update vehicle states

Parameters
[in]dtdelta time [s]

◆ updateEuler()

void SimModelInterface::updateEuler ( const double &  dt,
const Eigen::VectorXd &  input 
)

update vehicle states with Euler methods

Parameters
[in]dtdelta time [s]
[in]inputvehicle input

◆ updateRungeKutta()

void SimModelInterface::updateRungeKutta ( const double &  dt,
const Eigen::VectorXd &  input 
)

update vehicle states with Runge-Kutta methods

Parameters
[in]dtdelta time [s]
[in]inputvehicle input

Member Data Documentation

◆ dim_u_

const int SimModelInterface::dim_u_
protected

dimension of input u

◆ dim_x_

const int SimModelInterface::dim_x_
protected

dimension of state x

◆ 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

vehicle state vector


The documentation for this class was generated from the following files: