![]() |
0.3.0
|
Motion System Model. More...
Public Member Functions | |
std::pair< KeyedMatrix6d< StateKeyType >, KeyedMatrix6d< StateKeyType > > | calcPhiAndQ (double dt, const double &latitude, const double &longitude, SystemModelCalcAlgorithm algorithm) |
Calculates the state transition matrix (𝚽) and the process noise covariance matrix (𝐐) | |
template<typename Scalar , int Size> | |
void | initialize (KeyedMatrix< Scalar, StateKeyType, StateKeyType, Size, Size > &F, KeyedMatrix< Scalar, StateKeyType, StateKeyType, Size, Size > &W) |
Initializes the motion model. | |
bool | ShowGui (float itemWidth, float unitWidth, const char *id) |
Shows a GUI. | |
template<typename Scalar , int Size> | |
void | updatePhiAndQ (KeyedMatrix< Scalar, StateKeyType, StateKeyType, Size, Size > &Phi, KeyedMatrix< Scalar, StateKeyType, StateKeyType, Size, Size > &Q, KeyedMatrix< Scalar, StateKeyType, StateKeyType, Size, Size > &G, const KeyedMatrix< Scalar, StateKeyType, StateKeyType, Size, Size > &F, const KeyedMatrix< Scalar, StateKeyType, StateKeyType, Size, Size > &W, double dt, const double &latitude, const double &longitude, SystemModelCalcAlgorithm algorithm) |
Updates the provided Phi, Q and G matrix. | |
Private Member Functions | |
KeyedMatrix6d< StateKeyType > | calcProcessNoiseMatrixTaylor (double dt, double latitude, double longitude) const |
Calculates the process noise matrix Q. | |
Private Attributes | |
std::array< double, 2 > | _covarianceAccel |
Covariance of the acceleration 𝜎_a due to user motion in horizontal and vertical component [m²/s³]. | |
std::array< double, 2 > | _gui_covarianceAccel |
GUI selection for the Standard deviation of the acceleration 𝜎_a due to user motion in horizontal and vertical component. | |
Units::CovarianceAccelUnits | _gui_covarianceAccelUnit |
Gui selection for the Unit of the input covarianceAccel parameter for the StDev due to acceleration due to user motion. | |
const std::vector< StateKeyType > & | Pos |
All position keys. | |
const std::vector< StateKeyType > & | PosVel |
All position and velocity keys. | |
const std::vector< StateKeyType > & | Vel |
All velocity keys. | |
Friends | |
void | from_json (const json &j, MotionModel &data) |
Converts the provided json object into the data object. | |
void | to_json (json &j, const MotionModel &data) |
Converts the provided data into a json object. | |
Motion System Model.
|
inlinenodiscard |
Calculates the state transition matrix (𝚽) and the process noise covariance matrix (𝐐)
[in] | dt | Time step size in [s] |
[in] | latitude | Latitude [rad] |
[in] | longitude | Longitude [rad] |
[in] | algorithm | Algorithm to use for the calculation |
|
inlinenodiscardprivate |
Calculates the process noise matrix Q.
[in] | dt | Time step [s] |
[in] | latitude | Latitude [rad] |
[in] | longitude | Longitude [rad] |
|
inline |
Initializes the motion model.
[in,out] | F | System model matrix |
[in,out] | W | Noise scale matrix |
|
inline |
Shows a GUI.
[in] | itemWidth | Width of the space for the config items |
[in] | unitWidth | Width of the units |
[in] | id | Unique id for ImGui |
|
inline |
Updates the provided Phi, Q and G matrix.
[in,out] | Phi | State transition matrix |
[in,out] | Q | System/Process noise covariance matrix |
[in,out] | G | Noise input matrix |
[in] | F | System model matrix |
[in] | W | Noise scale matrix |
[in] | dt | Time step size in [s] |
[in] | latitude | Latitude [rad] |
[in] | longitude | Longitude [rad] |
[in] | algorithm | Algorithm to use for the calculation |
|
friend |
Converts the provided json object into the data object.
[in] | j | Json object with the needed values |
[out] | data | Object to fill from the json |
|
friend |
Converts the provided data into a json object.
[out] | j | Json object which gets filled with the info |
[in] | data | Data to convert into json |
|
private |
GUI selection for the Standard deviation of the acceleration 𝜎_a due to user motion in horizontal and vertical component.