Fixposition SDK 0.0.0-heads/main-0-g7b59b93
Collection of c++ libraries and apps for use with Fixposition products
|
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. | |
Transformation utilities.
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.
[in] | lat | Reference latitude [rad] |
[in] | lon | Reference longitude [rad] |
Eigen::Matrix3d fpsdk::common::trafo::RotEnuEcef | ( | const Eigen::Vector3d & | ecef | ) |
Calculate the rotation matrix from ECEF to ENU for a given reference position.
[in] | ecef | Reference position in ECEF [m] |
Eigen::Matrix3d fpsdk::common::trafo::RotNedEnu | ( | ) |
Returns rotation matrix between NED and ENU.
| 0, 1, 0 | | 1, 0, 0 | | 0, 0,-1 |
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.
[in] | lat | Reference latitude [rad] |
[in] | lon | Reference longitude [rad] |
Eigen::Matrix3d fpsdk::common::trafo::RotNedEcef | ( | const Eigen::Vector3d & | ecef | ) |
Calculate the rotation matrix from ECEF to NED for a given reference origin.
[in] | ecef | Reference position in ECEF [m] |
Eigen::Vector3d fpsdk::common::trafo::TfEnuEcef | ( | const Eigen::Vector3d & | ecef, |
const Eigen::Vector3d & | wgs84llh_ref ) |
Transform ECEF coordinate to ENU with specified ENU-origin.
[in] | ecef | ECEF position to be transformed [m] |
[in] | wgs84llh_ref | ENU-origin in geodetic coordinates (lat [rad], lon [rad], height [m]) |
Eigen::Vector3d fpsdk::common::trafo::TfEcefEnu | ( | const Eigen::Vector3d & | enu, |
const Eigen::Vector3d & | wgs84llh_ref ) |
Transform ENU coordinate to ECEF with specified ENU-origin.
[in] | enu | ENU position to be transformed [m] |
[in] | wgs84llh_ref | ENU-origin in geodetic coordinates (lat [rad], lon [rad], height [m]) |
Eigen::Vector3d fpsdk::common::trafo::TfNedEcef | ( | const Eigen::Vector3d & | ecef, |
const Eigen::Vector3d & | wgs84llh_ref ) |
Convert ECEF coordinates to ENU with specified ENU origin.
[in] | ecef | ECEF position to be converted |
[in] | wgs84llh_ref | ENU-origin input given in geodetic coordinates |
Eigen::Vector3d fpsdk::common::trafo::TfEcefNed | ( | const Eigen::Vector3d & | ned, |
const Eigen::Vector3d & | wgs84llh_ref ) |
Eigen::Vector3d fpsdk::common::trafo::TfEcefWgs84Llh | ( | const Eigen::Vector3d & | wgs84llh | ) |
Convert geodetic coordinates (latitude, longitude, height) to ECEF (x, y, z).
[in] | wgs84llh | Geodetic coordinates (Lat[rad], Lon[rad], Height[m]) |
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).
[in] | ecef | ECEF coordinates [m] |
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
[in] | ecef_p | 3D position vector in ECEF |
[in] | ecef_r | 3x3 rotation matrix representing rotation from body to ECEF |
Eigen::Vector3d fpsdk::common::trafo::QuatToEul | ( | const Eigen::Quaterniond & | quat | ) |
Vector4 quaternion to intrinsic Euler Angles in ZYX (yaw,pitch,roll)
[in] | quat | Quaternion (w, i, j, k) |
Eigen::Vector3d fpsdk::common::trafo::RotToEul | ( | const Eigen::Matrix3d & | rot | ) |
Rotation Matrix to intrinsic Euler Angles in ZYX (Yaw-Pitch-Roll) order in radian.
rot | Eigen::Matrix3d |
Eigen::Vector3d fpsdk::common::trafo::LlhDegToRad | ( | const Eigen::Vector3d & | llh_deg | ) |
Convert llh from deg to rad, height component unchanged.
[in] | llh_deg | llh in degrees |
Eigen::Vector3d fpsdk::common::trafo::LlhRadToDeg | ( | const Eigen::Vector3d & | llh_rad | ) |
Convert llh from rad to deg, height component unchanged.
[in] | llh_rad | llh in radian |
|
staticconstexpr |
|
staticconstexpr |
|
staticconstexpr |
|
staticconstexpr |