Fixposition SDK 0.0.0-heads/main-0-g90a51ff
Collection of c++ libraries and apps for use with Fixposition products
Loading...
Searching...
No Matches
trafo.hpp
Go to the documentation of this file.
1/**
2 * \verbatim
3 * ___ ___
4 * \ \ / /
5 * \ \/ / Copyright (c) Fixposition AG (www.fixposition.com) and contributors
6 * / /\ \ License: see the LICENSE file
7 * /__/ \__\
8 * \endverbatim
9 *
10 * @file
11 * @brief Fixposition SDK: Transformation utilities
12 *
13 * @page FPSDK_COMMON_TRAFO Transformation utilities
14 *
15 * **API**: fpsdk_common/trafo.hpp and fpsdk::common::trafo
16 *
17 */
18#ifndef __FPSDK_COMMON_TRAFO_HPP__
19#define __FPSDK_COMMON_TRAFO_HPP__
20
21/* LIBC/STL */
22#include <memory>
23#include <string>
24
25/* EXTERNAL */
26#include "fpsdk_common/ext/eigen_core.hpp"
27#include "fpsdk_common/ext/eigen_geometry.hpp"
28
29/* PACKAGE */
30
31namespace fpsdk {
32namespace common {
33/**
34 * @brief Transformation utilities
35 */
36namespace trafo {
37/* ****************************************************************************************************************** */
38
39/**
40 * @name WGS-84 constants
41 *
42 * https://en.wikipedia.org/wiki/World_Geodetic_System#Defining_Parameters
43 *
44 * @{
45 */
46static constexpr double WGS84_A = 6378137.0; //!< WGS-84 Earth radius major axis [m]
47static constexpr double WGS84_B = 6356752.314245; //!< WGS-84 Earth radius minor axis [m]
48static constexpr double WGS84_1F = 298.257223563; //!< WGS-84 1/f inverse of flattening parameter
49static constexpr double WGS84_E2 = 6.69437999014e-3; //!< WGS-84 first eccentricity squared
50static constexpr double WGS84_A2 = WGS84_A * WGS84_A; //!< WGS-84 a^2
51static constexpr double WGS84_B2 = WGS84_B * WGS84_B; //!< WGS-84 b^2
52static constexpr double WGS84_EE2 = WGS84_A2 / WGS84_B2 - 1; //!< WGS-84 e'^2 second eccentricity squared
53///@}
54
55/**
56 * @brief Calculate the rotation matrix from ECEF to ENU for a given reference latitude/longitude
57 *
58 * @param[in] lat Reference latitude [rad]
59 * @param[in] lon Reference longitude [rad]
60 *
61 * @returns the rotation matrix from ECEF to ENU
62 *
63 * Reference https://gssc.esa.int/navipedia/index.php/Transformations_between_ECEF_and_ENU_coordinates
64 */
65Eigen::Matrix3d RotEnuEcef(const double lat, const double lon);
66
67/**
68 * @brief Calculate the rotation matrix from ECEF to ENU for a given reference position
69 *
70 * @note The reference position is projected to the WGS84 ellipsoid
71 *
72 * @param[in] ecef Reference position in ECEF [m]
73 *
74 * @returns the rotation matrix from ECEF to ENU
75 */
76Eigen::Matrix3d RotEnuEcef(const Eigen::Vector3d& ecef);
77
78/**
79 * @brief Returns rotation matrix between NED and ENU
80 *
81 * | 0, 1, 0 |
82 * | 1, 0, 0 |
83 * | 0, 0, -1 |
84 *
85 * @returns the rotation matrix between NED and ENU
86 */
87Eigen::Matrix3d RotNedEnu();
88
89/**
90 * @brief Calculate the rotation matrix from ECEF to NED for a given reference latitude/longitude
91 *
92 * @param[in] lat Reference latitude [rad]
93 * @param[in] lon Reference longitude [rad]
94 *
95 * @returns the rotation matrix from ECEF to NED
96 */
97Eigen::Matrix3d RotNedEcef(const double lat, const double lon);
98
99/**
100 * @brief Calculate the rotation matrix from ECEF to NED for a given reference origin
101 *
102 * @note The reference position is projected to the WGS84 ellipsoid
103 *
104 * @param[in] ecef Reference position in ECEF [m]
105 *
106 * @returns the rRotation matrix from ECEF to NED
107 */
108Eigen::Matrix3d RotNedEcef(const Eigen::Vector3d& ecef);
109
110/**
111 * @brief Transform ECEF coordinate to ENU with specified ENU-origin
112 *
113 * @param[in] ecef ECEF position to be transformed [m]
114 * @param[in] wgs84llh_ref ENU-origin in geodetic coordinates (lat [rad], lon [rad], height [m])
115 *
116 * @returns the position in ENU coordinates
117 */
118Eigen::Vector3d TfEnuEcef(const Eigen::Vector3d& ecef, const Eigen::Vector3d& wgs84llh_ref);
119
120/**
121 * @brief Transform ENU coordinate to ECEF with specified ENU-origin
122 *
123 * @param[in] enu ENU position to be transformed [m]
124 * @param[in] wgs84llh_ref ENU-origin in geodetic coordinates (lat [rad], lon [rad], height [m])
125 *
126 * @returns @todo documentation
127 */
128Eigen::Vector3d TfEcefEnu(const Eigen::Vector3d& enu, const Eigen::Vector3d& wgs84llh_ref);
129
130/**
131 * @brief Convert ECEF coordinates to ENU with specified ENU origin
132 *
133 * @param[in] ecef ECEF position to be converted
134 * @param[in] wgs84llh_ref ENU-origin input given in geodetic coordinates
135 *
136 * @returns the position in ENU coordinates
137 */
138Eigen::Vector3d TfNedEcef(const Eigen::Vector3d& ecef, const Eigen::Vector3d& wgs84llh_ref);
139
140/**
141 * @todo documentation
142 */
143Eigen::Vector3d TfEcefNed(const Eigen::Vector3d& ned, const Eigen::Vector3d& wgs84llh_ref);
144
145/**
146 * @brief Convert geodetic coordinates (latitude, longitude, height) to ECEF (x, y, z).
147 *
148 * @param[in] wgs84llh Geodetic coordinates (Lat[rad], Lon[rad], Height[m])
149 *
150 * @returns the ECEF coordinates [m]
151 */
152Eigen::Vector3d TfEcefWgs84Llh(const Eigen::Vector3d& wgs84llh);
153
154/**
155 * @brief Convert ECEF (x, y, z) coordinates to geodetic coordinates (latitude, longitude, height)
156 *
157 * @param[in] ecef ECEF coordinates [m]
158 *
159 * @returns the geodetic coordinates (lat [rad], lon [rad], height [m])
160 */
161Eigen::Vector3d TfWgs84LlhEcef(const Eigen::Vector3d& ecef);
162
163/**
164 * @brief Calculate yaw, pitch and roll in ENU from a given pose in ECEF
165 *
166 * Yaw is -Pi/2 when X points North, because ENU starts with East
167 *
168 * @param[in] ecef_p 3D position vector in ECEF
169 * @param[in] ecef_r 3x3 rotation matrix representing rotation from body to ECEF
170 *
171 * @returns yaw, pitch and roll in ENU
172 */
173Eigen::Vector3d EcefPoseToEnuEul(const Eigen::Vector3d& ecef_p, const Eigen::Matrix3d& ecef_r);
174
175/**
176 * @brief Vector4 quaternion to intrinsic Euler angles in ZYX (yaw, pitch, roll)
177 *
178 * @param[in] quat Quaternion (w, i, j, k)
179 *
180 * @returns the intrinsic Euler angles in ZYX (yaw, pitch, roll) order
181 */
182Eigen::Vector3d QuatToEul(const Eigen::Quaterniond& quat);
183
184/**
185 * @brief Rotation Matrix to intrinsic Euler angles in ZYX (yaw, pitch, roll) order in radian
186 *
187 * @param[in] rot Eigen::Matrix3d
188 *
189 * @returns intrinsic euler angle in ZYX (Yaw-Pitch-Roll) order in radian
190 */
191Eigen::Vector3d RotToEul(const Eigen::Matrix3d& rot);
192
193/**
194 * @brief Convert llh from deg to rad, height component unchanged
195 *
196 * @param[in] llh_deg llh in degrees
197 *
198 * @returns llh in radian
199 */
200Eigen::Vector3d LlhDegToRad(const Eigen::Vector3d& llh_deg);
201
202/**
203 * @brief Convert llh from rad to deg, height component unchanged
204 *
205 * @param[in] llh_rad llh in radian
206 *
207 * @returns llh in degrees
208 */
209Eigen::Vector3d LlhRadToDeg(const Eigen::Vector3d& llh_rad);
210
211#if FP_USE_PROJ
212/**
213 * @brief "Universal" coordinate transformer, backed by PROJ
214 */
216{
217 public:
218 /**
219 * @brief Constructor
220 *
221 * @param[in] name Optional name, for debugging
222 */
223 Transformer(const std::string& name = "");
224
225 ~Transformer();
226
227 /**
228 * @brief Initialise transformer
229 *
230 * The source and target CRS specification can be anything that proj_create_crs_to_crs() understands (see
231 * https://proj.org/en/9.4/development/reference/functions.html#c.proj_create_crs_to_crs). You may have to change
232 * the PROJ configuration (proj.ini) and/or update some PROJ data yourself to support some CRS. See the PROJ
233 * documentation for details (see https://proj.org/en/9.4/resource_files.html).
234 *
235 * @param[in] source_crs Source coordinate reference system, e.g. "EPSG:4326"
236 * @param[in] target_crs Target coordinate reference system, e.g. "EPSG:2056"
237 *
238 * @returns true on success, false otherwise (bad params, missing data, ...)
239 */
240 bool Init(const std::string& source_crs, const std::string& target_crs);
241
242 /**
243 * @brief Transform coordinates
244 *
245 * @param[in,out] inout Coordinates to transform, replaced with result
246 * @param[in] inv Do the inverse transformation (true), default is forward (false)
247 *
248 * @returns true on success, false otherwise
249 */
250 bool Transform(Eigen::Vector3d& inout, const bool inv = false);
251
252 /**
253 * @brief Transform coordinates
254 *
255 * @param[in] in Coordinates to transform
256 * @param[out] out Transformed coordinates
257 * @param[in] inv Do the inverse transformation (true), default is forward (false)
258 *
259 * @returns true on success, false otherwise
260 */
261 bool Transform(const Eigen::Vector3d& in, Eigen::Vector3d& out, const bool inv = false);
262
263 /**
264 * @brief Transform coordinates (with time)
265 *
266 * @param[in] in Coordinates to transform (with time)
267 * @param[out] out Transformed coordinates (with time)
268 * @param[in] inv Do the inverse transformation (true), default is forward (false)
269 *
270 * @returns true on success, false otherwise
271 */
272 bool Transform(const Eigen::Vector4d& in, Eigen::Vector4d& out, const bool inv = false);
273
274 // No copy, no move
275 Transformer& operator=(const Transformer&) = delete;
276 Transformer(const Transformer&) = delete;
277 Transformer(Transformer&&) = delete;
278 Transformer& operator=(Transformer&&) = delete;
279
280 private:
281 const std::string name_; //!< Name, for debugging
282 bool pj_init_; //!< Proj is initialised
283 void* pj_ctx_; //!< Proj context
284 void* pj_tf_; //!< Proj transformation object
285};
286#endif // FP_USE_PROJ
287
288/* ****************************************************************************************************************** */
289} // namespace trafo
290} // namespace common
291} // namespace fpsdk
292#endif // __FPSDK_COMMON_TRAFO_HPP__
"Universal" coordinate transformer, backed by PROJ
Definition trafo.hpp:216
Transformer(const std::string &name="")
Constructor.
bool Transform(Eigen::Vector3d &inout, const bool inv=false)
Transform coordinates.
bool Transform(const Eigen::Vector3d &in, Eigen::Vector3d &out, const bool inv=false)
Transform coordinates.
bool Transform(const Eigen::Vector4d &in, Eigen::Vector4d &out, const bool inv=false)
Transform coordinates (with time)
bool Init(const std::string &source_crs, const std::string &target_crs)
Initialise transformer.
Eigen::Matrix3d RotEnuEcef(const double lat, const double lon)
Calculate the rotation matrix from ECEF to ENU for a given reference latitude/longitude.
Eigen::Matrix3d RotNedEcef(const double lat, const double lon)
Calculate the rotation matrix from ECEF to NED for a given reference latitude/longitude.
Eigen::Vector3d LlhDegToRad(const Eigen::Vector3d &llh_deg)
Convert llh from deg to rad, height component unchanged.
Eigen::Vector3d LlhRadToDeg(const Eigen::Vector3d &llh_rad)
Convert llh from rad to deg, height component unchanged.
static constexpr double WGS84_1F
WGS-84 1/f inverse of flattening parameter.
Definition trafo.hpp:48
Eigen::Vector3d TfEcefNed(const Eigen::Vector3d &ned, const Eigen::Vector3d &wgs84llh_ref)
static constexpr double WGS84_B2
WGS-84 b^2.
Definition trafo.hpp:51
Eigen::Vector3d TfNedEcef(const Eigen::Vector3d &ecef, const Eigen::Vector3d &wgs84llh_ref)
Convert ECEF coordinates to ENU with specified ENU origin.
static constexpr double WGS84_E2
WGS-84 first eccentricity squared.
Definition trafo.hpp:49
Eigen::Vector3d QuatToEul(const Eigen::Quaterniond &quat)
Vector4 quaternion to intrinsic Euler angles in ZYX (yaw, pitch, roll)
Eigen::Vector3d RotToEul(const Eigen::Matrix3d &rot)
Rotation Matrix to intrinsic Euler angles in ZYX (yaw, pitch, roll) order in radian.
static constexpr double WGS84_B
WGS-84 Earth radius minor axis [m].
Definition trafo.hpp:47
Eigen::Matrix3d RotNedEnu()
Returns rotation matrix between NED and ENU.
Eigen::Vector3d TfWgs84LlhEcef(const Eigen::Vector3d &ecef)
Convert ECEF (x, y, z) coordinates to geodetic coordinates (latitude, longitude, height)
Eigen::Vector3d TfEcefEnu(const Eigen::Vector3d &enu, const Eigen::Vector3d &wgs84llh_ref)
Transform ENU coordinate to ECEF with specified ENU-origin.
static constexpr double WGS84_A
WGS-84 Earth radius major axis [m].
Definition trafo.hpp:46
Eigen::Vector3d EcefPoseToEnuEul(const Eigen::Vector3d &ecef_p, const Eigen::Matrix3d &ecef_r)
Calculate yaw, pitch and roll in ENU from a given pose in ECEF.
Eigen::Vector3d TfEnuEcef(const Eigen::Vector3d &ecef, const Eigen::Vector3d &wgs84llh_ref)
Transform ECEF coordinate to ENU with specified ENU-origin.
Eigen::Vector3d TfEcefWgs84Llh(const Eigen::Vector3d &wgs84llh)
Convert geodetic coordinates (latitude, longitude, height) to ECEF (x, y, z).
static constexpr double WGS84_A2
WGS-84 a^2.
Definition trafo.hpp:50
static constexpr double WGS84_EE2
WGS-84 e'^2 second eccentricity squared.
Definition trafo.hpp:52
Fixposition SDK.