Formula Student Autonomous Systems
The code for the main driverless system
Loading...
Searching...
No Matches
BicycleModel Class Reference

Simple bicycle model structure. More...

#include <bicycle_model.hpp>

Inheritance diagram for BicycleModel:
Inheritance graph
Collaboration diagram for BicycleModel:
Collaboration graph

Public Member Functions

 BicycleModel (const std::string &config_path)
 
 ~BicycleModel () override=default
 
void step (double dt) override
 
void reset () override
 
double get_position_x () const override
 
double get_position_y () const override
 
double get_yaw () const override
 
double get_velocity_x () const override
 
void set_position (double x, double y, double yaw) override
 
void set_velocity (double vx) override
 
void set_steering (double angle) override
 
void set_throttle (double throttle) override
 
std::string get_model_name () const override
 
 BicycleModel (common_lib::car_parameters::CarParameters car_parameters)
 
std::pair< double, double > wheels_velocities_to_cg (double rl_rpm, double fl_rpm, double rr_rpm, double fr_rpm, double steering_angle) override
 assumes a bicycle model and a set of parameters about the vehicle to calculate the velocities of the center of mass given the velocities of the wheels
 
common_lib::structures::Position rear_axis_position (const common_lib::structures::Position &cg, double orientation, double dist_cg_2_rear_axis) override
 Calculates the position of the rear axis given the position of the center of mass, the the orientation and the distance between the center of mass and the rear axis.
 
Eigen::VectorXd cg_velocity_to_wheels (const Eigen::Vector3d &cg_velocities) override
 Assumes a bicycle model and a set of parameters about the vehicle to calculate the velocities of the wheels given the velocities of the center of mass.
 
Eigen::MatrixXd jacobian_cg_velocity_to_wheels (const Eigen::Vector3d &cg_velocities) override
 Calculates the jacobian of the function cg_velocity_to_wheels with respect to the center of mass velocities.
 
- Public Member Functions inherited from VehicleModel
virtual ~VehicleModel ()=default
 

Private Attributes

double lr_
 
double lf_
 
double sf_
 
double sr_
 
double h_cg_
 
double max_steering_angle_
 
double Blat_
 
double Clat_
 
double Dlat_
 
double Elat_
 
double cla_
 
double cda_
 
double aero_area_
 
double mass_
 
double Izz_
 
double wheel_radius_
 
double gear_ratio_
 
double x_
 
double y_
 
double yaw_
 
double vx_
 
double steering_angle_
 
double throttle_
 
common_lib::car_parameters::CarParameters car_parameters_
 

Detailed Description

Simple bicycle model structure.

Definition at line 13 of file bicycle_model.hpp.

Constructor & Destructor Documentation

◆ BicycleModel() [1/2]

BicycleModel::BicycleModel ( const std::string &  config_path)
explicit

Definition at line 3 of file bicycle_model.cpp.

◆ ~BicycleModel()

BicycleModel::~BicycleModel ( )
overridedefault

◆ BicycleModel() [2/2]

BicycleModel::BicycleModel ( common_lib::car_parameters::CarParameters  car_parameters)
inline

Definition at line 14 of file bicycle_model.hpp.

Member Function Documentation

◆ cg_velocity_to_wheels()

Eigen::VectorXd BicycleModel::cg_velocity_to_wheels ( const Eigen::Vector3d &  cg_velocities)
overridevirtual

Assumes a bicycle model and a set of parameters about the vehicle to calculate the velocities of the wheels given the velocities of the center of mass.

Parameters
cg_velocitiesvector of velocities on the Center of Gravity {velocity_x, velocity_y, rotational_velocity} in m/s and rad/s respectively
Returns
Eigen::VectorXd rpms of the wheels, the steering angle, and motor rpms {fl_rpm, fr_rpm, rl_rpm, rr_rpm, steering_angle, motor_rpm}

Implements S2VModel.

Here is the caller graph for this function:

◆ get_model_name()

std::string BicycleModel::get_model_name ( ) const
overridevirtual

Implements VehicleModel.

Definition at line 80 of file bicycle_model.cpp.

◆ get_position_x()

double BicycleModel::get_position_x ( ) const
overridevirtual

Implements VehicleModel.

Definition at line 68 of file bicycle_model.cpp.

◆ get_position_y()

double BicycleModel::get_position_y ( ) const
overridevirtual

Implements VehicleModel.

Definition at line 70 of file bicycle_model.cpp.

◆ get_velocity_x()

double BicycleModel::get_velocity_x ( ) const
overridevirtual

Implements VehicleModel.

Definition at line 74 of file bicycle_model.cpp.

◆ get_yaw()

double BicycleModel::get_yaw ( ) const
overridevirtual

Implements VehicleModel.

Definition at line 72 of file bicycle_model.cpp.

◆ jacobian_cg_velocity_to_wheels()

Eigen::MatrixXd BicycleModel::jacobian_cg_velocity_to_wheels ( const Eigen::Vector3d &  cg_velocities)
overridevirtual

Calculates the jacobian of the function cg_velocity_to_wheels with respect to the center of mass velocities.

Parameters
cg_velocitiesvector of velocities on the Center of Gravity {velocity_x, velocity_y, rotational_velocity} in m/s and rad/s respectively
Returns
Eigen::MatrixXd jacobian matrix of dimension 6x3

Implements S2VModel.

Here is the caller graph for this function:

◆ rear_axis_position()

common_lib::structures::Position BicycleModel::rear_axis_position ( const common_lib::structures::Position cg,
double  orientation,
double  dist_cg_2_rear_axis 
)
overridevirtual

Calculates the position of the rear axis given the position of the center of mass, the the orientation and the distance between the center of mass and the rear axis.

Parameters
cgposition of the center of mass in meters
orientationorientation of the vehicle relative to the world frame in radians
dist_cg_2_rear_axisdisntance between the center of mass and the rear axis in meters
Returns
common_lib::structures::Position

Implements S2VModel.

◆ reset()

void BicycleModel::reset ( )
overridevirtual

Implements VehicleModel.

Definition at line 51 of file bicycle_model.cpp.

◆ set_position()

void BicycleModel::set_position ( double  x,
double  y,
double  yaw 
)
overridevirtual

Implements VehicleModel.

Definition at line 60 of file bicycle_model.cpp.

◆ set_steering()

void BicycleModel::set_steering ( double  angle)
overridevirtual

Implements VehicleModel.

Definition at line 76 of file bicycle_model.cpp.

◆ set_throttle()

void BicycleModel::set_throttle ( double  throttle)
overridevirtual

Implements VehicleModel.

Definition at line 78 of file bicycle_model.cpp.

◆ set_velocity()

void BicycleModel::set_velocity ( double  vx)
overridevirtual

Implements VehicleModel.

Definition at line 66 of file bicycle_model.cpp.

◆ step()

void BicycleModel::step ( double  dt)
overridevirtual

Implements VehicleModel.

Definition at line 45 of file bicycle_model.cpp.

◆ wheels_velocities_to_cg()

std::pair< double, double > BicycleModel::wheels_velocities_to_cg ( double  rl_rpm,
double  fl_rpm,
double  rr_rpm,
double  fr_rpm,
double  steering_angle 
)
overridevirtual

assumes a bicycle model and a set of parameters about the vehicle to calculate the velocities of the center of mass given the velocities of the wheels

Parameters
rl_rpmrear left wheel velocity in rpm
fl_rpmfront left wheel velocity in rpm
rr_rpmrear right wheel velocity in rpm
fr_rpmfront right wheel velocity in rpm
steering_anglesteering angle in radians
Returns
std::pair<double, double> translational and rotational velocities of the center of mass in m/s and rad/s respectively

Implements S2VModel.

Here is the caller graph for this function:

Member Data Documentation

◆ aero_area_

double BicycleModel::aero_area_
private

Definition at line 50 of file bicycle_model.hpp.

◆ Blat_

double BicycleModel::Blat_
private

Definition at line 42 of file bicycle_model.hpp.

◆ car_parameters_

common_lib::car_parameters::CarParameters BicycleModel::car_parameters_
private

Definition at line 11 of file bicycle_model.hpp.

◆ cda_

double BicycleModel::cda_
private

Definition at line 49 of file bicycle_model.hpp.

◆ cla_

double BicycleModel::cla_
private

Definition at line 48 of file bicycle_model.hpp.

◆ Clat_

double BicycleModel::Clat_
private

Definition at line 43 of file bicycle_model.hpp.

◆ Dlat_

double BicycleModel::Dlat_
private

Definition at line 44 of file bicycle_model.hpp.

◆ Elat_

double BicycleModel::Elat_
private

Definition at line 45 of file bicycle_model.hpp.

◆ gear_ratio_

double BicycleModel::gear_ratio_
private

Definition at line 58 of file bicycle_model.hpp.

◆ h_cg_

double BicycleModel::h_cg_
private

Definition at line 38 of file bicycle_model.hpp.

◆ Izz_

double BicycleModel::Izz_
private

Definition at line 54 of file bicycle_model.hpp.

◆ lf_

double BicycleModel::lf_
private

Definition at line 35 of file bicycle_model.hpp.

◆ lr_

double BicycleModel::lr_
private

Definition at line 34 of file bicycle_model.hpp.

◆ mass_

double BicycleModel::mass_
private

Definition at line 53 of file bicycle_model.hpp.

◆ max_steering_angle_

double BicycleModel::max_steering_angle_
private

Definition at line 39 of file bicycle_model.hpp.

◆ sf_

double BicycleModel::sf_
private

Definition at line 36 of file bicycle_model.hpp.

◆ sr_

double BicycleModel::sr_
private

Definition at line 37 of file bicycle_model.hpp.

◆ steering_angle_

double BicycleModel::steering_angle_
private

Definition at line 67 of file bicycle_model.hpp.

◆ throttle_

double BicycleModel::throttle_
private

Definition at line 68 of file bicycle_model.hpp.

◆ vx_

double BicycleModel::vx_
private

Definition at line 64 of file bicycle_model.hpp.

◆ wheel_radius_

double BicycleModel::wheel_radius_
private

Definition at line 57 of file bicycle_model.hpp.

◆ x_

double BicycleModel::x_
private

Definition at line 61 of file bicycle_model.hpp.

◆ y_

double BicycleModel::y_
private

Definition at line 62 of file bicycle_model.hpp.

◆ yaw_

double BicycleModel::yaw_
private

Definition at line 63 of file bicycle_model.hpp.


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