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