|
Formula Student Autonomous Systems
The code for the main driverless system
|
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>


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) |
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.
|
explicit |
Construct a new Motion Model object.
| process_noise_covariance_matrix | covariance matrix of the process noise (R) |
Definition at line 11 of file motion_models.cpp.
|
overridevirtual |
Calculate state covariance matrix from velocity model using IMU data and linear functions Uses translational velocity in x and y axis.
| expected_state | |
| motion_prediction_data | |
| time_interval | in seconds |
Implements MotionModel.
Definition at line 104 of file motion_models.cpp.

|
overridevirtual |
Calculate expected state vector from velocity model using IMU data and linear functions Uses translational velocity in x and y axis.
| expected_state | |
| motion_prediction_data | |
| time_interval | in seconds |
Implements MotionModel.
Definition at line 86 of file motion_models.cpp.


|
private |
Definition at line 94 of file motion_models.hpp.