0.3.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]] std::string getType() const override { return type(); }
37
40 [[nodiscard]] static std::vector<std::string> parentTypes()
41 {
42 auto parent = PosVel::parentTypes();
43 parent.push_back(PosVel::type());
44 return parent;
45 }
46
48 [[nodiscard]] static std::vector<std::string> GetStaticDataDescriptors()
49 {
51 desc.reserve(GetStaticDescriptorCount());
52 desc.emplace_back("Roll [deg]");
53 desc.emplace_back("Pitch [deg]");
54 desc.emplace_back("Yaw [deg]");
55 desc.emplace_back("Quaternion::w");
56 desc.emplace_back("Quaternion::x");
57 desc.emplace_back("Quaternion::y");
58 desc.emplace_back("Quaternion::z");
59 return desc;
60 }
61
63 [[nodiscard]] static constexpr size_t GetStaticDescriptorCount() { return PosVel::GetStaticDescriptorCount() + 7; }
64
66 [[nodiscard]] std::vector<std::string> staticDataDescriptors() const override { return GetStaticDataDescriptors(); }
67
69 [[nodiscard]] size_t staticDescriptorCount() const override { return GetStaticDescriptorCount(); }
70
74 [[nodiscard]] std::optional<double> getValueAt(size_t idx) const override
75 {
77 if (idx < PosVel::GetStaticDescriptorCount()) { return PosVel::getValueAt(idx); }
78 switch (idx)
79 {
80 case PosVel::GetStaticDescriptorCount() + 0: // Roll [deg]
81 if (_e_Quat_b.norm() != 0) { return rad2deg(rollPitchYaw().x()); }
82 break;
83 case PosVel::GetStaticDescriptorCount() + 1: // Pitch [deg]
84 if (_e_Quat_b.norm() != 0) { return rad2deg(rollPitchYaw().y()); }
85 break;
86 case PosVel::GetStaticDescriptorCount() + 2: // Yaw [deg]
87 if (_e_Quat_b.norm() != 0) { return rad2deg(rollPitchYaw().z()); }
88 break;
89 case PosVel::GetStaticDescriptorCount() + 3: // Quaternion::w
90 if (_e_Quat_b.norm() != 0) { return n_Quat_b().w(); }
91 break;
92 case PosVel::GetStaticDescriptorCount() + 4: // Quaternion::x
93 if (_e_Quat_b.norm() != 0) { return n_Quat_b().x(); }
94 break;
95 case PosVel::GetStaticDescriptorCount() + 5: // Quaternion::y
96 if (_e_Quat_b.norm() != 0) { return n_Quat_b().y(); }
97 break;
98 case PosVel::GetStaticDescriptorCount() + 6: // Quaternion::z
99 if (_e_Quat_b.norm() != 0) { return n_Quat_b().z(); }
100 break;
101 default:
102 return std::nullopt;
103 }
104 return std::nullopt;
105 }
106
111 [[nodiscard]] bool setValueAt(size_t idx, double value) override
112 {
114 if (idx < PosVel::GetStaticDescriptorCount()) { return PosVel::setValueAt(idx, value); }
115 // switch (idx)
116 // {
117 // case PosVel::GetStaticDescriptorCount() + 0: // Roll [deg]
118 // case PosVel::GetStaticDescriptorCount() + 1: // Pitch [deg]
119 // case PosVel::GetStaticDescriptorCount() + 2: // Yaw [deg]
120 // case PosVel::GetStaticDescriptorCount() + 3: // Quaternion::w
121 // case PosVel::GetStaticDescriptorCount() + 4: // Quaternion::x
122 // case PosVel::GetStaticDescriptorCount() + 5: // Quaternion::y
123 // case PosVel::GetStaticDescriptorCount() + 6: // Quaternion::z
124 // default:
125 // }
126
127 return false;
128 }
129
130 /* -------------------------------------------------------------------------------------------------------- */
131 /* Rotation Quaternions */
132 /* -------------------------------------------------------------------------------------------------------- */
133
136 [[nodiscard]] const Eigen::Quaterniond& n_Quat_b() const
137 {
138 return _n_Quat_b;
139 }
140
143 [[nodiscard]] Eigen::Quaterniond b_Quat_n() const
144 {
145 return n_Quat_b().conjugate();
146 }
147
150 [[nodiscard]] const Eigen::Quaterniond& e_Quat_b() const
151 {
152 return _e_Quat_b;
153 }
154
157 [[nodiscard]] Eigen::Quaterniond b_Quat_e() const
158 {
159 return e_Quat_b().conjugate();
160 }
161
164 [[nodiscard]] Eigen::Vector3d rollPitchYaw() const
165 {
166 return trafo::quat2eulerZYX(n_Quat_b());
167 }
168
169 // ###########################################################################################################
170 // Setter
171 // ###########################################################################################################
172
175 template<typename Derived>
176 void setAttitude_e_Quat_b(const Eigen::QuaternionBase<Derived>& e_Quat_b)
177 {
180 }
181
184 template<typename Derived>
185 void setAttitude_n_Quat_b(const Eigen::QuaternionBase<Derived>& n_Quat_b)
186 {
189 }
190
195 template<typename DerivedP, typename DerivedV, typename DerivedA>
196 void setState_e(const Eigen::MatrixBase<DerivedP>& e_position, const Eigen::MatrixBase<DerivedV>& e_velocity, const Eigen::QuaternionBase<DerivedA>& e_Quat_b)
197 {
201 }
202
207 template<typename DerivedP, typename DerivedV, typename DerivedA>
208 void setState_n(const Eigen::MatrixBase<DerivedP>& lla_position, const Eigen::MatrixBase<DerivedV>& n_velocity, const Eigen::QuaternionBase<DerivedA>& n_Quat_b)
209 {
213 }
214
221 template<typename DerivedP, typename DerivedP2, typename DerivedV, typename DerivedV2, typename DerivedA>
222 void setStateAndStdDev_e(const Eigen::MatrixBase<DerivedP>& e_position, const Eigen::MatrixBase<DerivedP2>& e_positionCovarianceMatrix,
223 const Eigen::MatrixBase<DerivedV>& e_velocity, const Eigen::MatrixBase<DerivedV2>& e_velocityCovarianceMatrix,
224 const Eigen::QuaternionBase<DerivedA>& e_Quat_b)
225 {
226 setPositionAndStdDev_e(e_position, e_positionCovarianceMatrix);
227 setVelocityAndStdDev_e(e_velocity, e_velocityCovarianceMatrix);
229 }
230
237 template<typename DerivedP, typename DerivedP2, typename DerivedV, typename DerivedV2, typename DerivedA>
238 void setStateAndStdDev_n(const Eigen::MatrixBase<DerivedP>& lla_position, const Eigen::MatrixBase<DerivedP2>& n_positionCovarianceMatrix,
239 const Eigen::MatrixBase<DerivedV>& n_velocity, const Eigen::MatrixBase<DerivedV2>& n_velocityCovarianceMatrix,
240 const Eigen::QuaternionBase<DerivedA>& n_Quat_b)
241 {
242 setPositionAndStdDev_lla(lla_position, n_positionCovarianceMatrix);
243 setVelocityAndStdDev_n(n_velocity, n_velocityCovarianceMatrix);
245 }
246
247 /* -------------------------------------------------------------------------------------------------------- */
248 /* Member variables */
249 /* -------------------------------------------------------------------------------------------------------- */
250
251 private:
253 Eigen::Quaterniond _e_Quat_b{ 0, 0, 0, 0 };
255 Eigen::Quaterniond _n_Quat_b{ 0, 0, 0, 0 };
256};
257
258} // 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:143
size_t staticDescriptorCount() const override
Get the amount of descriptors.
Definition PosVelAtt.hpp:69
void setStateAndStdDev_e(const Eigen::MatrixBase< DerivedP > &e_position, const Eigen::MatrixBase< DerivedP2 > &e_positionCovarianceMatrix, const Eigen::MatrixBase< DerivedV > &e_velocity, const Eigen::MatrixBase< DerivedV2 > &e_velocityCovarianceMatrix, const Eigen::QuaternionBase< DerivedA > &e_Quat_b)
Set the State and the standard deviations.
Definition PosVelAtt.hpp:222
std::vector< std::string > staticDataDescriptors() const override
Returns a vector of data descriptors.
Definition PosVelAtt.hpp:66
void setAttitude_e_Quat_b(const Eigen::QuaternionBase< Derived > &e_Quat_b)
Set the Quaternion from body to earth frame.
Definition PosVelAtt.hpp:176
void setState_n(const Eigen::MatrixBase< DerivedP > &lla_position, const Eigen::MatrixBase< DerivedV > &n_velocity, const Eigen::QuaternionBase< DerivedA > &n_Quat_b)
Set the State.
Definition PosVelAtt.hpp:208
static std::vector< std::string > GetStaticDataDescriptors()
Returns a vector of data descriptors.
Definition PosVelAtt.hpp:48
static constexpr size_t GetStaticDescriptorCount()
Get the amount of descriptors.
Definition PosVelAtt.hpp:63
std::optional< double > getValueAt(size_t idx) const override
Get the value at the index.
Definition PosVelAtt.hpp:74
Eigen::Quaterniond _n_Quat_b
Quaternion body to navigation frame (roll, pitch, yaw)
Definition PosVelAtt.hpp:255
void setAttitude_n_Quat_b(const Eigen::QuaternionBase< Derived > &n_Quat_b)
Set the Quaternion from body to navigation frame.
Definition PosVelAtt.hpp:185
const Eigen::Quaterniond & n_Quat_b() const
Returns the Quaternion from body to navigation frame (NED)
Definition PosVelAtt.hpp:136
bool setValueAt(size_t idx, double value) override
Set the value at the index.
Definition PosVelAtt.hpp:111
static std::string type()
Returns the type of the data class.
Definition PosVelAtt.hpp:29
void setState_e(const Eigen::MatrixBase< DerivedP > &e_position, const Eigen::MatrixBase< DerivedV > &e_velocity, const Eigen::QuaternionBase< DerivedA > &e_Quat_b)
Set the State.
Definition PosVelAtt.hpp:196
void setStateAndStdDev_n(const Eigen::MatrixBase< DerivedP > &lla_position, const Eigen::MatrixBase< DerivedP2 > &n_positionCovarianceMatrix, const Eigen::MatrixBase< DerivedV > &n_velocity, const Eigen::MatrixBase< DerivedV2 > &n_velocityCovarianceMatrix, const Eigen::QuaternionBase< DerivedA > &n_Quat_b)
Set the State and the standard deviations.
Definition PosVelAtt.hpp:238
Eigen::Quaterniond b_Quat_e() const
Returns the Quaternion from Earth-fixed to body frame.
Definition PosVelAtt.hpp:157
Eigen::Quaterniond _e_Quat_b
Quaternion body to earth frame.
Definition PosVelAtt.hpp:253
Eigen::Vector3d rollPitchYaw() const
Returns the Roll, Pitch and Yaw angles in [rad].
Definition PosVelAtt.hpp:164
std::string getType() const override
Returns the type of the data class.
Definition PosVelAtt.hpp:36
const Eigen::Quaterniond & e_Quat_b() const
Returns the Quaternion from body to Earth-fixed frame.
Definition PosVelAtt.hpp:150
static std::vector< std::string > parentTypes()
Returns the parent types of the data class.
Definition PosVelAtt.hpp:40
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
static std::vector< std::string > GetStaticDataDescriptors()
Returns a vector of data descriptors.
Definition PosVel.hpp:46
static std::string type()
Returns the type of the data class.
Definition PosVel.hpp:27
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
const Eigen::Vector3d & e_velocity() const
Returns the velocity in [m/s], in earth coordinates.
Definition PosVel.hpp:234
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
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 setPositionAndStdDev_e(const Eigen::MatrixBase< Derived > &e_position, const Eigen::MatrixBase< Derived2 > &e_positionCovarianceMatrix)
Set the Position in ECEF coordinates and its standard deviation.
Definition Pos.hpp:305
Eigen::Quaterniond e_Quat_n() const
Returns the Quaternion from navigation to Earth-fixed frame.
Definition Pos.hpp:218
Eigen::Quaterniond n_Quat_e() const
Returns the Quaternion from Earth-fixed frame to navigation.
Definition Pos.hpp:225
const Eigen::Vector3d & e_position() const
Returns the coordinates in [m].
Definition Pos.hpp:265
void setPositionAndStdDev_lla(const Eigen::MatrixBase< Derived > &lla_position, const Eigen::MatrixBase< Derived2 > &n_positionCovarianceMatrix)
Set the Position in LLA coordinates and its standard deviation.
Definition Pos.hpp:316
void setPosition_e(const Eigen::MatrixBase< Derived > &e_position)
Set the Position in coordinates.
Definition Pos.hpp:286
const Eigen::Vector3d & lla_position() const
Returns the latitude 𝜙, longitude λ and altitude (height above ground) in [rad, rad,...
Definition Pos.hpp:253
void setPosition_lla(const Eigen::MatrixBase< Derived > &lla_position)
Set the Position lla object.
Definition Pos.hpp:295