Fixposition SDK 0.0.0-heads/main-0-g7b59b93
Collection of c++ libraries and apps for use with Fixposition products
Loading...
Searching...
No Matches
fpsdk::common::trafo Namespace Reference

Transformation utilities. More...

Classes

class  Transformer
 "Universal" coordinate transformer, backed by PROJ More...
 

Functions

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 RotEnuEcef (const Eigen::Vector3d &ecef)
 Calculate the rotation matrix from ECEF to ENU for a given reference position.
 
Eigen::Matrix3d RotNedEnu ()
 Returns rotation matrix between NED and ENU.
 
Eigen::Matrix3d RotNedEcef (const double lat, const double lon)
 Calculate the rotation matrix from ECEF to NED for a given reference latitude/longitude.
 
Eigen::Matrix3d RotNedEcef (const Eigen::Vector3d &ecef)
 Calculate the rotation matrix from ECEF to NED for a given reference origin.
 
Eigen::Vector3d TfEnuEcef (const Eigen::Vector3d &ecef, const Eigen::Vector3d &wgs84llh_ref)
 Transform ECEF coordinate to ENU with specified ENU-origin.
 
Eigen::Vector3d TfEcefEnu (const Eigen::Vector3d &enu, const Eigen::Vector3d &wgs84llh_ref)
 Transform ENU coordinate to ECEF with specified ENU-origin.
 
Eigen::Vector3d TfNedEcef (const Eigen::Vector3d &ecef, const Eigen::Vector3d &wgs84llh_ref)
 Convert ECEF coordinates to ENU with specified ENU origin.
 
Eigen::Vector3d TfEcefNed (const Eigen::Vector3d &ned, const Eigen::Vector3d &wgs84llh_ref)
 
Eigen::Vector3d TfEcefWgs84Llh (const Eigen::Vector3d &wgs84llh)
 Convert geodetic coordinates (latitude, longitude, height) to ECEF (x, y, z).
 
Eigen::Vector3d TfWgs84LlhEcef (const Eigen::Vector3d &ecef)
 Convert ECEF (x, y, z) coordinates to geodetic coordinates (latitude, longitude, height) (latitude, longitude, altitude).
 
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 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.
 
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.
 

Variables

WGS-84 constants
static constexpr double WGS84_A = 6378137.0
 WGS-84 Earth radius major axis [m].
 
static constexpr double WGS84_B = 6356752.314245
 WGS-84 Earth radius minor axis [m].
 
static constexpr double WGS84_1F = 298.257223563
 WGS-84 1/f inverse of flattening parameter.
 
static constexpr double WGS84_E2 = 6.69437999014e-3
 WGS-84 first eccentricity squared.
 
static constexpr double WGS84_A2 = WGS84_A * WGS84_A
 WGS-84 a_^2.
 
static constexpr double WGS84_B2 = WGS84_B * WGS84_B
 WGS-84 b_^2.
 
static constexpr double WGS84_EE2 = WGS84_A2 / WGS84_B2 - 1
 WGS-84 e'^2 second eccentricity squared.
 

Detailed Description

Transformation utilities.

Function Documentation

◆ RotEnuEcef() [1/2]

Eigen::Matrix3d fpsdk::common::trafo::RotEnuEcef ( const double lat,
const double lon )

Calculate the rotation matrix from ECEF to ENU for a given reference latitude/longitude.

Parameters
[in]latReference latitude [rad]
[in]lonReference longitude [rad]
Returns
the rotation matrix from ECEF to ENU

◆ RotEnuEcef() [2/2]

Eigen::Matrix3d fpsdk::common::trafo::RotEnuEcef ( const Eigen::Vector3d & ecef)

Calculate the rotation matrix from ECEF to ENU for a given reference position.

Parameters
[in]ecefReference position in ECEF [m]
Returns
the rotation matrix from ECEF to ENU

◆ RotNedEnu()

Eigen::Matrix3d fpsdk::common::trafo::RotNedEnu ( )

Returns rotation matrix between NED and ENU.

| 0, 1, 0 | | 1, 0, 0 | | 0, 0,-1 |

Returns
the rotation matrix between NED and ENU

◆ RotNedEcef() [1/2]

Eigen::Matrix3d fpsdk::common::trafo::RotNedEcef ( const double lat,
const double lon )

Calculate the rotation matrix from ECEF to NED for a given reference latitude/longitude.

Parameters
[in]latReference latitude [rad]
[in]lonReference longitude [rad]
Returns
the rotation matrix from ECEF to NED

◆ RotNedEcef() [2/2]

Eigen::Matrix3d fpsdk::common::trafo::RotNedEcef ( const Eigen::Vector3d & ecef)

Calculate the rotation matrix from ECEF to NED for a given reference origin.

Parameters
[in]ecefReference position in ECEF [m]
Returns
the rRotation matrix from ECEF to NED

◆ TfEnuEcef()

Eigen::Vector3d fpsdk::common::trafo::TfEnuEcef ( const Eigen::Vector3d & ecef,
const Eigen::Vector3d & wgs84llh_ref )

Transform ECEF coordinate to ENU with specified ENU-origin.

Parameters
[in]ecefECEF position to be transformed [m]
[in]wgs84llh_refENU-origin in geodetic coordinates (lat [rad], lon [rad], height [m])
Returns
the position in ENU coordinates

◆ TfEcefEnu()

Eigen::Vector3d fpsdk::common::trafo::TfEcefEnu ( const Eigen::Vector3d & enu,
const Eigen::Vector3d & wgs84llh_ref )

Transform ENU coordinate to ECEF with specified ENU-origin.

Parameters
[in]enuENU position to be transformed [m]
[in]wgs84llh_refENU-origin in geodetic coordinates (lat [rad], lon [rad], height [m])
Returns
Todo
documentation

◆ TfNedEcef()

Eigen::Vector3d fpsdk::common::trafo::TfNedEcef ( const Eigen::Vector3d & ecef,
const Eigen::Vector3d & wgs84llh_ref )

Convert ECEF coordinates to ENU with specified ENU origin.

Parameters
[in]ecefECEF position to be converted
[in]wgs84llh_refENU-origin input given in geodetic coordinates
Returns
the position in ENU coordinates

◆ TfEcefNed()

Eigen::Vector3d fpsdk::common::trafo::TfEcefNed ( const Eigen::Vector3d & ned,
const Eigen::Vector3d & wgs84llh_ref )
Todo
documentation

◆ TfEcefWgs84Llh()

Eigen::Vector3d fpsdk::common::trafo::TfEcefWgs84Llh ( const Eigen::Vector3d & wgs84llh)

Convert geodetic coordinates (latitude, longitude, height) to ECEF (x, y, z).

Parameters
[in]wgs84llhGeodetic coordinates (Lat[rad], Lon[rad], Height[m])
Returns
Eigen::Vector3d ECEF coordinates [m]

◆ TfWgs84LlhEcef()

Eigen::Vector3d fpsdk::common::trafo::TfWgs84LlhEcef ( const Eigen::Vector3d & ecef)

Convert ECEF (x, y, z) coordinates to geodetic coordinates (latitude, longitude, height) (latitude, longitude, altitude).

Parameters
[in]ecefECEF coordinates [m]
Returns
the geodetic coordinates (lat [rad], lon [rad], height [m])

◆ EcefPoseToEnuEul()

Eigen::Vector3d fpsdk::common::trafo::EcefPoseToEnuEul ( const Eigen::Vector3d & ecef_p,
const Eigen::Matrix3d & ecef_r )

Calculate yaw, pitch and roll in ENU from a given pose in ECEF.

Yaw will be -Pi/2 when X is pointing North, because ENU starts with East

Parameters
[in]ecef_p3D position vector in ECEF
[in]ecef_r3x3 rotation matrix representing rotation from body to ECEF
Returns
yaw, pitch and roll in ENU

◆ QuatToEul()

Eigen::Vector3d fpsdk::common::trafo::QuatToEul ( const Eigen::Quaterniond & quat)

Vector4 quaternion to intrinsic Euler Angles in ZYX (yaw,pitch,roll)

Parameters
[in]quatQuaternion (w, i, j, k)
Returns
the intrinsic Euler angles in ZYX (yaw, pitch, roll) order

◆ RotToEul()

Eigen::Vector3d fpsdk::common::trafo::RotToEul ( const Eigen::Matrix3d & rot)

Rotation Matrix to intrinsic Euler Angles in ZYX (Yaw-Pitch-Roll) order in radian.

Parameters
rotEigen::Matrix3d
Returns
Eigen::Vector3d intrinsic euler angle in ZYX (Yaw-Pitch-Roll) order in radian

◆ LlhDegToRad()

Eigen::Vector3d fpsdk::common::trafo::LlhDegToRad ( const Eigen::Vector3d & llh_deg)

Convert llh from deg to rad, height component unchanged.

Parameters
[in]llh_degllh in degrees
Returns
Eigen::Vector3d llh in radian

◆ LlhRadToDeg()

Eigen::Vector3d fpsdk::common::trafo::LlhRadToDeg ( const Eigen::Vector3d & llh_rad)

Convert llh from rad to deg, height component unchanged.

Parameters
[in]llh_radllh in radian
Returns
Eigen::Vector3d llh in degrees

Variable Documentation

◆ WGS84_A

double fpsdk::common::trafo::WGS84_A = 6378137.0
staticconstexpr

WGS-84 Earth radius major axis [m].

Definition at line 46 of file trafo.hpp.

◆ WGS84_B

double fpsdk::common::trafo::WGS84_B = 6356752.314245
staticconstexpr

WGS-84 Earth radius minor axis [m].

Definition at line 47 of file trafo.hpp.

◆ WGS84_1F

double fpsdk::common::trafo::WGS84_1F = 298.257223563
staticconstexpr

WGS-84 1/f inverse of flattening parameter.

Definition at line 48 of file trafo.hpp.

◆ WGS84_E2

double fpsdk::common::trafo::WGS84_E2 = 6.69437999014e-3
staticconstexpr

WGS-84 first eccentricity squared.

Definition at line 49 of file trafo.hpp.

◆ WGS84_A2

double fpsdk::common::trafo::WGS84_A2 = WGS84_A * WGS84_A
staticconstexpr

WGS-84 a_^2.

Definition at line 50 of file trafo.hpp.

◆ WGS84_B2

double fpsdk::common::trafo::WGS84_B2 = WGS84_B * WGS84_B
staticconstexpr

WGS-84 b_^2.

Definition at line 51 of file trafo.hpp.

◆ WGS84_EE2

double fpsdk::common::trafo::WGS84_EE2 = WGS84_A2 / WGS84_B2 - 1
staticconstexpr

WGS-84 e'^2 second eccentricity squared.

Definition at line 52 of file trafo.hpp.