51template<
typename StateKeyType>
52const std::vector<StateKeyType>
Pos = { Keys::PosX, Keys::PosY, Keys::PosZ };
54template<
typename StateKeyType>
55const std::vector<StateKeyType>
Vel = { Keys::VelX, Keys::VelY, Keys::VelZ };
57template<
typename StateKeyType>
58const std::vector<StateKeyType>
PosVel = { Keys::PosX, Keys::PosY, Keys::PosZ,
59 Keys::VelX, Keys::VelY, Keys::VelZ };
64template<
typename StateKeyType>
71 template<
typename Scalar,
int Size>
81 F.template block<3>(
Pos,
Vel) = Eigen::Matrix3d::Identity();
95 template<
typename Scalar,
int Size>
102 const double& latitude,
103 const double& longitude,
106 if (algorithm == SystemModelCalcAlgorithm::VanLoan)
108 G.template block<3>(
Vel,
Vel) = trafo::e_Quat_n(latitude, longitude).toRotationMatrix();
140 updatePhiAndQ(Phi, Q, G, F, W, dt, latitude, longitude, algorithm);
150 bool ShowGui(
float itemWidth,
float unitWidth,
const char*
id)
152 bool changed =
false;
154 if (gui::widgets::InputDouble2WithUnit(fmt::format(
"{} of the acceleration due to user motion (Hor/Ver)##{}",
161 MakeComboItems<Units::CovarianceAccelUnits>().c_str(),
162 "%.2e", ImGuiInputTextFlags_CharsScientific))
169 gui::widgets::HelpMarker(fmt::format(
"Suitable values for the horizontal acceleration are around\n"
170 "- 1 {} for a pedestrian or ship,\n"
171 "- {} {} for a car, and\n"
172 "- {} {} for a military aircraft.\n"
173 "The vertical acceleration PSD is usually smaller.",
186 const std::vector<StateKeyType>&
Pos = Keys::Pos<StateKeyType>;
188 const std::vector<StateKeyType>&
Vel = Keys::Vel<StateKeyType>;
190 const std::vector<StateKeyType>&
PosVel = Keys::PosVel<StateKeyType>;
201 Eigen::Matrix3d a_S_n = Eigen::DiagonalMatrix<double, 3>(
_covarianceAccel[0],
205 Eigen::Matrix3d a_S_e = trafo::e_Quat_n(latitude, longitude) * a_S_n * trafo::n_Quat_e(latitude, longitude);
207 double dt2 = std::pow(dt, 2);
208 double dt3 = dt2 * dt;
213 Q.template block<3>(
Pos,
Pos) = dt3 / 3.0 * a_S_e;
214 Q.template block<3>(
Pos,
Vel) = dt2 / 2.0 * a_S_e;
215 Q.template block<3>(
Vel,
Pos) = Q.template block<3>(
Pos,
Vel).transpose();
216 Q.template block<3>(
Vel,
Vel) = dt * a_S_e;
246 if (j.contains(
"covarianceAccel")) { j.at(
"covarianceAccel").get_to(data.
_gui_covarianceAccel); }
258#ifndef DOXYGEN_IGNORE
262struct fmt::formatter<NAV::Keys::MotionModelKey> : fmt::formatter<const char*>
268 template<
typename FormatContext>
271 using namespace NAV::Keys;
276 return fmt::formatter<const char*>::format(
"PosX", ctx);
278 return fmt::formatter<const char*>::format(
"PosY", ctx);
280 return fmt::formatter<const char*>::format(
"PosZ", ctx);
282 return fmt::formatter<const char*>::format(
"VelX", ctx);
284 return fmt::formatter<const char*>::format(
"VelY", ctx);
286 return fmt::formatter<const char*>::format(
"VelZ", ctx);
287 case MotionModelKey_COUNT:
288 return fmt::formatter<const char*>::format(
"MotionModelKey_COUNT", ctx);
291 return fmt::formatter<const char*>::format(
"ERROR", ctx);
Transformation collection.
nlohmann::json json
json namespace
Definition FlowManager.hpp:21
Units used by the system model parameters.
double convertUnit(const double &value, Units::CovarianceAccelUnits unit)
Converts the value depending on the unit provided.
CovarianceAccelUnits
Possible Units for the Standard deviation of the acceleration due to user motion.
Definition Units.hpp:29
Text Help Marker (?) with Tooltip.
#define LOG_DEBUG
Debug information. Should not be called on functions which receive observations (spamming)
Definition Logger.hpp:67
Generalized Kalman Filter class.
Derived::PlainObject transitionMatrix_Phi_Taylor(const Eigen::MatrixBase< Derived > &F, double tau_s, size_t order)
Calculates the state transition matrix 𝚽 limited to specified order in 𝐅𝜏ₛ
Definition KalmanFilter.hpp:195
std::ostream & operator<<(std::ostream &os, const NAV::Keys::MotionModelKey &obj)
Stream insertion operator overload.
MotionModelKey
Keys used in the model.
Definition MotionModel.hpp:40
@ PosY
Position ECEF_Y [m].
Definition MotionModel.hpp:42
@ VelZ
Velocity ECEF_Z [m/s].
Definition MotionModel.hpp:46
@ VelY
Velocity ECEF_Y [m/s].
Definition MotionModel.hpp:45
@ VelX
Velocity ECEF_X [m/s].
Definition MotionModel.hpp:44
@ PosX
Position ECEF_X [m].
Definition MotionModel.hpp:41
@ PosZ
Position ECEF_Z [m].
Definition MotionModel.hpp:43
@ MotionModelKey_COUNT
Count.
Definition MotionModel.hpp:47
const std::vector< StateKeyType > Vel
All velocity keys.
Definition MotionModel.hpp:55
SystemModelCalcAlgorithm
Algorithms to calculate the system model with.
Definition SystemModel.hpp:23
Van Loan Method loan1978.
std::pair< typename DerivedF::PlainObject, typename DerivedF::PlainObject > calcPhiAndQWithVanLoanMethod(const Eigen::MatrixBase< DerivedF > &F, const Eigen::MatrixBase< DerivedG > &G, const Eigen::MatrixBase< DerivedW > &W, typename DerivedF::Scalar dt)
Numerical Method to calculate the State transition matrix 𝚽 and System/Process noise covariance matri...
Definition VanLoan.hpp:62
Static sized KeyedMatrix.
Definition KeyedMatrix.hpp:1910
Motion System Model.
Definition MotionModel.hpp:66
friend void to_json(json &j, const MotionModel &data)
Converts the provided data into a json object.
Definition MotionModel.hpp:233
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.
Definition MotionModel.hpp:96
std::array< double, 2 > _covarianceAccel
Covariance of the acceleration 𝜎_a due to user motion in horizontal and vertical component [m²/s³].
Definition MotionModel.hpp:228
std::array< double, 2 > _gui_covarianceAccel
GUI selection for the Standard deviation of the acceleration 𝜎_a due to user motion in horizontal and...
Definition MotionModel.hpp:225
void initialize(KeyedMatrix< Scalar, StateKeyType, StateKeyType, Size, Size > &F, KeyedMatrix< Scalar, StateKeyType, StateKeyType, Size, Size > &W)
Initializes the motion model.
Definition MotionModel.hpp:72
bool ShowGui(float itemWidth, float unitWidth, const char *id)
Shows a GUI.
Definition MotionModel.hpp:150
Units::CovarianceAccelUnits _gui_covarianceAccelUnit
Gui selection for the Unit of the input covarianceAccel parameter for the StDev due to acceleration d...
Definition MotionModel.hpp:222
KeyedMatrix6d< StateKeyType > calcProcessNoiseMatrixTaylor(double dt, double latitude, double longitude) const
Calculates the process noise matrix Q.
Definition MotionModel.hpp:198
friend void from_json(const json &j, MotionModel &data)
Converts the provided json object into the data object.
Definition MotionModel.hpp:243
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 (𝐐)
Definition MotionModel.hpp:131
const std::vector< StateKeyType > & Vel
All velocity keys.
Definition MotionModel.hpp:188
Position, Velocity and Attitude Storage Class.
Definition PosVel.hpp:23
Position, Velocity and Attitude Storage Class.
Definition Pos.hpp:30
Matrix which can be accessed by keys.