0.3.0
Loading...
Searching...
No Matches
MotionModel.hpp
Go to the documentation of this file.
1// This file is part of INSTINCT, the INS Toolkit for Integrated
2// Navigation Concepts and Training by the Institute of Navigation of
3// the University of Stuttgart, Germany.
4//
5// This Source Code Form is subject to the terms of the Mozilla Public
6// License, v. 2.0. If a copy of the MPL was not distributed with this
7// file, You can obtain one at https://mozilla.org/MPL/2.0/.
8
13
14#pragma once
15
16#include <array>
17#include <cmath>
19#include <Eigen/Core>
20#include <cstdint>
21#include <imgui.h>
22
28#include "Units.hpp"
31
32namespace NAV
33{
34
35namespace Keys
36{
37
49
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 };
60
61} // namespace Keys
62
64template<typename StateKeyType>
66{
67 public:
71 template<typename Scalar, int Size>
74 {
75 for (size_t i = 0; i < _gui_covarianceAccel.size(); i++)
76 {
77 // Covariance of the acceleration 𝜎_a due to user motion in horizontal and vertical component [m²/s³]
79 }
80
81 F.template block<3>(Pos, Vel) = Eigen::Matrix3d::Identity();
82 W.template block<3>(Vel, Vel) = Eigen::DiagonalMatrix<double, 3>(_covarianceAccel[0], _covarianceAccel[0], _covarianceAccel[1]);
83 }
84
95 template<typename Scalar, int Size>
101 double dt,
102 const double& latitude,
103 const double& longitude,
104 SystemModelCalcAlgorithm algorithm)
105 {
106 if (algorithm == SystemModelCalcAlgorithm::VanLoan)
107 {
108 G.template block<3>(Vel, Vel) = trafo::e_Quat_n(latitude, longitude).toRotationMatrix();
109 auto [PhiMot, QMot] = NAV::calcPhiAndQWithVanLoanMethod(
110 F.template block<6>(PosVel, PosVel),
111 G.template block<6>(PosVel, PosVel),
112 W.template block<6>(PosVel, PosVel),
113 dt);
114 Phi.template block<6>(PosVel, PosVel) = PhiMot;
115 Q.template block<6>(PosVel, PosVel) = QMot;
116 }
117 else // QCalculationAlgorithm::Taylor1
118 {
119 Phi.template block<6>(PosVel, PosVel) = transitionMatrix_Phi_Taylor(F.template block<6>(PosVel, PosVel), dt, 1);
120 Q.template block<6>(PosVel, PosVel) = calcProcessNoiseMatrixTaylor(dt, latitude, longitude)(all, all);
121 }
122 }
123
130 [[nodiscard]] std::pair<KeyedMatrix6d<StateKeyType>, KeyedMatrix6d<StateKeyType>>
131 calcPhiAndQ(double dt, const double& latitude, const double& longitude, SystemModelCalcAlgorithm algorithm)
132 {
133 KeyedMatrix6d<StateKeyType> F(Eigen::Matrix6d::Zero(), PosVel, PosVel);
134 KeyedMatrix6d<StateKeyType> G(Eigen::Matrix6d::Zero(), PosVel, PosVel);
135 KeyedMatrix6d<StateKeyType> W(Eigen::Matrix6d::Zero(), PosVel, PosVel);
136 initialize(F, W);
137
138 KeyedMatrix6d<StateKeyType> Phi(Eigen::Matrix6d::Zero(), PosVel, PosVel);
139 KeyedMatrix6d<StateKeyType> Q(Eigen::Matrix6d::Zero(), PosVel, PosVel);
140 updatePhiAndQ(Phi, Q, G, F, W, dt, latitude, longitude, algorithm);
141
142 return { Phi, Q };
143 }
144
150 bool ShowGui(float itemWidth, float unitWidth, const char* id)
151 {
152 bool changed = false;
153
154 if (gui::widgets::InputDouble2WithUnit(fmt::format("{} of the acceleration due to user motion (Hor/Ver)##{}",
155 _gui_covarianceAccelUnit == Units::CovarianceAccelUnits::m_sqrts3
156 ? "StdDev"
157 : "Variance",
158 id)
159 .c_str(),
160 itemWidth, unitWidth, _gui_covarianceAccel.data(), _gui_covarianceAccelUnit,
161 MakeComboItems<Units::CovarianceAccelUnits>().c_str(), //"m/√(s^3)\0m^2/s^3\0\0",
162 "%.2e", ImGuiInputTextFlags_CharsScientific))
163 {
164 LOG_DEBUG("{}: _gui_covarianceAccel changed to {}", id, fmt::join(_gui_covarianceAccel.begin(), _gui_covarianceAccel.end(), ", "));
165 LOG_DEBUG("{}: _gui_covarianceAccelUnit changed to {}", id, to_string(_gui_covarianceAccelUnit));
166 changed = true;
167 }
168 ImGui::SameLine();
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.",
175 _gui_covarianceAccelUnit == Units::CovarianceAccelUnits::m_sqrts3 ? 3 : 10,
177 _gui_covarianceAccelUnit == Units::CovarianceAccelUnits::m_sqrts3 ? 10 : 100,
179 .c_str());
180
181 return changed;
182 }
183
184 private:
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>;
191
197 [[nodiscard]] KeyedMatrix6d<StateKeyType>
198 calcProcessNoiseMatrixTaylor(double dt, double latitude, double longitude) const
199 {
200 // Scaling matrix in n-frame
201 Eigen::Matrix3d a_S_n = Eigen::DiagonalMatrix<double, 3>(_covarianceAccel[0],
204 // Scaling matrix in e-frame
205 Eigen::Matrix3d a_S_e = trafo::e_Quat_n(latitude, longitude) * a_S_n * trafo::n_Quat_e(latitude, longitude);
206
207 double dt2 = std::pow(dt, 2);
208 double dt3 = dt2 * dt;
209
210 KeyedMatrix6d<StateKeyType> Q(Eigen::Matrix6d::Zero(), PosVel, PosVel);
211
212 // Groves ch. 9.4.2.2, eq. 9.152, p. 417
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;
217
218 return Q;
219 }
220
222 Units::CovarianceAccelUnits _gui_covarianceAccelUnit = Units::CovarianceAccelUnits::m_sqrts3;
225 std::array<double, 2> _gui_covarianceAccel = { 3.0, 1.5 } /* [ m / √(s^3) ] */;
226
228 std::array<double, 2> _covarianceAccel = { 3.0, 1.5 };
229
233 friend void to_json(json& j, const MotionModel& data)
234 {
235 j = {
236 { "covarianceAccelUnit", data._gui_covarianceAccelUnit },
237 { "covarianceAccel", data._gui_covarianceAccel },
238 };
239 }
243 friend void from_json(const json& j, MotionModel& data)
244 {
245 if (j.contains("covarianceAccelUnit")) { j.at("covarianceAccelUnit").get_to(data._gui_covarianceAccelUnit); }
246 if (j.contains("covarianceAccel")) { j.at("covarianceAccel").get_to(data._gui_covarianceAccel); }
247 }
248};
249
250} // namespace NAV
251
256std::ostream& operator<<(std::ostream& os, const NAV::Keys::MotionModelKey& obj);
257
258#ifndef DOXYGEN_IGNORE
259
261template<>
262struct fmt::formatter<NAV::Keys::MotionModelKey> : fmt::formatter<const char*>
263{
268 template<typename FormatContext>
269 auto format(const NAV::Keys::MotionModelKey& state, FormatContext& ctx) const
270 {
271 using namespace NAV::Keys; // NOLINT(google-build-using-namespace)
272
273 switch (state)
274 {
275 case PosX:
276 return fmt::formatter<const char*>::format("PosX", ctx);
277 case PosY:
278 return fmt::formatter<const char*>::format("PosY", ctx);
279 case PosZ:
280 return fmt::formatter<const char*>::format("PosZ", ctx);
281 case VelX:
282 return fmt::formatter<const char*>::format("VelX", ctx);
283 case VelY:
284 return fmt::formatter<const char*>::format("VelY", ctx);
285 case VelZ:
286 return fmt::formatter<const char*>::format("VelZ", ctx);
287 case MotionModelKey_COUNT:
288 return fmt::formatter<const char*>::format("MotionModelKey_COUNT", ctx);
289 }
290
291 return fmt::formatter<const char*>::format("ERROR", ctx);
292 }
293};
294
295#endif
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.
Defines Widgets which allow the input of values and the selection of the unit.
#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
const char * to_string(gui::widgets::PositionWithFrame::ReferenceFrame refFrame)
Converts the enum to a string.
System Model.
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.