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

Abstract Moiton Model class designed to be implemented by the different motion models. More...

#include <motion_models.hpp>

Inheritance diagram for MotionModel:
Inheritance graph
Collaboration diagram for MotionModel:
Collaboration graph

Public Member Functions

 MotionModel (const Eigen::MatrixXf &process_noise_covariance_matrix)
 Construct a new Motion Model object.
 
virtual Eigen::VectorXf predict_expected_state (const Eigen::VectorXf &expected_state, const MotionUpdate &motion_prediction_data, const double time_interval) const =0
 Calculate expected state vector from motion estimation.
 
virtual Eigen::MatrixXf get_motion_to_state_matrix (const Eigen::VectorXf &expected_state, const MotionUpdate &motion_prediction_data, const double time_interval) const =0
 Calculate state covariance matrix from motion estimation.
 
Eigen::MatrixXf get_process_noise_covariance_matrix (const unsigned int state_size) const
 Get the process noise covariance matrix object.
 
virtual ~MotionModel ()=default
 

Static Public Member Functions

static Eigen::MatrixXf create_process_noise_covariance_matrix (float process_noise)
 

Private Attributes

Eigen::MatrixXf _process_noise_covariance_matrix
 R.
 

Detailed Description

Abstract Moiton Model class designed to be implemented by the different motion models.

Definition at line 34 of file motion_models.hpp.

Constructor & Destructor Documentation

◆ MotionModel()

MotionModel::MotionModel ( 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 5 of file motion_models.cpp.

◆ ~MotionModel()

virtual MotionModel::~MotionModel ( )
virtualdefault

Member Function Documentation

◆ create_process_noise_covariance_matrix()

Eigen::MatrixXf MotionModel::create_process_noise_covariance_matrix ( float  process_noise)
static

Definition at line 20 of file motion_models.cpp.

Here is the caller graph for this function:

◆ get_motion_to_state_matrix()

virtual Eigen::MatrixXf MotionModel::get_motion_to_state_matrix ( const Eigen::VectorXf &  expected_state,
const MotionUpdate motion_prediction_data,
const double  time_interval 
) const
pure virtual

Calculate state covariance matrix from motion estimation.

Corresponds to G in documentation

Parameters
expected_state
motion_prediction_data
time_intervalin seconds
Returns
Eigen::MatrixXf

Implemented in ImuVelocityModel, and NormalVelocityModel.

◆ get_process_noise_covariance_matrix()

Eigen::MatrixXf MotionModel::get_process_noise_covariance_matrix ( const unsigned int  state_size) const

Get the process noise covariance matrix object.

Parameters
state_size
Returns
Eigen::MatrixXf

Definition at line 14 of file motion_models.cpp.

◆ predict_expected_state()

virtual Eigen::VectorXf MotionModel::predict_expected_state ( const Eigen::VectorXf &  expected_state,
const MotionUpdate motion_prediction_data,
const double  time_interval 
) const
pure virtual

Calculate expected state vector from motion estimation.

Corresponds to g in documentation

Parameters
expected_state
motion_prediction_data
time_intervalin seconds
Returns
Eigen::VectorXf

Implemented in ImuVelocityModel, and NormalVelocityModel.

Member Data Documentation

◆ _process_noise_covariance_matrix

Eigen::MatrixXf MotionModel::_process_noise_covariance_matrix
private

R.

Definition at line 35 of file motion_models.hpp.


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