0.2.0
Loading...
Searching...
No Matches
PosVelAtt.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
18#include "Navigation/Transformations/Units.hpp"
20
21namespace NAV
22{
24class PosVelAtt : public PosVel
25{
26 public:
29 [[nodiscard]] static std::string type()
30 {
31 return "PosVelAtt";
32 }
33
36 [[nodiscard]] static std::vector<std::string> parentTypes()
37 {
38 auto parent = PosVel::parentTypes();
39 parent.push_back(PosVel::type());
40 return parent;
41 }
42
44 [[nodiscard]] static std::vector<std::string> GetStaticDataDescriptors()
45 {
47 desc.reserve(GetStaticDescriptorCount());
48 desc.emplace_back("Roll [deg]");
49 desc.emplace_back("Pitch [deg]");
50 desc.emplace_back("Yaw [deg]");
51 desc.emplace_back("Quaternion::w");
52 desc.emplace_back("Quaternion::x");
53 desc.emplace_back("Quaternion::y");
54 desc.emplace_back("Quaternion::z");
55 return desc;
56 }
57
59 [[nodiscard]] static constexpr size_t GetStaticDescriptorCount() { return 46; }
60
62 [[nodiscard]] std::vector<std::string> staticDataDescriptors() const override { return GetStaticDataDescriptors(); }
63
65 [[nodiscard]] size_t staticDescriptorCount() const override { return GetStaticDescriptorCount(); }
66
70 [[nodiscard]] std::optional<double> getValueAt(size_t idx) const override
71 {
73 switch (idx)
74 {
75 case 0: // Latitude [deg]
76 case 1: // Longitude [deg]
77 case 2: // Altitude [m]
78 case 3: // North/South [m]
79 case 4: // East/West [m]
80 case 5: // X-ECEF [m]
81 case 6: // Y-ECEF [m]
82 case 7: // Z-ECEF [m]
83 case 8: // X-ECEF StDev [m]
84 case 9: // Y-ECEF StDev [m]
85 case 10: // Z-ECEF StDev [m]
86 case 11: // XY-ECEF StDev [m]
87 case 12: // XZ-ECEF StDev [m]
88 case 13: // YZ-ECEF StDev [m]
89 case 14: // North StDev [m]
90 case 15: // East StDev [m]
91 case 16: // Down StDev [m]
92 case 17: // NE StDev [m]
93 case 18: // ND StDev [m]
94 case 19: // ED StDev [m]
95 case 20: // Velocity norm [m/s]
96 case 21: // X velocity ECEF [m/s]
97 case 22: // Y velocity ECEF [m/s]
98 case 23: // Z velocity ECEF [m/s]
99 case 24: // North velocity [m/s]
100 case 25: // East velocity [m/s]
101 case 26: // Down velocity [m/s]
102 case 27: // X velocity ECEF StDev [m/s]
103 case 28: // Y velocity ECEF StDev [m/s]
104 case 29: // Z velocity ECEF StDev [m/s]
105 case 30: // XY velocity StDev [m]
106 case 31: // XZ velocity StDev [m]
107 case 32: // YZ velocity StDev [m]
108 case 33: // North velocity StDev [m/s]
109 case 34: // East velocity StDev [m/s]
110 case 35: // Down velocity StDev [m/s]
111 case 36: // NE velocity StDev [m]
112 case 37: // ND velocity StDev [m]
113 case 38: // ED velocity StDev [m]
114 return PosVel::getValueAt(idx);
115 case 39: // Roll [deg]
116 return rad2deg(rollPitchYaw().x());
117 case 40: // Pitch [deg]
118 return rad2deg(rollPitchYaw().y());
119 case 41: // Yaw [deg]
120 return rad2deg(rollPitchYaw().z());
121 case 42: // Quaternion::w
122 return n_Quat_b().w();
123 case 43: // Quaternion::x
124 return n_Quat_b().x();
125 case 44: // Quaternion::y
126 return n_Quat_b().y();
127 case 45: // Quaternion::z
128 return n_Quat_b().z();
129 default:
130 return std::nullopt;
131 }
132 return std::nullopt;
133 }
134
135 /* -------------------------------------------------------------------------------------------------------- */
136 /* Rotation Quaternions */
137 /* -------------------------------------------------------------------------------------------------------- */
138
141 [[nodiscard]] const Eigen::Quaterniond& n_Quat_b() const
142 {
143 return _n_Quat_b;
144 }
145
148 [[nodiscard]] Eigen::Quaterniond b_Quat_n() const
149 {
150 return n_Quat_b().conjugate();
151 }
152
155 [[nodiscard]] const Eigen::Quaterniond& e_Quat_b() const
156 {
157 return _e_Quat_b;
158 }
159
162 [[nodiscard]] Eigen::Quaterniond b_Quat_e() const
163 {
164 return e_Quat_b().conjugate();
165 }
166
169 [[nodiscard]] Eigen::Vector3d rollPitchYaw() const
170 {
171 return trafo::quat2eulerZYX(n_Quat_b());
172 }
173
174 // ###########################################################################################################
175 // Setter
176 // ###########################################################################################################
177
180 void setAttitude_e_Quat_b(const Eigen::Quaterniond& e_Quat_b)
181 {
182 _e_Quat_b = e_Quat_b;
183 _n_Quat_b = n_Quat_e() * e_Quat_b;
184 }
185
188 void setAttitude_n_Quat_b(const Eigen::Quaterniond& n_Quat_b)
189 {
190 _e_Quat_b = e_Quat_n() * n_Quat_b;
191 _n_Quat_b = n_Quat_b;
192 }
193
198 void setState_e(const Eigen::Vector3d& e_position, const Eigen::Vector3d& e_velocity, const Eigen::Quaterniond& e_Quat_b)
199 {
203 }
204
209 void setState_n(const Eigen::Vector3d& lla_position, const Eigen::Vector3d& n_velocity, const Eigen::Quaterniond& n_Quat_b)
210 {
214 }
215
222 void setStateAndCovariance_e(const Eigen::Vector3d& e_position, const Eigen::Matrix3d& e_positionCovarianceMatrix,
223 const Eigen::Vector3d& e_velocity, const Eigen::Matrix3d& e_velocityCovarianceMatrix,
224 const Eigen::Quaterniond& e_Quat_b)
225 {
226 setPositionAndStdDev_e(e_position, e_positionCovarianceMatrix);
227 setVelocityAndStdDev_e(e_velocity, e_velocityCovarianceMatrix);
229 }
230
237 void setStateAndCovariance_n(const Eigen::Vector3d& lla_position, const Eigen::Matrix3d& n_positionCovarianceMatrix,
238 const Eigen::Vector3d& n_velocity, const Eigen::Matrix3d& n_velocityCovarianceMatrix,
239 const Eigen::Quaterniond& n_Quat_b)
240 {
241 setPositionAndStdDev_lla(lla_position, n_positionCovarianceMatrix);
242 setVelocityAndStdDev_n(n_velocity, n_velocityCovarianceMatrix);
244 }
245
246 /* -------------------------------------------------------------------------------------------------------- */
247 /* Member variables */
248 /* -------------------------------------------------------------------------------------------------------- */
249
250 private:
252 Eigen::Quaterniond _e_Quat_b{ 0, 0, 0, 0 };
254 Eigen::Quaterniond _n_Quat_b{ 0, 0, 0, 0 };
255};
256
257} // namespace NAV
#define INS_ASSERT(_EXPR)
Assert function wrapper.
Definition Assert.h:19
Transformation collection.
Position, Velocity and Attitude Storage Class.
Position, Velocity and Attitude Storage Class.
Definition PosVelAtt.hpp:25
Eigen::Quaterniond b_Quat_n() const
Returns the Quaternion from navigation to body frame (NED)
Definition PosVelAtt.hpp:148
void setStateAndCovariance_n(const Eigen::Vector3d &lla_position, const Eigen::Matrix3d &n_positionCovarianceMatrix, const Eigen::Vector3d &n_velocity, const Eigen::Matrix3d &n_velocityCovarianceMatrix, const Eigen::Quaterniond &n_Quat_b)
Set the State and the covariances.
Definition PosVelAtt.hpp:237
size_t staticDescriptorCount() const override
Get the amount of descriptors.
Definition PosVelAtt.hpp:65
void setStateAndCovariance_e(const Eigen::Vector3d &e_position, const Eigen::Matrix3d &e_positionCovarianceMatrix, const Eigen::Vector3d &e_velocity, const Eigen::Matrix3d &e_velocityCovarianceMatrix, const Eigen::Quaterniond &e_Quat_b)
Set the State and the covariances.
Definition PosVelAtt.hpp:222
std::vector< std::string > staticDataDescriptors() const override
Returns a vector of data descriptors.
Definition PosVelAtt.hpp:62
static std::vector< std::string > GetStaticDataDescriptors()
Returns a vector of data descriptors.
Definition PosVelAtt.hpp:44
void setAttitude_n_Quat_b(const Eigen::Quaterniond &n_Quat_b)
Set the Quaternion from body to navigation frame.
Definition PosVelAtt.hpp:188
static constexpr size_t GetStaticDescriptorCount()
Get the amount of descriptors.
Definition PosVelAtt.hpp:59
std::optional< double > getValueAt(size_t idx) const override
Get the value at the index.
Definition PosVelAtt.hpp:70
void setState_e(const Eigen::Vector3d &e_position, const Eigen::Vector3d &e_velocity, const Eigen::Quaterniond &e_Quat_b)
Set the State.
Definition PosVelAtt.hpp:198
const Eigen::Quaterniond & n_Quat_b() const
Returns the Quaternion from body to navigation frame (NED)
Definition PosVelAtt.hpp:141
static std::string type()
Returns the type of the data class.
Definition PosVelAtt.hpp:29
void setAttitude_e_Quat_b(const Eigen::Quaterniond &e_Quat_b)
Set the Quaternion from body to earth frame.
Definition PosVelAtt.hpp:180
Eigen::Quaterniond b_Quat_e() const
Returns the Quaternion from Earth-fixed to body frame.
Definition PosVelAtt.hpp:162
void setState_n(const Eigen::Vector3d &lla_position, const Eigen::Vector3d &n_velocity, const Eigen::Quaterniond &n_Quat_b)
Set the State.
Definition PosVelAtt.hpp:209
Eigen::Vector3d rollPitchYaw() const
Returns the Roll, Pitch and Yaw angles in [rad].
Definition PosVelAtt.hpp:169
const Eigen::Quaterniond & e_Quat_b() const
Returns the Quaternion from body to Earth-fixed frame.
Definition PosVelAtt.hpp:155
static std::vector< std::string > parentTypes()
Returns the parent types of the data class.
Definition PosVelAtt.hpp:36
Position, Velocity and Attitude Storage Class.
Definition PosVel.hpp:23
static std::vector< std::string > parentTypes()
Returns the parent types of the data class.
Definition PosVel.hpp:34
void setVelocityAndStdDev_e(const Eigen::Vector3d &e_velocity, const Eigen::Matrix3d &e_velocityCovarianceMatrix)
Set the Velocity in ECEF coordinates and its standard deviation.
Definition PosVel.hpp:233
const Eigen::Vector3d & n_velocity() const
Returns the velocity in [m/s], in navigation coordinates.
Definition PosVel.hpp:196
static std::vector< std::string > GetStaticDataDescriptors()
Returns a vector of data descriptors.
Definition PosVel.hpp:42
void setVelocity_e(const Eigen::Vector3d &e_velocity)
Set the Velocity in the earth frame.
Definition PosVel.hpp:216
static std::string type()
Returns the type of the data class.
Definition PosVel.hpp:27
void setVelocity_n(const Eigen::Vector3d &n_velocity)
Set the Velocity in the NED frame.
Definition PosVel.hpp:224
const Eigen::Vector3d & e_velocity() const
Returns the velocity in [m/s], in earth coordinates.
Definition PosVel.hpp:193
std::optional< double > getValueAt(size_t idx) const override
Get the value at the index.
Definition PosVel.hpp:80
void setVelocityAndStdDev_n(const Eigen::Vector3d &n_velocity, const Eigen::Matrix3d &n_velocityCovarianceMatrix)
Set the Velocity in NED coordinates and its standard deviation.
Definition PosVel.hpp:243
void setPositionAndStdDev_e(const Eigen::Vector3d &e_position, const Eigen::Matrix3d &e_positionCovarianceMatrix)
Set the Position in ECEF coordinates and its standard deviation.
Definition Pos.hpp:237
Eigen::Quaterniond e_Quat_n() const
Returns the Quaternion from navigation to Earth-fixed frame.
Definition Pos.hpp:153
void setPositionAndStdDev_lla(const Eigen::Vector3d &lla_position, const Eigen::Matrix3d &n_positionCovarianceMatrix)
Set the Position in LLA coordinates and its standard deviation.
Definition Pos.hpp:247
Eigen::Quaterniond n_Quat_e() const
Returns the Quaternion from Earth-fixed frame to navigation.
Definition Pos.hpp:160
const Eigen::Vector3d & e_position() const
Returns the coordinates in [m].
Definition Pos.hpp:200
const Eigen::Vector3d & lla_position() const
Returns the latitude 𝜙, longitude λ and altitude (height above ground) in [rad, rad,...
Definition Pos.hpp:188
void setPosition_e(const Eigen::Vector3d &e_position)
Set the Position in coordinates.
Definition Pos.hpp:220
void setPosition_lla(const Eigen::Vector3d &lla_position)
Set the Position lla object.
Definition Pos.hpp:228