Cooperative Localisation Filters 0.0.1
|
Houses the parameters required for performing Bayesian filtering. More...
#include <filter.h>
Public Attributes | |
unsigned short | id |
unsigned short | barcode |
state_t | state_estimate = state_t::Zero() |
Estimated robot state - x coordinate [m], y-coordinate [m], and orientation (heading) [rad]: 3x1 matrix. | |
measurement_t | measurement = measurement_t::Zero() |
Recieved range and bearing measurement: 2x1 matrix. | |
measurement_t | innovation = measurement_t::Zero() |
The difference between the measurement recieved by the sensor and the predicted measurement based on the vehicles' states. | |
measurementCovariance_t | innovation_covariance |
Measurement innovation covariance matrix: 2x2 matrix. | |
augmentedState_t | estimation_residual = augmentedState_t::Zero() |
The difference between the prior and posterior state estimtes. | |
covariance_t | error_covariance = covariance_t::Identity() * 0.001 |
Estimation Error Covariance: 3x3 matrix. | |
kalmanGain_t | kalman_gain = kalmanGain_t::Zero() |
Kalman gain: 5x2 matrix. | |
processCovariance_t | process_noise = processCovariance_t::Zero() |
Odometry process noise covariance matrix: 2x2 matrix. | |
measurementCovariance_t | measurement_noise = measurementCovariance_t::Zero() |
Measurement noise covariance matrix: 2x2 matrix. | |
motionJacobian_t | motion_jacobian = motionJacobian_t::Zero() |
Jacobian matrix of the motion model evaluated in terms of the systems states: x, y and orientation. | |
processJacobian_t | process_jacobian = processJacobian_t::Zero() |
Jacobian matrix of the motion model evaluated in terms of the process inputs. | |
measurementJacobian_t | measurement_jacobian = measurementJacobian_t::Zero() |
Jacobian of the measurement model: 2 x 6 matrix. | |
state_t | information_vector = state_t::Zero() |
Information vector: 3x1 matrix. | |
precision_t | precision_matrix = error_covariance.inverse() |
Precision matrix: 3x3 matrix. | |
Houses the parameters required for performing Bayesian filtering.
unsigned short Filter::EstimationParameters::barcode |
covariance_t Filter::EstimationParameters::error_covariance = covariance_t::Identity() * 0.001 |
Estimation Error Covariance: 3x3 matrix.
There is a high certainty in the prior value of system state, therefore the prior estimation error covariance is initialised to a small value.
augmentedState_t Filter::EstimationParameters::estimation_residual = augmentedState_t::Zero() |
The difference between the prior and posterior state estimtes.
The estimation residual is defined by the expresssion:
\[\delta \mathbf{x}_k = \mathbf{x}_{k\mid k-1} - \mathbf{x}_{k\mid k} \]
.
unsigned short Filter::EstimationParameters::id |
state_t Filter::EstimationParameters::information_vector = state_t::Zero() |
Information vector: 3x1 matrix.
Used by the information form of the (Extended) Kalman Filter. The expression of the information vector take the form:
\[\begin{align}\nabla &= \Sigma^{-1}\mathbf{x} \\ &= \Lambda \mathbf{x}\end{align}\]
, where \(\Sigma\) denotes the estimation error covariance matrix (Filter::EstimationParameters.error_covariance); \(\Lambda\) denotes the information matrix (Filter::EstimationParameters.information_vector) \(\mathbf{x}\) denotes the state of the system (Filter::EstimationParameters.state_estimate).
measurement_t Filter::EstimationParameters::innovation = measurement_t::Zero() |
The difference between the measurement recieved by the sensor and the predicted measurement based on the vehicles' states.
The measurement residual is defined by the expression:
\[ \tilde{\mathbf{y}}_k = \mathbf{z}_k - h(\hat{\mathbf{x}}_{k\mid k-1})\]
, where \(\mathbf{z}\) is the measurement taken, and \(x_{k\mid k-1}\) is the estimated state of the robot.
measurementCovariance_t Filter::EstimationParameters::innovation_covariance |
Measurement innovation covariance matrix: 2x2 matrix.
kalmanGain_t Filter::EstimationParameters::kalman_gain = kalmanGain_t::Zero() |
Kalman gain: 5x2 matrix.
measurement_t Filter::EstimationParameters::measurement = measurement_t::Zero() |
Recieved range and bearing measurement: 2x1 matrix.
measurementJacobian_t Filter::EstimationParameters::measurement_jacobian = measurementJacobian_t::Zero() |
Jacobian of the measurement model: 2 x 6 matrix.
measurementCovariance_t Filter::EstimationParameters::measurement_noise = measurementCovariance_t::Zero() |
Measurement noise covariance matrix: 2x2 matrix.
The matrix for the measurement noise covariance matrix take the form
\[ v = \begin{bmatrix} q_r & 0 \\ 0 & q_\phi \end{bmatrix}, \]
where \(q_r\) denotes the range noise variance; and \(\phi_r\) denotes the bearing noise variance.
motionJacobian_t Filter::EstimationParameters::motion_jacobian = motionJacobian_t::Zero() |
Jacobian matrix of the motion model evaluated in terms of the systems states: x, y and orientation.
precision_t Filter::EstimationParameters::precision_matrix = error_covariance.inverse() |
Precision matrix: 3x3 matrix.
Used by the information form of the (Extended) Kalman Filter. The expression for the information matrix takes the form
\[\Lambda = \Sigma^{-1}\]
, where \(\Sigma\) denotes the estimation error covariance matrix (Filter::EstimationParameters.error_covariance).
processJacobian_t Filter::EstimationParameters::process_jacobian = processJacobian_t::Zero() |
Jacobian matrix of the motion model evaluated in terms of the process inputs.
processCovariance_t Filter::EstimationParameters::process_noise = processCovariance_t::Zero() |
Odometry process noise covariance matrix: 2x2 matrix.
The process noise covariance matrix is defined by the expression:
\[ w = \begin{bmatrix} q_v & 0 \\ 0 & q_\omega \end{bmatrix}, \]
where \(q_v\) denotes the forward velocity noise variance; and \(q_\omega\) denotes the angular velocity noise variance.
state_t Filter::EstimationParameters::state_estimate = state_t::Zero() |
Estimated robot state - x coordinate [m], y-coordinate [m], and orientation (heading) [rad]: 3x1 matrix.
The state vector of the robot take the form
\[\begin{bmatrix} x & y & \theta \end{bmatrix}^\top, \]
where \(x\) and \(y\) denotes the robots 2D coordinates; and \(\theta \) denotes the robots heading.