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

Motion estimation that uses the specific values of the x and y axis accelerations, being the angle of the vehicle and its position independent. More...

#include <motion_models.hpp>

Inheritance diagram for ImuVelocityModel:
Inheritance graph
Collaboration diagram for ImuVelocityModel:
Collaboration graph

Public Member Functions

 ImuVelocityModel (const Eigen::MatrixXf &process_noise_covariance_matrix)
 Construct a new Motion Model object.
 
Eigen::VectorXf predict_expected_state (const Eigen::VectorXf &expected_state, const MotionUpdate &motion_prediction_data, const double time_interval) const override
 Calculate expected state vector from velocity model using IMU data and linear functions Uses translational velocity in x and y axis.
 
Eigen::MatrixXf get_motion_to_state_matrix (const Eigen::VectorXf &expected_state, const MotionUpdate &motion_prediction_data, const double time_interval) const override
 Calculate state covariance matrix from velocity model using IMU data and linear functions Uses translational velocity in x and y axis.
 
- Public Member Functions inherited from MotionModel
 MotionModel (const Eigen::MatrixXf &process_noise_covariance_matrix)
 Construct a new Motion Model object.
 
Eigen::MatrixXf get_process_noise_covariance_matrix (const unsigned int state_size) const
 Get the process noise covariance matrix object.
 
virtual ~MotionModel ()=default
 

Private Attributes

Eigen::MatrixXf _process_noise_covariance_matrix
 

Additional Inherited Members

- Static Public Member Functions inherited from MotionModel
static Eigen::MatrixXf create_process_noise_covariance_matrix (float process_noise)
 

Detailed Description

Motion estimation that uses the specific values of the x and y axis accelerations, being the angle of the vehicle and its position independent.

Definition at line 93 of file motion_models.hpp.

Constructor & Destructor Documentation

◆ ImuVelocityModel()

ImuVelocityModel::ImuVelocityModel ( const Eigen::MatrixXf &  process_noise_covariance_matrix)
explicit

Construct a new Motion Model object.

Parameters
process_noise_covariance_matrixcovariance matrix of the process noise (R)

Definition at line 11 of file motion_models.cpp.

Member Function Documentation

◆ get_motion_to_state_matrix()

Eigen::MatrixXf ImuVelocityModel::get_motion_to_state_matrix ( const Eigen::VectorXf &  expected_state,
const MotionUpdate motion_prediction_data,
const double  time_interval 
) const
overridevirtual

Calculate state covariance matrix from velocity model using IMU data and linear functions Uses translational velocity in x and y axis.

Parameters
expected_state
motion_prediction_data
time_intervalin seconds
Returns
Eigen::MatrixXf

Implements MotionModel.

Definition at line 104 of file motion_models.cpp.

Here is the caller graph for this function:

◆ predict_expected_state()

Eigen::VectorXf ImuVelocityModel::predict_expected_state ( const Eigen::VectorXf &  expected_state,
const MotionUpdate motion_prediction_data,
const double  time_interval 
) const
overridevirtual

Calculate expected state vector from velocity model using IMU data and linear functions Uses translational velocity in x and y axis.

Parameters
expected_state
motion_prediction_data
time_intervalin seconds
Returns
Eigen::VectorXf

Implements MotionModel.

Definition at line 86 of file motion_models.cpp.

Here is the call graph for this function:
Here is the caller graph for this function:

Member Data Documentation

◆ _process_noise_covariance_matrix

Eigen::MatrixXf ImuVelocityModel::_process_noise_covariance_matrix
private

Definition at line 94 of file motion_models.hpp.


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