#include <XYModel.hpp>

Classes | |
| struct | ModelParams |
Public Types | |
| enum | { u = 0, v, r, xp, yp, psi, xc, yc, b1, b2 } |
| enum | { stateNum = 10 } |
| enum | { inputSize = 3 } |
| enum | { measSize = 3 } |
| enum | { X = 0, Y, N } |
| enum | { x_m = 0, y_m, psi_m, psiOnly_m = 0 } |
| typedef vector | input_type |
| typedef vector | output_type |
Public Member Functions | |
| void | calculateXYInovationVariance (const matrix &P, double &xin, double &yin) |
| void | estimate_y (output_type &y) |
| const output_type & | fullUpdate (double x, double y, double yaw) |
| void | getNEDSpeed (double &xdot, double &ydot) |
| void | initModel () |
| const output_type & | positionUpdate (double x, double y) |
| void | setParameters (const ModelParams &surge, const ModelParams &sway, const ModelParams &yaw) |
| void | step (const input_type &input) |
| const output_type & | update (vector &measurements, vector &newMeas) |
| XYModel () | |
| const output_type & | yawUpdate (double yaw) |
| ~XYModel () | |
Protected Member Functions | |
| void | derivativeAW () |
| void | derivativeHV (int num) |
Protected Attributes | |
| output_type | measurement |
| ModelParams | surge |
| ModelParams | sway |
| double | xdot |
| ModelParams | yaw |
| double | ydot |
Private Types | |
| typedef SSModel< double > | Base |
This class implements a x-y surface dynamic model for the EKF filter.
Definition at line 48 of file XYModel.hpp.
typedef SSModel<double> labust::navigation::XYModel::Base [private] |
Definition at line 50 of file XYModel.hpp.
Definition at line 52 of file XYModel.hpp.
Definition at line 53 of file XYModel.hpp.
| anonymous enum |
Definition at line 75 of file XYModel.hpp.
| anonymous enum |
Definition at line 76 of file XYModel.hpp.
| anonymous enum |
Definition at line 77 of file XYModel.hpp.
| anonymous enum |
Definition at line 78 of file XYModel.hpp.
| anonymous enum |
Definition at line 79 of file XYModel.hpp.
| anonymous enum |
Definition at line 80 of file XYModel.hpp.
| XYModel::XYModel | ( | ) |
The default constructor.
Definition at line 42 of file XYModel.cpp.
Generic destructor.
Definition at line 49 of file XYModel.cpp.
| void XYModel::calculateXYInovationVariance | ( | const matrix & | P, |
| double & | xin, | ||
| double & | yin | ||
| ) |
Definition at line 129 of file XYModel.cpp.
| void XYModel::derivativeAW | ( | ) | [protected] |
Calculate the Jacobian matrices.
Definition at line 152 of file XYModel.cpp.
| void labust::navigation::XYModel::derivativeHV | ( | int | num | ) | [protected] |
Calculate the Jacobian matrices.
| void XYModel::estimate_y | ( | output_type & | y | ) |
Calculates the estimated output of the model.
| y | Inserts the estimated output values here. |
Definition at line 202 of file XYModel.cpp.
| const output_type& labust::navigation::XYModel::fullUpdate | ( | double | x, |
| double | y, | ||
| double | yaw | ||
| ) |
Setup the measurement matrix for full update.
| void labust::navigation::XYModel::getNEDSpeed | ( | double & | xdot, |
| double & | ydot | ||
| ) | [inline] |
Return the speeds in the local frame.
Definition at line 145 of file XYModel.hpp.
| void XYModel::initModel | ( | ) |
Initialize the model to default values
Definition at line 51 of file XYModel.cpp.
| const output_type& labust::navigation::XYModel::positionUpdate | ( | double | x, |
| double | y | ||
| ) |
Setup the measurement matrix for position update.
| void labust::navigation::XYModel::setParameters | ( | const ModelParams & | surge, |
| const ModelParams & | sway, | ||
| const ModelParams & | yaw | ||
| ) | [inline] |
Set the model parameters.
Definition at line 131 of file XYModel.hpp.
| void XYModel::step | ( | const input_type & | input | ) |
Perform a prediction step based on the system input.
| u | System input. |
Definition at line 135 of file XYModel.cpp.
| const XYModel::output_type & XYModel::update | ( | vector & | measurements, |
| vector & | newMeas | ||
| ) |
Setup the measurement matrix for available measurements.
Definition at line 62 of file XYModel.cpp.
| const output_type& labust::navigation::XYModel::yawUpdate | ( | double | yaw | ) |
Setup the measurement matrix for heading only.
output_type labust::navigation::XYModel::measurement [protected] |
The newest measurement.
Definition at line 168 of file XYModel.hpp.
ModelParams labust::navigation::XYModel::surge [protected] |
The model parameters.
Definition at line 164 of file XYModel.hpp.
ModelParams labust::navigation::XYModel::sway [protected] |
Definition at line 164 of file XYModel.hpp.
double labust::navigation::XYModel::xdot [protected] |
The NED speeds.
Definition at line 172 of file XYModel.hpp.
ModelParams labust::navigation::XYModel::yaw [protected] |
Definition at line 164 of file XYModel.hpp.
double labust::navigation::XYModel::ydot [protected] |
Definition at line 172 of file XYModel.hpp.