Abstract Moiton Model class designed to be implemented by the different motion models.
More...
#include <motion_models.hpp>
|
| | 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 |
| |
Abstract Moiton Model class designed to be implemented by the different motion models.
Definition at line 34 of file motion_models.hpp.
◆ MotionModel()
| MotionModel::MotionModel |
( |
const Eigen::MatrixXf & |
process_noise_covariance_matrix | ) |
|
|
explicit |
Construct a new Motion Model object.
- Parameters
-
| process_noise_covariance_matrix | covariance matrix of the process noise (R) |
Definition at line 5 of file motion_models.cpp.
◆ ~MotionModel()
| virtual MotionModel::~MotionModel |
( |
| ) |
|
|
virtualdefault |
◆ create_process_noise_covariance_matrix()
| Eigen::MatrixXf MotionModel::create_process_noise_covariance_matrix |
( |
float |
process_noise | ) |
|
|
static |
◆ 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_interval | in 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
-
- 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_interval | in seconds |
- Returns
- Eigen::VectorXf
Implemented in ImuVelocityModel, and NormalVelocityModel.
◆ _process_noise_covariance_matrix
| Eigen::MatrixXf MotionModel::_process_noise_covariance_matrix |
|
private |
The documentation for this class was generated from the following files: