0.3.0
Loading...
Searching...
No Matches
PosVel.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
17#include <Eigen/src/Core/Matrix.h>
18
19namespace NAV
20{
22class PosVel : public Pos
23{
24 public:
27 [[nodiscard]] static std::string type()
28 {
29 return "PosVel";
30 }
31
34 [[nodiscard]] std::string getType() const override { return type(); }
35
38 [[nodiscard]] static std::vector<std::string> parentTypes()
39 {
40 auto parent = Pos::parentTypes();
41 parent.push_back(Pos::type());
42 return parent;
43 }
44
46 [[nodiscard]] static std::vector<std::string> GetStaticDataDescriptors()
47 {
49 desc.reserve(GetStaticDescriptorCount());
50 desc.emplace_back("Velocity norm [m/s]");
51 desc.emplace_back("X velocity ECEF [m/s]");
52 desc.emplace_back("Y velocity ECEF [m/s]");
53 desc.emplace_back("Z velocity ECEF [m/s]");
54 desc.emplace_back("North velocity [m/s]");
55 desc.emplace_back("East velocity [m/s]");
56 desc.emplace_back("Down velocity [m/s]");
57 desc.emplace_back("X velocity ECEF StDev [m/s]");
58 desc.emplace_back("Y velocity ECEF StDev [m/s]");
59 desc.emplace_back("Z velocity ECEF StDev [m/s]");
60 desc.emplace_back("XY velocity StDev [m]");
61 desc.emplace_back("XZ velocity StDev [m]");
62 desc.emplace_back("YZ velocity StDev [m]");
63 desc.emplace_back("North velocity StDev [m/s]");
64 desc.emplace_back("East velocity StDev [m/s]");
65 desc.emplace_back("Down velocity StDev [m/s]");
66 desc.emplace_back("NE velocity StDev [m]");
67 desc.emplace_back("ND velocity StDev [m]");
68 desc.emplace_back("ED velocity StDev [m]");
69 return desc;
70 }
71
73 [[nodiscard]] static constexpr size_t GetStaticDescriptorCount() { return Pos::GetStaticDescriptorCount() + 19; }
74
76 [[nodiscard]] std::vector<std::string> staticDataDescriptors() const override { return GetStaticDataDescriptors(); }
77
79 [[nodiscard]] size_t staticDescriptorCount() const override { return GetStaticDescriptorCount(); }
80
84 [[nodiscard]] std::optional<double> getValueAt(size_t idx) const override
85 {
87 if (idx < Pos::GetStaticDescriptorCount()) { return Pos::getValueAt(idx); }
88 switch (idx)
89 {
90 case Pos::GetStaticDescriptorCount() + 0: // Velocity norm [m/s]
91 return e_velocity().norm();
92 case Pos::GetStaticDescriptorCount() + 1: // X velocity ECEF [m/s]
93 return e_velocity().x();
94 case Pos::GetStaticDescriptorCount() + 2: // Y velocity ECEF [m/s]
95 return e_velocity().y();
96 case Pos::GetStaticDescriptorCount() + 3: // Z velocity ECEF [m/s]
97 return e_velocity().z();
98 case Pos::GetStaticDescriptorCount() + 4: // North velocity [m/s]
99 return n_velocity().x();
100 case Pos::GetStaticDescriptorCount() + 5: // East velocity [m/s]
101 return n_velocity().y();
102 case Pos::GetStaticDescriptorCount() + 6: // Down velocity [m/s]
103 return n_velocity().z();
104 case Pos::GetStaticDescriptorCount() + 7: // X velocity ECEF StDev [m/s]
105 if (auto stDev = e_velocityStdev()) { return stDev->get().x(); }
106 break;
107 case Pos::GetStaticDescriptorCount() + 8: // Y velocity ECEF StDev [m/s]
108 if (auto stDev = e_velocityStdev()) { return stDev->get().y(); }
109 break;
110 case Pos::GetStaticDescriptorCount() + 9: // Z velocity ECEF StDev [m/s]
111 if (auto stDev = e_velocityStdev()) { return stDev->get().z(); }
112 break;
113 case Pos::GetStaticDescriptorCount() + 10: // XY velocity StDev [m]
114 if (e_CovarianceMatrix().has_value() && (*e_CovarianceMatrix()).get().hasAnyCols(States::Vel)) { return (*e_CovarianceMatrix())(States::VelX, States::VelY); }
115 break;
116 case Pos::GetStaticDescriptorCount() + 11: // XZ velocity StDev [m]
117 if (e_CovarianceMatrix().has_value() && (*e_CovarianceMatrix()).get().hasAnyCols(States::Vel)) { return (*e_CovarianceMatrix())(States::VelX, States::VelZ); }
118 break;
119 case Pos::GetStaticDescriptorCount() + 12: // YZ velocity StDev [m]
120 if (e_CovarianceMatrix().has_value() && (*e_CovarianceMatrix()).get().hasAnyCols(States::Vel)) { return (*e_CovarianceMatrix())(States::VelY, States::VelZ); }
121 break;
122 case Pos::GetStaticDescriptorCount() + 13: // North velocity StDev [m/s]
123 if (auto stDev = n_velocityStdev()) { return stDev->get().x(); }
124 break;
125 case Pos::GetStaticDescriptorCount() + 14: // East velocity StDev [m/s]
126 if (auto stDev = n_velocityStdev()) { return stDev->get().y(); }
127 break;
128 case Pos::GetStaticDescriptorCount() + 15: // Down velocity StDev [m/s]
129 if (auto stDev = n_velocityStdev()) { return stDev->get().z(); }
130 break;
131 case Pos::GetStaticDescriptorCount() + 16: // NE velocity StDev [m]
132 if (n_CovarianceMatrix().has_value() && (*n_CovarianceMatrix()).get().hasAnyCols(States::Vel)) { return (*n_CovarianceMatrix())(States::VelX, States::VelY); }
133 break;
134 case Pos::GetStaticDescriptorCount() + 17: // ND velocity StDev [m]
135 if (n_CovarianceMatrix().has_value() && (*n_CovarianceMatrix()).get().hasAnyCols(States::Vel)) { return (*n_CovarianceMatrix())(States::VelX, States::VelZ); }
136 break;
137 case Pos::GetStaticDescriptorCount() + 18: // ED velocity StDev [m]
138 if (n_CovarianceMatrix().has_value() && (*n_CovarianceMatrix()).get().hasAnyCols(States::Vel)) { return (*n_CovarianceMatrix())(States::VelY, States::VelZ); }
139 break;
140 default:
141 return std::nullopt;
142 }
143 return std::nullopt;
144 }
145
150 [[nodiscard]] bool setValueAt(size_t idx, double value) override
151 {
153 if (idx < Pos::GetStaticDescriptorCount()) { return Pos::setValueAt(idx, value); }
154 switch (idx)
155 {
156 case Pos::GetStaticDescriptorCount() + 0: // Velocity norm [m/s]
157 _e_velocity = value * _e_velocity.normalized();
158 _n_velocity = value * _n_velocity.normalized();
159 break;
160 case Pos::GetStaticDescriptorCount() + 1: // X velocity ECEF [m/s]
161 _e_velocity(0) = value;
163 break;
164 case Pos::GetStaticDescriptorCount() + 2: // Y velocity ECEF [m/s]
165 _e_velocity(1) = value;
167 break;
168 case Pos::GetStaticDescriptorCount() + 3: // Z velocity ECEF [m/s]
169 _e_velocity(2) = value;
171 break;
172 case Pos::GetStaticDescriptorCount() + 4: // North velocity [m/s]
173 _n_velocity(0) = value;
175 break;
176 case Pos::GetStaticDescriptorCount() + 5: // East velocity [m/s]
177 _n_velocity(1) = value;
179 break;
180 case Pos::GetStaticDescriptorCount() + 6: // Down velocity [m/s]
181 _n_velocity(2) = value;
183 break;
184 case Pos::GetStaticDescriptorCount() + 7: // X velocity ECEF StDev [m/s]
185 case Pos::GetStaticDescriptorCount() + 8: // Y velocity ECEF StDev [m/s]
186 case Pos::GetStaticDescriptorCount() + 9: // Z velocity ECEF StDev [m/s]
187 case Pos::GetStaticDescriptorCount() + 10: // XY velocity StDev [m]
188 case Pos::GetStaticDescriptorCount() + 11: // XZ velocity StDev [m]
189 case Pos::GetStaticDescriptorCount() + 12: // YZ velocity StDev [m]
190 case Pos::GetStaticDescriptorCount() + 13: // North velocity StDev [m/s]
191 case Pos::GetStaticDescriptorCount() + 14: // East velocity StDev [m/s]
192 case Pos::GetStaticDescriptorCount() + 15: // Down velocity StDev [m/s]
193 case Pos::GetStaticDescriptorCount() + 16: // NE velocity StDev [m]
194 case Pos::GetStaticDescriptorCount() + 17: // ND velocity StDev [m]
195 case Pos::GetStaticDescriptorCount() + 18: // ED velocity StDev [m]
196 default:
197 return false;
198 }
199
200 return true;
201 }
202
203 /* -------------------------------------------------------------------------------------------------------- */
204 /* Velocity */
205 /* -------------------------------------------------------------------------------------------------------- */
206
208 struct States
209 {
211 States() = delete;
212
225 inline static const std::vector<StateKeys> Pos = { PosX, PosY, PosZ };
227 inline static const std::vector<StateKeys> Vel = { States::VelX, States::VelY, States::VelZ };
229 inline static const std::vector<StateKeys> PosVel = { States::PosX, States::PosY, States::PosZ,
231 };
232
234 [[nodiscard]] const Eigen::Vector3d& e_velocity() const { return _e_velocity; }
235
237 [[nodiscard]] const Eigen::Vector3d& n_velocity() const { return _n_velocity; }
238
240 [[nodiscard]] std::optional<std::reference_wrapper<const Eigen::Vector3d>> e_velocityStdev() const { return _e_velocityStdev; }
241
243 [[nodiscard]] std::optional<std::reference_wrapper<const Eigen::Vector3d>> n_velocityStdev() const { return _n_velocityStdev; }
244
246 [[nodiscard]] std::optional<std::reference_wrapper<const KeyedMatrixXd<States::StateKeys, States::StateKeys>>> e_CovarianceMatrix() const { return _e_covarianceMatrix; }
247
249 [[nodiscard]] std::optional<std::reference_wrapper<const KeyedMatrixXd<States::StateKeys, States::StateKeys>>> n_CovarianceMatrix() const { return _n_covarianceMatrix; }
250
251 // ###########################################################################################################
252 // Setter
253 // ###########################################################################################################
254
257 template<typename Derived>
258 void setVelocity_e(const Eigen::MatrixBase<Derived>& e_velocity)
259 {
262 }
263
266 template<typename Derived>
267 void setVelocity_n(const Eigen::MatrixBase<Derived>& n_velocity)
268 {
271 }
272
276 template<typename Derived, typename Derived2>
277 void setVelocityAndStdDev_e(const Eigen::MatrixBase<Derived>& e_velocity, const Eigen::MatrixBase<Derived2>& e_velocityCovarianceMatrix)
278 {
280 _e_velocityStdev = e_velocityCovarianceMatrix.diagonal().cwiseSqrt();
281 _n_velocityStdev = (n_Quat_e() * e_velocityCovarianceMatrix * e_Quat_n()).diagonal().cwiseSqrt();
282 }
283
287 template<typename Derived, typename Derived2>
288 void setVelocityAndStdDev_n(const Eigen::MatrixBase<Derived>& n_velocity, const Eigen::MatrixBase<Derived2>& n_velocityCovarianceMatrix)
289 {
291 _n_velocityStdev = n_velocityCovarianceMatrix.diagonal().cwiseSqrt();
292 _e_velocityStdev = (e_Quat_n() * n_velocityCovarianceMatrix * n_Quat_e()).diagonal().cwiseSqrt();
293 }
294
298 template<typename Derived>
299 void setPosVelCovarianceMatrix_e(const Eigen::MatrixBase<Derived>& e_covarianceMatrix)
300 {
301 INS_ASSERT_USER_ERROR(e_covarianceMatrix.rows() == 6, "This function needs a 6x6 matrix as input");
302 INS_ASSERT_USER_ERROR(e_covarianceMatrix.cols() == 6, "This function needs a 6x6 matrix as input");
303
305 States::StateKeys>(e_covarianceMatrix,
308
309 Eigen::Quaterniond n_Quat_e = trafo::n_Quat_e(latitude(), longitude());
310 Eigen::Quaterniond e_Quat_n = trafo::e_Quat_n(latitude(), longitude());
311
312 (*_n_covarianceMatrix)(all, all).setZero();
315 }
316
320 template<typename Derived>
321 void setPosVelCovarianceMatrix_n(const Eigen::MatrixBase<Derived>& n_covarianceMatrix)
322 {
323 INS_ASSERT_USER_ERROR(n_covarianceMatrix.rows() == 6, "This function needs a 6x6 matrix as input");
324 INS_ASSERT_USER_ERROR(n_covarianceMatrix.cols() == 6, "This function needs a 6x6 matrix as input");
325
327 States::StateKeys>(n_covarianceMatrix,
330
331 Eigen::Quaterniond n_Quat_e = trafo::n_Quat_e(latitude(), longitude());
332 Eigen::Quaterniond e_Quat_n = trafo::e_Quat_n(latitude(), longitude());
333
334 (*_e_covarianceMatrix)(all, all).setZero();
337 }
338
339 /* -------------------------------------------------------------------------------------------------------- */
340 /* Member variables */
341 /* -------------------------------------------------------------------------------------------------------- */
342
343 private:
345 Eigen::Vector3d _e_velocity{ std::nan(""), std::nan(""), std::nan("") };
347 Eigen::Vector3d _n_velocity{ std::nan(""), std::nan(""), std::nan("") };
348
350 std::optional<Eigen::Vector3d> _e_velocityStdev;
352 std::optional<Eigen::Vector3d> _n_velocityStdev;
353
355 std::optional<KeyedMatrixXd<States::StateKeys, States::StateKeys>> _e_covarianceMatrix;
356
358 std::optional<KeyedMatrixXd<States::StateKeys, States::StateKeys>> _n_covarianceMatrix;
359};
360
361} // namespace NAV
#define INS_ASSERT(_EXPR)
Assert function wrapper.
Definition Assert.h:19
#define INS_ASSERT_USER_ERROR(_EXP, _MSG)
Assert function with message.
Definition Assert.h:21
Position Storage Class.
Dynamic sized KeyedMatrix.
Definition KeyedMatrix.hpp:2055
Position, Velocity and Attitude Storage Class.
Definition PosVel.hpp:23
static constexpr size_t GetStaticDescriptorCount()
Get the amount of descriptors.
Definition PosVel.hpp:73
static std::vector< std::string > parentTypes()
Returns the parent types of the data class.
Definition PosVel.hpp:38
const Eigen::Vector3d & n_velocity() const
Returns the velocity in [m/s], in navigation coordinates.
Definition PosVel.hpp:237
bool setValueAt(size_t idx, double value) override
Set the value at the index.
Definition PosVel.hpp:150
std::optional< std::reference_wrapper< const Eigen::Vector3d > > e_velocityStdev() const
Returns the standard deviation of the velocity in [m/s], in earth coordinates.
Definition PosVel.hpp:240
std::string getType() const override
Returns the type of the data class.
Definition PosVel.hpp:34
static std::vector< std::string > GetStaticDataDescriptors()
Returns a vector of data descriptors.
Definition PosVel.hpp:46
std::vector< std::string > staticDataDescriptors() const override
Returns a vector of data descriptors.
Definition PosVel.hpp:76
static std::string type()
Returns the type of the data class.
Definition PosVel.hpp:27
std::optional< std::reference_wrapper< const Eigen::Vector3d > > n_velocityStdev() const
Returns the standard deviation of the velocity in [m/s], in navigation coordinates.
Definition PosVel.hpp:243
size_t staticDescriptorCount() const override
Get the amount of descriptors.
Definition PosVel.hpp:79
void setPosVelCovarianceMatrix_e(const Eigen::MatrixBase< Derived > &e_covarianceMatrix)
Set the Covariance matrix in ECEF coordinates.
Definition PosVel.hpp:299
std::optional< KeyedMatrixXd< States::StateKeys, States::StateKeys > > _n_covarianceMatrix
Covariance matrix in local navigation coordinates.
Definition PosVel.hpp:358
std::optional< Eigen::Vector3d > _n_velocityStdev
Standard deviation of Velocity in navigation coordinates [m/s].
Definition PosVel.hpp:352
std::optional< KeyedMatrixXd< States::StateKeys, States::StateKeys > > _e_covarianceMatrix
Covariance matrix in ECEF coordinates.
Definition PosVel.hpp:355
std::optional< std::reference_wrapper< const KeyedMatrixXd< States::StateKeys, States::StateKeys > > > e_CovarianceMatrix() const
Returns the Covariance matrix in ECEF frame.
Definition PosVel.hpp:246
Eigen::Vector3d _e_velocity
Velocity in earth coordinates [m/s].
Definition PosVel.hpp:345
void setVelocityAndStdDev_n(const Eigen::MatrixBase< Derived > &n_velocity, const Eigen::MatrixBase< Derived2 > &n_velocityCovarianceMatrix)
Set the Velocity in NED coordinates and its standard deviation.
Definition PosVel.hpp:288
Eigen::Vector3d _n_velocity
Velocity in navigation coordinates [m/s].
Definition PosVel.hpp:347
const Eigen::Vector3d & e_velocity() const
Returns the velocity in [m/s], in earth coordinates.
Definition PosVel.hpp:234
std::optional< std::reference_wrapper< const KeyedMatrixXd< States::StateKeys, States::StateKeys > > > n_CovarianceMatrix() const
Returns the Covariance matrix in local navigation frame.
Definition PosVel.hpp:249
std::optional< double > getValueAt(size_t idx) const override
Get the value at the index.
Definition PosVel.hpp:84
void setVelocityAndStdDev_e(const Eigen::MatrixBase< Derived > &e_velocity, const Eigen::MatrixBase< Derived2 > &e_velocityCovarianceMatrix)
Set the Velocity in ECEF coordinates and its standard deviation.
Definition PosVel.hpp:277
std::optional< Eigen::Vector3d > _e_velocityStdev
Standard deviation of Velocity in earth coordinates [m/s].
Definition PosVel.hpp:350
void setVelocity_n(const Eigen::MatrixBase< Derived > &n_velocity)
Set the Velocity in the NED frame.
Definition PosVel.hpp:267
void setVelocity_e(const Eigen::MatrixBase< Derived > &e_velocity)
Set the Velocity in the earth frame.
Definition PosVel.hpp:258
void setPosVelCovarianceMatrix_n(const Eigen::MatrixBase< Derived > &n_covarianceMatrix)
Set the Covariance matrix in NED coordinates.
Definition PosVel.hpp:321
Position, Velocity and Attitude Storage Class.
Definition Pos.hpp:30
std::optional< double > getValueAt(size_t idx) const override
Get the value at the index.
Definition Pos.hpp:89
static std::vector< std::string > GetStaticDataDescriptors()
Returns a vector of data descriptors.
Definition Pos.hpp:51
static constexpr size_t GetStaticDescriptorCount()
Get the amount of descriptors.
Definition Pos.hpp:78
bool setValueAt(size_t idx, double value) override
Set the value at the index.
Definition Pos.hpp:156
const double & latitude() const
Returns the latitude 𝜙 in [rad].
Definition Pos.hpp:256
static std::vector< std::string > parentTypes()
Returns the parent types of the data class.
Definition Pos.hpp:45
Eigen::Quaterniond e_Quat_n() const
Returns the Quaternion from navigation to Earth-fixed frame.
Definition Pos.hpp:218
static std::string type()
Returns the type of the data class.
Definition Pos.hpp:34
Eigen::Quaterniond n_Quat_e() const
Returns the Quaternion from Earth-fixed frame to navigation.
Definition Pos.hpp:225
const double & longitude() const
Returns the longitude λ in [rad].
Definition Pos.hpp:259
States.
Definition PosVel.hpp:209
StateKeys
State Keys.
Definition PosVel.hpp:215
@ States_COUNT
Count.
Definition PosVel.hpp:222
@ PosY
Position ECEF_Y [m].
Definition PosVel.hpp:217
@ PosZ
Position ECEF_Z [m].
Definition PosVel.hpp:218
@ PosX
Position ECEF_X [m].
Definition PosVel.hpp:216
@ VelY
Velocity ECEF_Y [m/s].
Definition PosVel.hpp:220
@ VelZ
Velocity ECEF_Z [m/s].
Definition PosVel.hpp:221
@ VelX
Velocity ECEF_X [m/s].
Definition PosVel.hpp:219
States()=delete
Constructor.
static const std::vector< StateKeys > PosVel
Vector with all position and velocity state keys.
Definition PosVel.hpp:229
static const std::vector< StateKeys > Vel
All velocity keys.
Definition PosVel.hpp:227
static const std::vector< StateKeys > Pos
All position keys.
Definition PosVel.hpp:225