0.3.0
Loading...
Searching...
No Matches
NAV::MotionModel< StateKeyType > Class Template Reference

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.
 

Detailed Description

template<typename StateKeyType>
class NAV::MotionModel< StateKeyType >

Motion System Model.

Member Function Documentation

◆ calcPhiAndQ()

template<typename StateKeyType >
std::pair< KeyedMatrix6d< StateKeyType >, KeyedMatrix6d< StateKeyType > > NAV::MotionModel< StateKeyType >::calcPhiAndQ ( double dt,
const double & latitude,
const double & longitude,
SystemModelCalcAlgorithm algorithm )
inlinenodiscard

Calculates the state transition matrix (𝚽) and the process noise covariance matrix (𝐐)

Parameters
[in]dtTime step size in [s]
[in]latitudeLatitude [rad]
[in]longitudeLongitude [rad]
[in]algorithmAlgorithm to use for the calculation
Returns
Phi and Q matrix

◆ calcProcessNoiseMatrixTaylor()

template<typename StateKeyType >
KeyedMatrix6d< StateKeyType > NAV::MotionModel< StateKeyType >::calcProcessNoiseMatrixTaylor ( double dt,
double latitude,
double longitude ) const
inlinenodiscardprivate

Calculates the process noise matrix Q.

Parameters
[in]dtTime step [s]
[in]latitudeLatitude [rad]
[in]longitudeLongitude [rad]
Note
See [17] Groves, ch. 9.4.2.2, eq. 9.152, p. 417

◆ initialize()

template<typename StateKeyType >
template<typename Scalar , int Size>
void NAV::MotionModel< StateKeyType >::initialize ( KeyedMatrix< Scalar, StateKeyType, StateKeyType, Size, Size > & F,
KeyedMatrix< Scalar, StateKeyType, StateKeyType, Size, Size > & W )
inline

Initializes the motion model.

Parameters
[in,out]FSystem model matrix
[in,out]WNoise scale matrix

◆ ShowGui()

template<typename StateKeyType >
bool NAV::MotionModel< StateKeyType >::ShowGui ( float itemWidth,
float unitWidth,
const char * id )
inline

Shows a GUI.

Parameters
[in]itemWidthWidth of the space for the config items
[in]unitWidthWidth of the units
[in]idUnique id for ImGui
Returns
True if something was changed

◆ updatePhiAndQ()

template<typename StateKeyType >
template<typename Scalar , int Size>
void NAV::MotionModel< StateKeyType >::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 )
inline

Updates the provided Phi, Q and G matrix.

Parameters
[in,out]PhiState transition matrix
[in,out]QSystem/Process noise covariance matrix
[in,out]GNoise input matrix
[in]FSystem model matrix
[in]WNoise scale matrix
[in]dtTime step size in [s]
[in]latitudeLatitude [rad]
[in]longitudeLongitude [rad]
[in]algorithmAlgorithm to use for the calculation

Friends And Related Symbol Documentation

◆ from_json

template<typename StateKeyType >
void from_json ( const json & j,
MotionModel< StateKeyType > & data )
friend

Converts the provided json object into the data object.

Parameters
[in]jJson object with the needed values
[out]dataObject to fill from the json

◆ to_json

template<typename StateKeyType >
void to_json ( json & j,
const MotionModel< StateKeyType > & data )
friend

Converts the provided data into a json object.

Parameters
[out]jJson object which gets filled with the info
[in]dataData to convert into json

Member Data Documentation

◆ _gui_covarianceAccel

template<typename StateKeyType >
std::array<double, 2> NAV::MotionModel< StateKeyType >::_gui_covarianceAccel
private

GUI selection for the Standard deviation of the acceleration 𝜎_a due to user motion in horizontal and vertical component.

Note
See Groves (2013) eq. (9.156)

The documentation for this class was generated from the following file: