0.3.0
Loading...
Searching...
No Matches
CoordinateFrames.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
40
41#pragma once
42
43#include "util/Eigen.hpp"
44#include "util/Logger.hpp"
45
48#include "Navigation/Transformations/Units.hpp"
49
50namespace NAV::trafo
51{
52namespace internal
53{
60template<typename Derived>
61Eigen::Vector3<typename Derived::Scalar> lla2ecef(const Eigen::MatrixBase<Derived>& lla_position, double a, double e_squared)
62{
63 const auto& latitude = lla_position(0); // 𝜙 Geodetic latitude
64 const auto& longitude = lla_position(1); // λ Geodetic longitude
65 const auto& altitude = lla_position(2); // Altitude (Height above ground)
66
67 // Radius of curvature of the ellipsoid in the prime vertical plane,
68 // i.e., the plane containing the normal at P and perpendicular to the meridian (eq. 1.81)
69 auto R_E = calcEarthRadius_E(latitude, a, e_squared);
70
71 // Jekeli, 2001 (eq. 1.80) (see Torge, 1991, for further details)
72 return { (R_E + altitude) * std::cos(latitude) * std::cos(longitude),
73 (R_E + altitude) * std::cos(latitude) * std::sin(longitude),
74 (R_E * (1 - e_squared) + altitude) * std::sin(latitude) };
75}
76
84template<typename Derived>
85Eigen::Vector3<typename Derived::Scalar> ecef2lla(const Eigen::MatrixBase<Derived>& e_position,
86 double a, double b, double e_squared)
87{
88 if (e_position.isZero())
89 {
90 return {
91 typename Derived::Scalar(0.0),
92 typename Derived::Scalar(0.0),
93 typename Derived::Scalar(-a)
94 };
95 }
96
97 const auto& x = e_position(0);
98 const auto& y = e_position(1);
99 const auto& z = e_position(2);
100
101 // Calculate longitude
102
103 auto lon = atan2(y, x);
104
105 // Start computing intermediate variables needed to compute altitude
106
107 auto p = e_position.head(2).norm();
108 auto E = sqrt(a * a - b * b);
109 auto F = 54.0 * pow(b * z, 2.0);
110 auto G = p * p + (1.0 - e_squared) * z * z - e_squared * E * E;
111 auto c = e_squared * e_squared * F * p * p / pow(G, 3.0);
112 auto s = pow(1.0 + c + sqrt(c * c + 2.0 * c), 1.0 / 3.0);
113 auto P = (F / (3.0 * G * G)) / pow(s + (1.0 / s) + 1.0, 2.0);
114 auto Q = sqrt(1.0 + 2.0 * e_squared * e_squared * P);
115 auto k_1 = -P * e_squared * p / (1.0 + Q);
116 auto k_2 = 0.5 * a * a * (1.0 + 1.0 / Q);
117 auto k_3 = -P * (1.0 - e_squared) * z * z / (Q * (1.0 + Q));
118 auto k_4 = -0.5 * P * p * p;
119 auto r_0 = k_1 + sqrt(k_2 + k_3 + k_4);
120 auto k_5 = (p - e_squared * r_0);
121 auto U = sqrt(k_5 * k_5 + z * z);
122 auto V = sqrt(k_5 * k_5 + (1.0 - e_squared) * z * z);
123
124 auto alt = U * (1.0 - (b * b / (a * V)));
125
126 // Compute additional values required for computing latitude
127
128 auto z_0 = (b * b * z) / (a * V);
129 auto e_p = (a / b) * sqrt(e_squared);
130
131 auto lat = atan((z + z_0 * (e_p * e_p)) / p);
132
133 return { lat, lon, alt };
134}
135} // namespace internal
136
140template<typename Derived>
141[[nodiscard]] Eigen::Vector3<typename Derived::Scalar> quat2eulerZYX(const Eigen::QuaternionBase<Derived>& q)
142{
143 // Given range [-pi:pi] x [-pi:pi] x [0:pi]
144 Eigen::Vector3<typename Derived::Scalar> XYZ = q.toRotationMatrix().eulerAngles(2, 1, 0).reverse();
145
146 // Wanted range (-pi:pi] x (-pi/2:pi/2] x (-pi:pi]
147 if (XYZ.y() >= M_PI / 2.0 || XYZ.y() <= -M_PI / 2.0)
148 {
149 typename Derived::Scalar x = XYZ.x() > 0 ? XYZ.x() - M_PI : XYZ.x() + M_PI;
150 typename Derived::Scalar y = XYZ.y() >= M_PI / 2.0 ? -(XYZ.y() - M_PI) : -(XYZ.y() + M_PI);
151 typename Derived::Scalar z = XYZ.z() - M_PI;
152
153 XYZ = { x, y, z };
154 }
155
156 return XYZ;
157}
158
163template<typename Scalar>
164[[nodiscard]] Eigen::Quaternion<Scalar> e_Quat_i(Scalar time, Scalar omega_ie = InsConst::omega_ie)
165{
166 // Initialize angle-axis rotation from an angle in radian and an axis which must be normalized.
167 Eigen::AngleAxis<Scalar> zAngle(-omega_ie * time, Eigen::Vector3<Scalar>::UnitZ());
168
169 return Eigen::Quaternion<Scalar>(zAngle).normalized();
170}
171
176template<typename Scalar>
177[[nodiscard]] Eigen::Quaternion<Scalar> i_Quat_e(Scalar time, Scalar omega_ie = InsConst::omega_ie)
178{
179 return e_Quat_i(time, omega_ie).conjugate();
180}
181
186template<typename Scalar>
187[[nodiscard]] Eigen::Quaternion<Scalar> e_Quat_n(Scalar latitude, Scalar longitude)
188{
189 // Initialize angle-axis rotation from an angle in radian and an axis which must be normalized.
190 // Eigen uses here a different sign convention as the physical system.
191 Eigen::AngleAxis<Scalar> longitudeAngle(longitude, Eigen::Vector3<Scalar>::UnitZ());
192 Eigen::AngleAxis<Scalar> latitudeAngle(-M_PI_2 - latitude, Eigen::Vector3<Scalar>::UnitY());
193
194 return (longitudeAngle * latitudeAngle).normalized();
195}
196
201template<typename Scalar>
202[[nodiscard]] Eigen::Quaternion<Scalar> n_Quat_e(Scalar latitude, Scalar longitude)
203{
204 return e_Quat_n(latitude, longitude).conjugate();
205}
206
212template<typename Scalar>
213[[nodiscard]] Eigen::Quaternion<Scalar> b_Quat_n(Scalar roll, Scalar pitch, Scalar yaw)
214{
215 // Initialize angle-axis rotation from an angle in radian and an axis which must be normalized.
216 // Eigen uses here a different sign convention as the physical system.
217 Eigen::AngleAxis<Scalar> rollAngle(-roll, Eigen::Vector3<Scalar>::UnitX());
218 Eigen::AngleAxis<Scalar> pitchAngle(-pitch, Eigen::Vector3<Scalar>::UnitY());
219 Eigen::AngleAxis<Scalar> yawAngle(-yaw, Eigen::Vector3<Scalar>::UnitZ());
220
221 return (rollAngle * pitchAngle * yawAngle).normalized();
222}
223
227template<typename Derived>
228[[nodiscard]] Eigen::Quaternion<typename Derived::Scalar> b_Quat_n(const Eigen::MatrixBase<Derived>& rollPitchYaw)
229{
230 return b_Quat_n(rollPitchYaw(0), rollPitchYaw(1), rollPitchYaw(2));
231}
232
238template<typename Scalar>
239[[nodiscard]] Eigen::Quaternion<Scalar> n_Quat_b(Scalar roll, Scalar pitch, Scalar yaw)
240{
241 return b_Quat_n(roll, pitch, yaw).conjugate();
242}
243
247template<typename Derived>
248[[nodiscard]] Eigen::Quaternion<typename Derived::Scalar> n_Quat_b(const Eigen::MatrixBase<Derived>& rollPitchYaw)
249{
250 return n_Quat_b(rollPitchYaw(0), rollPitchYaw(1), rollPitchYaw(2));
251}
252
258template<typename Scalar>
259[[nodiscard]] Eigen::Quaternion<Scalar> b_Quat_p(Scalar mountingAngleX, Scalar mountingAngleY, Scalar mountingAngleZ)
260{
261 // Initialize angle-axis rotation from an angle in radian and an axis which must be normalized.
262 Eigen::AngleAxis<Scalar> xAngle(-mountingAngleX, Eigen::Vector3<Scalar>::UnitX());
263 Eigen::AngleAxis<Scalar> yAngle(-mountingAngleY, Eigen::Vector3<Scalar>::UnitY());
264 Eigen::AngleAxis<Scalar> zAngle(-mountingAngleZ, Eigen::Vector3<Scalar>::UnitZ());
265
266 return (xAngle * yAngle * zAngle).normalized();
267}
268
274template<typename Scalar>
275[[nodiscard]] Eigen::Quaternion<Scalar> p_Quat_b(Scalar mountingAngleX, Scalar mountingAngleY, Scalar mountingAngleZ)
276{
277 return b_Quat_p(mountingAngleX, mountingAngleY, mountingAngleZ).conjugate();
278}
279
283template<typename Derived>
284[[nodiscard]] Eigen::Vector3<typename Derived::Scalar> lla2ecef_WGS84(const Eigen::MatrixBase<Derived>& lla_position)
285{
286 return internal::lla2ecef(lla_position, InsConst::WGS84::a, InsConst::WGS84::e_squared);
287}
288
292template<typename Derived>
293[[nodiscard]] Eigen::Vector3<typename Derived::Scalar> lla2ecef_GRS80(const Eigen::MatrixBase<Derived>& lla_position)
294{
295 return internal::lla2ecef(lla_position, InsConst::GRS80::a, InsConst::GRS80::e_squared);
296}
297
301template<typename Derived>
302[[nodiscard]] Eigen::Vector3<typename Derived::Scalar> ecef2lla_WGS84(const Eigen::MatrixBase<Derived>& e_position)
303{
304 return internal::ecef2lla(e_position,
308}
309
313template<typename Derived>
314[[nodiscard]] Eigen::Vector3<typename Derived::Scalar> ecef2lla_GRS80(const Eigen::MatrixBase<Derived>& e_position)
315{
316 return internal::ecef2lla(e_position,
320}
321
328template<typename DerivedA, typename DerivedB>
329[[nodiscard]] Eigen::Vector3<typename DerivedA::Scalar> ecef2ned(const Eigen::MatrixBase<DerivedA>& e_position, const Eigen::MatrixBase<DerivedB>& lla_position_ref)
330{
331 const auto& latitude_ref = lla_position_ref(0); // 𝜙 Geodetic latitude
332 const auto& longitude_ref = lla_position_ref(1); // λ Geodetic longitude
333
334 auto e_position_ref = lla2ecef_WGS84(lla_position_ref);
335
336 Eigen::Matrix3<typename DerivedA::Scalar> R_ne;
337 // clang-format off
338 R_ne << -std::sin(latitude_ref) * std::cos(longitude_ref), -std::sin(latitude_ref) * std::sin(longitude_ref), std::cos(latitude_ref),
339 -std::sin(longitude_ref) , std::cos(longitude_ref) , 0 ,
340 -std::cos(latitude_ref) * std::cos(longitude_ref), -std::cos(latitude_ref) * std::sin(longitude_ref), -std::sin(latitude_ref);
341 // clang-format on
342
343 return R_ne * (e_position - e_position_ref);
344}
345
352template<typename DerivedA, typename DerivedB>
353[[nodiscard]] Eigen::Vector3<typename DerivedA::Scalar> ned2ecef(const Eigen::MatrixBase<DerivedA>& n_position, const Eigen::MatrixBase<DerivedB>& lla_position_ref)
354{
355 const auto& latitude_ref = lla_position_ref(0); // 𝜙 Geodetic latitude
356 const auto& longitude_ref = lla_position_ref(1); // λ Geodetic longitude
357
358 auto e_position_ref = lla2ecef_WGS84(lla_position_ref);
359
360 Eigen::Matrix3<typename DerivedA::Scalar> R_en;
361 // clang-format off
362 R_en << -std::sin(latitude_ref) * std::cos(longitude_ref), -std::sin(longitude_ref), -std::cos(latitude_ref) * std::cos(longitude_ref),
363 -std::sin(latitude_ref) * std::sin(longitude_ref), std::cos(longitude_ref), -std::cos(latitude_ref) * std::sin(longitude_ref),
364 std::cos(latitude_ref) , 0 , -std::sin(latitude_ref) ;
365 // clang-format on
366
367 return e_position_ref + R_en * n_position;
368}
369
374template<typename Derived>
375[[nodiscard]] Eigen::Vector3<typename Derived::Scalar> pz90toWGS84_pos(const Eigen::MatrixBase<Derived>& pz90_pos)
376{
377 typename Derived::Scalar m = -0.008e-6;
378 auto omega_x = static_cast<typename Derived::Scalar>(-2.3_mas);
379 auto omega_y = static_cast<typename Derived::Scalar>(3.54_mas);
380 auto omega_z = static_cast<typename Derived::Scalar>(-4.21_mas);
381 Eigen::Vector3<typename Derived::Scalar> dX{ -0.013, 0.106, 0.022 };
382
383 Eigen::Matrix3<typename Derived::Scalar> T;
384 T << 1, -omega_z, omega_y,
385 omega_z, 1, -omega_x,
386 -omega_y, omega_x, 1;
387
388 return 1.0 / (1.0 + m) * T * (pz90_pos - dX);
389}
390
395template<typename DerivedA, typename DerivedB>
396[[nodiscard]] Eigen::Vector3<typename DerivedA::Scalar> pz90toWGS84(const Eigen::MatrixBase<DerivedA>& pz90, const Eigen::MatrixBase<DerivedB>& pz90_pos)
397{
398 return pz90toWGS84_pos(pz90_pos + pz90) - pz90toWGS84_pos(pz90_pos);
399}
400
406template<typename Derived>
407[[nodiscard]] Eigen::Vector3<typename Derived::Scalar> sph2ecef(const Eigen::MatrixBase<Derived>& position_s,
408 const typename Derived::Scalar& elevation,
409 const typename Derived::Scalar& azimuth)
410{
411 Eigen::Matrix3<typename Derived::Scalar> R_se;
412 R_se << std::sin(elevation) * std::cos(azimuth), std::cos(elevation) * std::cos(azimuth), -std::sin(azimuth),
413 std::sin(elevation) * std::sin(azimuth), std::cos(elevation) * std::sin(azimuth), std::cos(azimuth),
414 std::cos(elevation), -std::sin(elevation), 0.0;
415
416 return R_se * position_s;
417}
418
419} // namespace NAV::trafo
Holds all Constants.
Eigen::Vector3< typename Derived::Scalar > ecef2lla(const Eigen::MatrixBase< Derived > &e_position, double a, double b, double e_squared)
Converts Earth-centered-Earth-fixed coordinates into latitude, longitude and altitude.
Definition CoordinateFrames.hpp:85
Eigen::Vector3< typename Derived::Scalar > ecef2lla_WGS84(const Eigen::MatrixBase< Derived > &e_position)
Converts Earth-centered-Earth-fixed coordinates into latitude, longitude and altitude using WGS84.
Definition CoordinateFrames.hpp:302
Eigen::Quaternion< Scalar > i_Quat_e(Scalar time, Scalar omega_ie=InsConst::omega_ie)
Quaternion for rotations from Earth-centered-Earth-fixed to inertial frame.
Definition CoordinateFrames.hpp:177
Eigen::Vector3< typename DerivedA::Scalar > ecef2ned(const Eigen::MatrixBase< DerivedA > &e_position, const Eigen::MatrixBase< DerivedB > &lla_position_ref)
Converts ECEF coordinates into local NED coordinates.
Definition CoordinateFrames.hpp:329
Eigen::Quaternion< Scalar > e_Quat_i(Scalar time, Scalar omega_ie=InsConst::omega_ie)
Quaternion for rotations from inertial to Earth-centered-Earth-fixed frame.
Definition CoordinateFrames.hpp:164
Eigen::Vector3< typename Derived::Scalar > pz90toWGS84_pos(const Eigen::MatrixBase< Derived > &pz90_pos)
Converts PZ-90.11 coordinates to WGS84 coordinates.
Definition CoordinateFrames.hpp:375
Eigen::Quaternion< Scalar > b_Quat_n(Scalar roll, Scalar pitch, Scalar yaw)
Quaternion for rotations from navigation to body frame.
Definition CoordinateFrames.hpp:213
Eigen::Vector3< typename Derived::Scalar > lla2ecef(const Eigen::MatrixBase< Derived > &lla_position, double a, double e_squared)
Converts latitude, longitude and altitude into Earth-centered-Earth-fixed coordinates.
Definition CoordinateFrames.hpp:61
Eigen::Quaternion< Scalar > b_Quat_p(Scalar mountingAngleX, Scalar mountingAngleY, Scalar mountingAngleZ)
Quaternion for rotations from platform to body frame.
Definition CoordinateFrames.hpp:259
Eigen::Quaternion< Scalar > e_Quat_n(Scalar latitude, Scalar longitude)
Quaternion for rotations from navigation to Earth-fixed frame.
Definition CoordinateFrames.hpp:187
Eigen::Vector3< typename DerivedA::Scalar > pz90toWGS84(const Eigen::MatrixBase< DerivedA > &pz90, const Eigen::MatrixBase< DerivedB > &pz90_pos)
Converts PZ-90.11 vectors to WGS84 frame.
Definition CoordinateFrames.hpp:396
Eigen::Vector3< typename Derived::Scalar > sph2ecef(const Eigen::MatrixBase< Derived > &position_s, const typename Derived::Scalar &elevation, const typename Derived::Scalar &azimuth)
Converts spherical Earth-centered-Earth-fixed coordinates into cartesian coordinates.
Definition CoordinateFrames.hpp:407
Eigen::Quaternion< Scalar > p_Quat_b(Scalar mountingAngleX, Scalar mountingAngleY, Scalar mountingAngleZ)
Quaternion for rotations from body to platform frame.
Definition CoordinateFrames.hpp:275
Eigen::Quaternion< Scalar > n_Quat_e(Scalar latitude, Scalar longitude)
Quaternion for rotations from Earth-fixed to navigation frame.
Definition CoordinateFrames.hpp:202
Eigen::Vector3< typename Derived::Scalar > quat2eulerZYX(const Eigen::QuaternionBase< Derived > &q)
Converts the quaternion to Euler rotation angles with rotation sequence ZYX.
Definition CoordinateFrames.hpp:141
Eigen::Vector3< typename Derived::Scalar > lla2ecef_GRS80(const Eigen::MatrixBase< Derived > &lla_position)
Converts latitude, longitude and altitude into Earth-centered-Earth-fixed coordinates using GRS90.
Definition CoordinateFrames.hpp:293
Eigen::Vector3< typename DerivedA::Scalar > ned2ecef(const Eigen::MatrixBase< DerivedA > &n_position, const Eigen::MatrixBase< DerivedB > &lla_position_ref)
Converts local NED coordinates into ECEF coordinates.
Definition CoordinateFrames.hpp:353
Eigen::Vector3< typename Derived::Scalar > lla2ecef_WGS84(const Eigen::MatrixBase< Derived > &lla_position)
Converts latitude, longitude and altitude into Earth-centered-Earth-fixed coordinates using WGS84.
Definition CoordinateFrames.hpp:284
Eigen::Vector3< typename Derived::Scalar > ecef2lla_GRS80(const Eigen::MatrixBase< Derived > &e_position)
Converts Earth-centered-Earth-fixed coordinates into latitude, longitude and altitude using GRS90.
Definition CoordinateFrames.hpp:314
Eigen::Quaternion< Scalar > n_Quat_b(Scalar roll, Scalar pitch, Scalar yaw)
Quaternion for rotations from body to navigation frame.
Definition CoordinateFrames.hpp:239
Vector space operations.
Functions concerning the ellipsoid model.
Scalar calcEarthRadius_E(const Scalar &latitude, const Scalar &a=InsConst::WGS84::a, const Scalar &e_squared=InsConst::WGS84::e_squared)
Calculates the East/West (prime vertical) earth radius.
Definition Ellipsoid.hpp:58
Utility class for logging to console and file.
static constexpr double a
Semi-major axis = equatorial radius.
Definition Constants.hpp:73
static constexpr double b
Semi-minor axis = polar radius.
Definition Constants.hpp:77
static constexpr double e_squared
Square of the first eccentricity of the ellipsoid.
Definition Constants.hpp:79
static constexpr double b
Semi-minor axis = polar radius.
Definition Constants.hpp:54
static constexpr double a
Semi-major axis = equatorial radius.
Definition Constants.hpp:50
static constexpr double e_squared
Square of the first eccentricity of the ellipsoid.
Definition Constants.hpp:56
static constexpr double omega_ie
Nominal mean angular velocity of the Earth in [rad/s].
Definition Constants.hpp:217