|
Formula Student Autonomous Systems
The code for the main driverless system
|
Observation Model class compiled of functions for observation model. More...
#include <observation_models.hpp>

Public Member Functions | |
| ObservationModel (const Eigen::MatrixXf &observation_noise_covariance_matrix) | |
| Construct a new Observation Model object. | |
| Eigen::Vector2f | observation_model (const Eigen::VectorXf &expected_state, const unsigned int landmark_index) const |
| Calculate expected observation from the state vector. | |
| Eigen::VectorXf | observation_model_n_landmarks (const Eigen::VectorXf ¤t_state, const std::vector< int > &matched_ids) const |
| Eigen::VectorXf | format_observation (const std::vector< Eigen::Vector2f > &observations) const |
| Eigen::MatrixXf | get_jacobian_of_observation_model (const Eigen::VectorXf ¤t_state, const std::vector< int > &matched_ids) const |
| Eigen::MatrixXf | get_full_observation_noise_covariance_matrix (const int observation_size) const |
| Eigen::Vector2f | inverse_observation_model (const Eigen::VectorXf &expected_state, const ObservationData &observation_data) const |
| Calculate landmark position from observation. | |
| Eigen::MatrixXf | get_gv (const Eigen::VectorXf &expected_state, const ObservationData &observation_data) const |
| Eigen::MatrixXf | get_gz (const Eigen::VectorXf &expected_state, const ObservationData &observation_data) const |
| Eigen::MatrixXf | get_state_to_observation_matrix (const Eigen::VectorXf &expected_state, const unsigned int landmark_index, const unsigned int state_size) const |
| Get the state to observation matrix of the observation model (H in LaTeX documentation) | |
| Eigen::MatrixXf | get_observation_noise_covariance_matrix () const |
| Get the observation noise covariance matrix (C or H) | |
Static Public Member Functions | |
| static Eigen::MatrixXf | create_observation_noise_covariance_matrix (float noise_value) |
| Create a Q matrix from a given noise value. | |
Private Attributes | |
| Eigen::MatrixXf | _observation_noise_covariance_matrix_ |
| H or C. | |
Observation Model class compiled of functions for observation model.
Definition at line 29 of file observation_models.hpp.
|
explicit |
Construct a new Observation Model object.
| observation_noise_covariance_matrix | covariance matrix of the observation noise (Q) |
Definition at line 5 of file observation_models.cpp.
|
static |
Create a Q matrix from a given noise value.
Definition at line 215 of file observation_models.cpp.

| Eigen::VectorXf ObservationModel::format_observation | ( | const std::vector< Eigen::Vector2f > & | observations | ) | const |
Definition at line 79 of file observation_models.cpp.
| Eigen::MatrixXf ObservationModel::get_full_observation_noise_covariance_matrix | ( | const int | observation_size | ) | const |
| Eigen::MatrixXf ObservationModel::get_gv | ( | const Eigen::VectorXf & | expected_state, |
| const ObservationData & | observation_data | ||
| ) | const |
Definition at line 32 of file observation_models.cpp.
| Eigen::MatrixXf ObservationModel::get_gz | ( | const Eigen::VectorXf & | expected_state, |
| const ObservationData & | observation_data | ||
| ) | const |
Definition at line 46 of file observation_models.cpp.
| Eigen::MatrixXf ObservationModel::get_jacobian_of_observation_model | ( | const Eigen::VectorXf & | current_state, |
| const std::vector< int > & | matched_ids | ||
| ) | const |
Definition at line 117 of file observation_models.cpp.
| Eigen::MatrixXf ObservationModel::get_observation_noise_covariance_matrix | ( | ) | const |
Get the observation noise covariance matrix (C or H)
Definition at line 205 of file observation_models.cpp.

| Eigen::MatrixXf ObservationModel::get_state_to_observation_matrix | ( | const Eigen::VectorXf & | expected_state, |
| const unsigned int | landmark_index, | ||
| const unsigned int | state_size | ||
| ) | const |
Get the state to observation matrix of the observation model (H in LaTeX documentation)
| landmark_index | index of the x variable of the landmark in the state vector |
| state_size | size of the state vector |
Definition at line 148 of file observation_models.cpp.

| Eigen::Vector2f ObservationModel::inverse_observation_model | ( | const Eigen::VectorXf & | expected_state, |
| const ObservationData & | observation_data | ||
| ) | const |
Calculate landmark position from observation.
Translates from the car's frame to the map frame.
| expected_state | |
| observation_data |
Definition at line 8 of file observation_models.cpp.

| Eigen::Vector2f ObservationModel::observation_model | ( | const Eigen::VectorXf & | expected_state, |
| const unsigned int | landmark_index | ||
| ) | const |
Calculate expected observation from the state vector.
Correponds to h in LaTeX documentation.
| expected_state | |
| landmark_index | index of the x variable of the landmark in the state vector |
Definition at line 56 of file observation_models.cpp.

| Eigen::VectorXf ObservationModel::observation_model_n_landmarks | ( | const Eigen::VectorXf & | current_state, |
| const std::vector< int > & | matched_ids | ||
| ) | const |
Definition at line 89 of file observation_models.cpp.
|
private |
H or C.
Definition at line 30 of file observation_models.hpp.