0.2.0
Loading...
Searching...
No Matches
CoordinateFrames.hpp File Reference

Transformation collection. More...

Go to the source code of this file.

Functions

template<typename Derived >
Eigen::Quaternion< typename Derived::Scalar > NAV::trafo::b_Quat_n (const Eigen::MatrixBase< Derived > &rollPitchYaw)
 Quaternion for rotations from navigation to body frame.
 
template<typename Scalar , typename = std::enable_if_t<std::is_floating_point_v<Scalar>>>
Eigen::Quaternion< Scalar > NAV::trafo::b_Quat_n (Scalar roll, Scalar pitch, Scalar yaw)
 Quaternion for rotations from navigation to body frame.
 
template<typename Scalar , typename = std::enable_if_t<std::is_floating_point_v<Scalar>>>
Eigen::Quaternion< Scalar > NAV::trafo::b_Quat_p (Scalar mountingAngleX, Scalar mountingAngleY, Scalar mountingAngleZ)
 Quaternion for rotations from platform to body frame.
 
template<typename Scalar , typename = std::enable_if_t<std::is_floating_point_v<Scalar>>>
Eigen::Quaternion< Scalar > NAV::trafo::e_Quat_i (Scalar time, Scalar omega_ie=InsConst< Scalar >::omega_ie)
 Quaternion for rotations from inertial to Earth-centered-Earth-fixed frame.
 
template<typename Scalar , typename = std::enable_if_t<std::is_floating_point_v<Scalar>>>
Eigen::Quaternion< Scalar > NAV::trafo::e_Quat_n (Scalar latitude, Scalar longitude)
 Quaternion for rotations from navigation to Earth-fixed frame.
 
template<typename Derived >
Eigen::Vector3< typename Derived::Scalar > NAV::trafo::internal::ecef2lla (const Eigen::MatrixBase< Derived > &e_position, typename Derived::Scalar a, typename Derived::Scalar b, typename Derived::Scalar e_squared)
 Converts Earth-centered-Earth-fixed coordinates into latitude, longitude and altitude.
 
template<typename Derived >
Eigen::Vector3< typename Derived::Scalar > NAV::trafo::ecef2lla_GRS80 (const Eigen::MatrixBase< Derived > &e_position)
 Converts Earth-centered-Earth-fixed coordinates into latitude, longitude and altitude using GRS90.
 
template<typename Derived >
Eigen::Vector3< typename Derived::Scalar > NAV::trafo::ecef2lla_WGS84 (const Eigen::MatrixBase< Derived > &e_position)
 Converts Earth-centered-Earth-fixed coordinates into latitude, longitude and altitude using WGS84.
 
template<typename DerivedA , typename DerivedB >
Eigen::Vector3< typename DerivedA::Scalar > NAV::trafo::ecef2ned (const Eigen::MatrixBase< DerivedA > &e_position, const Eigen::MatrixBase< DerivedB > &lla_position_ref)
 Converts ECEF coordinates into local NED coordinates.
 
template<typename Scalar , typename = std::enable_if_t<std::is_floating_point_v<Scalar>>>
Eigen::Quaternion< Scalar > NAV::trafo::i_Quat_e (Scalar time, Scalar omega_ie=InsConst< Scalar >::omega_ie)
 Quaternion for rotations from Earth-centered-Earth-fixed to inertial frame.
 
template<typename Derived >
Eigen::Vector3< typename Derived::Scalar > NAV::trafo::internal::lla2ecef (const Eigen::MatrixBase< Derived > &lla_position, typename Derived::Scalar a, typename Derived::Scalar e_squared)
 Converts latitude, longitude and altitude into Earth-centered-Earth-fixed coordinates.
 
template<typename Derived >
Eigen::Vector3< typename Derived::Scalar > NAV::trafo::lla2ecef_GRS80 (const Eigen::MatrixBase< Derived > &lla_position)
 Converts latitude, longitude and altitude into Earth-centered-Earth-fixed coordinates using GRS90.
 
template<typename Derived >
Eigen::Vector3< typename Derived::Scalar > NAV::trafo::lla2ecef_WGS84 (const Eigen::MatrixBase< Derived > &lla_position)
 Converts latitude, longitude and altitude into Earth-centered-Earth-fixed coordinates using WGS84.
 
template<typename Derived >
Eigen::Quaternion< typename Derived::Scalar > NAV::trafo::n_Quat_b (const Eigen::MatrixBase< Derived > &rollPitchYaw)
 Quaternion for rotations from body to navigation frame.
 
template<typename Scalar , typename = std::enable_if_t<std::is_floating_point_v<Scalar>>>
Eigen::Quaternion< Scalar > NAV::trafo::n_Quat_b (Scalar roll, Scalar pitch, Scalar yaw)
 Quaternion for rotations from body to navigation frame.
 
template<typename Scalar , typename = std::enable_if_t<std::is_floating_point_v<Scalar>>>
Eigen::Quaternion< Scalar > NAV::trafo::n_Quat_e (Scalar latitude, Scalar longitude)
 Quaternion for rotations from Earth-fixed to navigation frame.
 
template<typename DerivedA , typename DerivedB >
Eigen::Vector3< typename DerivedA::Scalar > NAV::trafo::ned2ecef (const Eigen::MatrixBase< DerivedA > &n_position, const Eigen::MatrixBase< DerivedB > &lla_position_ref)
 Converts local NED coordinates into ECEF coordinates.
 
template<typename Scalar , typename = std::enable_if_t<std::is_floating_point_v<Scalar>>>
Eigen::Quaternion< Scalar > NAV::trafo::p_Quat_b (Scalar mountingAngleX, Scalar mountingAngleY, Scalar mountingAngleZ)
 Quaternion for rotations from body to platform frame.
 
template<typename DerivedA , typename DerivedB >
Eigen::Vector3< typename DerivedA::Scalar > NAV::trafo::pz90toWGS84 (const Eigen::MatrixBase< DerivedA > &pz90, const Eigen::MatrixBase< DerivedB > &pz90_pos)
 Converts PZ-90.11 vectors to WGS84 frame.
 
template<typename Derived >
Eigen::Vector3< typename Derived::Scalar > NAV::trafo::pz90toWGS84_pos (const Eigen::MatrixBase< Derived > &pz90_pos)
 Converts PZ-90.11 coordinates to WGS84 coordinates.
 
template<typename Derived >
Eigen::Vector3< typename Derived::Scalar > NAV::trafo::quat2eulerZYX (const Eigen::QuaternionBase< Derived > &q)
 Converts the quaternion to Euler rotation angles with rotation sequence ZYX.
 
template<typename Derived >
Eigen::Vector3< typename Derived::Scalar > NAV::trafo::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.
 

Detailed Description

Transformation collection.

Author
T. Topp (topp@.nosp@m.ins..nosp@m.uni-s.nosp@m.tutt.nosp@m.gart..nosp@m.de)
Date
2020-09-08

Coordinate Frames:

  • Inertial frame (i-frame) O_i: Earth center x_i: Direction to Vernal equinox y_i: In equatorial plane, complementing to Right-Hand-System z_i: Vertical on equatorial plane (North)
  • Earth-centered-Earth-fixed frame (e-frame) O_e: Earth center of mass x_e: Direction to Greenwich meridian (longitude = 0掳) y_e: In equatorial plane, complementing to Right-Hand-System z_e: Vertical on equatorial plane (North)
  • Local Navigation frame (n-frame) O_n: Vehicle center of mass x_n: "North" y_n: Right-Hand-System ("East") z_n: Earth center ("Down")
  • Body frame (b-frame) O_b: Vehicle center of mass x_b: Roll-axis ("Forward") y_b: Pitch-axis ("Right") z_b: Yaw-axis ("Down")
  • Platform frame (p-frame) O_b: Center of IMU x_b: X-Axis Accelerometer/Gyrometer y_b: Y-Axis Accelerometer/Gyrometer z_b: Z-Axis Accelerometer/Gyrometer

Function Documentation

◆ b_Quat_n() [1/2]

template<typename Derived >
Eigen::Quaternion< typename Derived::Scalar > NAV::trafo::b_Quat_n ( const Eigen::MatrixBase< Derived > & rollPitchYaw)

Quaternion for rotations from navigation to body frame.

Parameters
[in]rollPitchYawRoll, Pitch, Yaw angle in [rad]
Returns
The rotation Quaternion representation

◆ b_Quat_n() [2/2]

template<typename Scalar , typename = std::enable_if_t<std::is_floating_point_v<Scalar>>>
Eigen::Quaternion< Scalar > NAV::trafo::b_Quat_n ( Scalar roll,
Scalar pitch,
Scalar yaw )

Quaternion for rotations from navigation to body frame.

Parameters
[in]rollRoll angle in [rad]
[in]pitchPitch angle in [rad]
[in]yawYaw angle in [rad]
Returns
The rotation Quaternion representation

◆ b_Quat_p()

template<typename Scalar , typename = std::enable_if_t<std::is_floating_point_v<Scalar>>>
Eigen::Quaternion< Scalar > NAV::trafo::b_Quat_p ( Scalar mountingAngleX,
Scalar mountingAngleY,
Scalar mountingAngleZ )

Quaternion for rotations from platform to body frame.

Parameters
[in]mountingAngleXMounting angle to x axis in [rad]. First rotation. (-pi:pi]
[in]mountingAngleYMounting angle to y axis in [rad]. Second rotation. (-pi/2:pi/2]
[in]mountingAngleZMounting angle to z axis in [rad]. Third rotation. (-pi:pi]
Returns
The rotation Quaternion representation

◆ e_Quat_i()

template<typename Scalar , typename = std::enable_if_t<std::is_floating_point_v<Scalar>>>
Eigen::Quaternion< Scalar > NAV::trafo::e_Quat_i ( Scalar time,
Scalar omega_ie = InsConst<Scalar>::omega_ie )

Quaternion for rotations from inertial to Earth-centered-Earth-fixed frame.

Parameters
[in]timeTime (t - t0)
[in]omega_ieAngular velocity in [rad/s] of earth frame with regard to the inertial frame
Returns
The rotation Quaternion representation

◆ e_Quat_n()

template<typename Scalar , typename = std::enable_if_t<std::is_floating_point_v<Scalar>>>
Eigen::Quaternion< Scalar > NAV::trafo::e_Quat_n ( Scalar latitude,
Scalar longitude )

Quaternion for rotations from navigation to Earth-fixed frame.

Parameters
[in]latitude饾湙 Geodetic latitude in [rad]
[in]longitude位 Geodetic longitude in [rad]
Returns
The rotation Quaternion representation

◆ ecef2lla()

template<typename Derived >
Eigen::Vector3< typename Derived::Scalar > NAV::trafo::internal::ecef2lla ( const Eigen::MatrixBase< Derived > & e_position,
typename Derived::Scalar a,
typename Derived::Scalar b,
typename Derived::Scalar e_squared )

Converts Earth-centered-Earth-fixed coordinates into latitude, longitude and altitude.

Parameters
[in]e_positionVector with coordinates in ECEF frame in [m]
[in]aSemi-major axis of the reference ellipsoid
[in]bSemi-minor axis of the reference ellipsoid
[in]e_squaredSquare of the first eccentricity of the ellipsoid
Returns
Vector containing [latitude 饾湙, longitude 位, altitude]^T in [rad, rad, m]
Note
See See S. Gleason (2009) - GNSS Applications and Methods: Software example 'Chapter6_GNSS_INS_1/wgsxyz2lla.m' (J.A. Farrel and M. Barth, 1999, GPS & Inertal Navigation. McGraw-Hill. pp. 29.)

◆ ecef2lla_GRS80()

template<typename Derived >
Eigen::Vector3< typename Derived::Scalar > NAV::trafo::ecef2lla_GRS80 ( const Eigen::MatrixBase< Derived > & e_position)

Converts Earth-centered-Earth-fixed coordinates into latitude, longitude and altitude using GRS90.

Parameters
[in]e_positionVector with coordinates in ECEF frame in [m]
Returns
Vector containing [latitude 饾湙, longitude 位, altitude]^T in [rad, rad, m]

◆ ecef2lla_WGS84()

template<typename Derived >
Eigen::Vector3< typename Derived::Scalar > NAV::trafo::ecef2lla_WGS84 ( const Eigen::MatrixBase< Derived > & e_position)

Converts Earth-centered-Earth-fixed coordinates into latitude, longitude and altitude using WGS84.

Parameters
[in]e_positionVector with coordinates in ECEF frame
Returns
Vector containing [latitude 饾湙, longitude 位, altitude]^T in [rad, rad, m]

◆ ecef2ned()

template<typename DerivedA , typename DerivedB >
Eigen::Vector3< typename DerivedA::Scalar > NAV::trafo::ecef2ned ( const Eigen::MatrixBase< DerivedA > & e_position,
const Eigen::MatrixBase< DerivedB > & lla_position_ref )

Converts ECEF coordinates into local NED coordinates.

Parameters
[in]e_positionECEF coordinates in [m] to convert
[in]lla_position_refReference [饾湙 latitude, 位 longitude, altitude]^T in [rad, rad, m] which represents the origin of the local frame
Returns
[x_N, x_E, x_D]^T Local NED coordinates in [m]
Note
See G. Cai, B.M. Chen, Lee, T.H. Lee, 2011, Unmanned Rotorcraft Systems. Springer. pp. 32
Attention
This function does not take the sphericity of the Earth into account

◆ i_Quat_e()

template<typename Scalar , typename = std::enable_if_t<std::is_floating_point_v<Scalar>>>
Eigen::Quaternion< Scalar > NAV::trafo::i_Quat_e ( Scalar time,
Scalar omega_ie = InsConst<Scalar>::omega_ie )

Quaternion for rotations from Earth-centered-Earth-fixed to inertial frame.

Parameters
[in]timeTime (t - t0)
[in]omega_ieAngular velocity in [rad/s] of earth frame with regard to the inertial frame
Returns
The rotation Quaternion representation

◆ lla2ecef()

template<typename Derived >
Eigen::Vector3< typename Derived::Scalar > NAV::trafo::internal::lla2ecef ( const Eigen::MatrixBase< Derived > & lla_position,
typename Derived::Scalar a,
typename Derived::Scalar e_squared )

Converts latitude, longitude and altitude into Earth-centered-Earth-fixed coordinates.

Parameters
[in]lla_position[饾湙 latitude, 位 longitude, altitude]^T in [rad, rad, m]
[in]aSemi-major axis of the reference ellipsoid
[in]e_squaredSquare of the first eccentricity of the ellipsoid
Returns
The ECEF coordinates in [m]
Note
See C. Jekeli, 2001, Inertial Navigation Systems with Geodetic Applications. pp. 23

◆ lla2ecef_GRS80()

template<typename Derived >
Eigen::Vector3< typename Derived::Scalar > NAV::trafo::lla2ecef_GRS80 ( const Eigen::MatrixBase< Derived > & lla_position)

Converts latitude, longitude and altitude into Earth-centered-Earth-fixed coordinates using GRS90.

Parameters
[in]lla_position[饾湙 latitude, 位 longitude, altitude]^T in [rad, rad, m]
Returns
The ECEF coordinates in [m]

◆ lla2ecef_WGS84()

template<typename Derived >
Eigen::Vector3< typename Derived::Scalar > NAV::trafo::lla2ecef_WGS84 ( const Eigen::MatrixBase< Derived > & lla_position)

Converts latitude, longitude and altitude into Earth-centered-Earth-fixed coordinates using WGS84.

Parameters
[in]lla_position[饾湙 latitude, 位 longitude, altitude]^T in [rad, rad, m]
Returns
The ECEF coordinates in [m]

◆ n_Quat_b() [1/2]

template<typename Derived >
Eigen::Quaternion< typename Derived::Scalar > NAV::trafo::n_Quat_b ( const Eigen::MatrixBase< Derived > & rollPitchYaw)

Quaternion for rotations from body to navigation frame.

Parameters
[in]rollPitchYawRoll, Pitch, Yaw angle in [rad]
Returns
The rotation Quaternion representation

◆ n_Quat_b() [2/2]

template<typename Scalar , typename = std::enable_if_t<std::is_floating_point_v<Scalar>>>
Eigen::Quaternion< Scalar > NAV::trafo::n_Quat_b ( Scalar roll,
Scalar pitch,
Scalar yaw )

Quaternion for rotations from body to navigation frame.

Parameters
[in]rollRoll angle in [rad]
[in]pitchPitch angle in [rad]
[in]yawYaw angle in [rad]
Returns
The rotation Quaternion representation

◆ n_Quat_e()

template<typename Scalar , typename = std::enable_if_t<std::is_floating_point_v<Scalar>>>
Eigen::Quaternion< Scalar > NAV::trafo::n_Quat_e ( Scalar latitude,
Scalar longitude )

Quaternion for rotations from Earth-fixed to navigation frame.

Parameters
[in]latitude饾湙 Geodetic latitude in [rad]
[in]longitude位 Geodetic longitude in [rad]
Returns
The rotation Quaternion representation

◆ ned2ecef()

template<typename DerivedA , typename DerivedB >
Eigen::Vector3< typename DerivedA::Scalar > NAV::trafo::ned2ecef ( const Eigen::MatrixBase< DerivedA > & n_position,
const Eigen::MatrixBase< DerivedB > & lla_position_ref )

Converts local NED coordinates into ECEF coordinates.

Parameters
[in]n_positionNED coordinates in [m] to convert
[in]lla_position_refReference [饾湙 latitude, 位 longitude, altitude]^T in [rad, rad, m] which represents the origin of the local frame
Returns
ECEF position in [m]
Note
See G. Cai, B.M. Chen, Lee, T.H. Lee, 2011, Unmanned Rotorcraft Systems. Springer. pp. 32
Attention
This function does not take the sphericity of the Earth into account

◆ p_Quat_b()

template<typename Scalar , typename = std::enable_if_t<std::is_floating_point_v<Scalar>>>
Eigen::Quaternion< Scalar > NAV::trafo::p_Quat_b ( Scalar mountingAngleX,
Scalar mountingAngleY,
Scalar mountingAngleZ )

Quaternion for rotations from body to platform frame.

Parameters
[in]mountingAngleXMounting angle to x axis in [rad]. First rotation. (-pi:pi]
[in]mountingAngleYMounting angle to y axis in [rad]. Second rotation. (-pi/2:pi/2]
[in]mountingAngleZMounting angle to z axis in [rad]. Third rotation. (-pi:pi]
Returns
The rotation Quaternion representation

◆ pz90toWGS84()

template<typename DerivedA , typename DerivedB >
Eigen::Vector3< typename DerivedA::Scalar > NAV::trafo::pz90toWGS84 ( const Eigen::MatrixBase< DerivedA > & pz90,
const Eigen::MatrixBase< DerivedB > & pz90_pos )

Converts PZ-90.11 vectors to WGS84 frame.

Parameters
[in]pz90Vector in PZ-90.11 frame
[in]pz90_posPosition in PZ-90.11 frame (needed for calculation)
Returns
Vector in WGS84 frame

◆ pz90toWGS84_pos()

template<typename Derived >
Eigen::Vector3< typename Derived::Scalar > NAV::trafo::pz90toWGS84_pos ( const Eigen::MatrixBase< Derived > & pz90_pos)

Converts PZ-90.11 coordinates to WGS84 coordinates.

Parameters
[in]pz90_posPosition in PZ-90.11 coordinates
Returns
Position in WGS84 coordinates
Note
See [35] PZ-90.11 Reference Document Appendix 4, p.34f

◆ quat2eulerZYX()

template<typename Derived >
Eigen::Vector3< typename Derived::Scalar > NAV::trafo::quat2eulerZYX ( const Eigen::QuaternionBase< Derived > & q)

Converts the quaternion to Euler rotation angles with rotation sequence ZYX.

Parameters
[in]qQuaternion to convert
Returns
[angleX, angleY, angleZ]^T vector in [rad]. The returned angles are in the ranges (-pi:pi] x (-pi/2:pi/2] x (-pi:pi]

◆ sph2ecef()

template<typename Derived >
Eigen::Vector3< typename Derived::Scalar > NAV::trafo::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.

Parameters
[in]position_sPosition in spherical coordinates to convert
[in]elevationElevation in [rad]
[in]azimuthAzimuth in [rad]
Returns
The ECEF coordinates in [m]