0.3.0
Loading...
Searching...
No Matches
NAV::trafo Namespace Reference

Namespaces

namespace  internal
 

Functions

template<typename Derived>
Eigen::Quaternion< typename Derived::Scalar > b_Quat_n (const Eigen::MatrixBase< Derived > &rollPitchYaw)
 Quaternion for rotations from navigation to body frame.
 
template<typename Scalar>
Eigen::Quaternion< Scalar > b_Quat_n (const Scalar &roll, const Scalar &pitch, const Scalar &yaw)
 Quaternion for rotations from navigation to body frame.
 
template<typename Scalar>
Eigen::Quaternion< Scalar > b_Quat_p (Scalar mountingAngleX, Scalar mountingAngleY, Scalar mountingAngleZ)
 Quaternion for rotations from platform to body frame.
 
template<typename Derived>
Eigen::Matrix< typename Derived::Scalar, 4, 4 > covQuat2QuatJacobian (const Eigen::QuaternionBase< Derived > &beta_quat_alpha)
 Calculates the Jacobian to convert an attitude represented in quaternions from one frame into another. Multiply: cov_beta = J * cov_alpha * J^T.
 
template<typename Derived, typename DerivedQ>
Eigen::Matrix3< typename Derived::Scalar > covQuat2RPY (const Eigen::MatrixBase< Derived > &covQuat, const Eigen::QuaternionBase< DerivedQ > &n_quat_b)
 Converts a covariance for an attitude represented in quaternion form into a covariance for Euler angels (yaw, pitch, roll)
 
template<typename Derived>
Eigen::Matrix< typename Derived::Scalar, 3, 4 > covQuat2RPYJacobian (const Eigen::QuaternionBase< Derived > &n_quat_b)
 Calculates the Jacobian to convert an attitude represented in quaternions into a covariance in Euler angels (roll, pitch, yaw)
 
template<typename Derived>
Eigen::Matrix< typename Derived::Scalar, 3, 4 > covQuatDiffJacobian (const Eigen::QuaternionBase< Derived > &quat)
 Calculates the Jacobian to convert an attitude represented in quaternions into the difference of the vector part of two quaternions.
 
template<typename Derived, typename DerivedQ>
Eigen::Matrix4< typename Derived::Scalar > covRPY2quat (const Eigen::MatrixBase< Derived > &covRPY, const Eigen::QuaternionBase< DerivedQ > &n_quat_b)
 Converts a covariance for an attitude represented in Euler angels (roll, pitch, yaw) into a covariance for a quaternion.
 
template<typename Derived>
Eigen::Matrix< typename Derived::Scalar, 4, 3 > covRPY2quatJacobian (const Eigen::QuaternionBase< Derived > &n_quat_b)
 Calculates the Jacobian to convert an attitude represented in Euler angels (roll, pitch, yaw) into a covariance for a quaternion.
 
template<typename Derived>
Eigen::Vector3< typename Derived::Scalar > e_posARP2APC (const Eigen::MatrixBase< Derived > &e_posARP, const std::shared_ptr< const GnssObs > &gnssObs, Frequency freq, const std::string &antennaType, const std::string &nameId)
 Converts a antenna reference point position position to the antenna phase center position.
 
template<typename Derived>
Eigen::Vector3< typename Derived::Scalar > e_posMarker2ARP (const Eigen::MatrixBase< Derived > &e_posMarker, const std::shared_ptr< const GnssObs > &gnssObs, const Eigen::Vector3d &hen_delta=Eigen::Vector3d::Zero())
 Converts a marker position to the antenna reference point position.
 
template<typename Scalar>
Eigen::Quaternion< Scalar > e_Quat_i (Scalar time, Scalar omega_ie=InsConst::omega_ie)
 Quaternion for rotations from inertial to Earth-centered-Earth-fixed frame.
 
template<typename Scalar>
Eigen::Quaternion< Scalar > e_Quat_n (const Scalar &latitude, const Scalar &longitude)
 Quaternion for rotations from navigation to Earth-fixed frame.
 
template<typename Derived>
Eigen::Vector3< typename Derived::Scalar > 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 > 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 > ecef2ned (const Eigen::MatrixBase< DerivedA > &e_position, const Eigen::MatrixBase< DerivedB > &lla_position_ref)
 Converts ECEF coordinates into local NED coordinates.
 
template<typename Scalar>
Eigen::Quaternion< Scalar > i_Quat_e (Scalar time, Scalar omega_ie=InsConst::omega_ie)
 Quaternion for rotations from Earth-centered-Earth-fixed to inertial frame.
 
template<typename Derived>
Eigen::Vector3< typename Derived::Scalar > 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 > 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::Vector3< typename Derived::Scalar > lla_posARP2APC (const Eigen::MatrixBase< Derived > &lla_posARP, const std::shared_ptr< const GnssObs > &gnssObs, Frequency freq, const std::string &antennaType, const std::string &nameId)
 Converts a antenna reference point position to the antenna phase center position.
 
template<typename Derived>
Eigen::Vector3< typename Derived::Scalar > lla_posMarker2ARP (const Eigen::MatrixBase< Derived > &lla_posMarker, const std::shared_ptr< const GnssObs > &gnssObs, const Eigen::Vector3d &hen_delta=Eigen::Vector3d::Zero())
 Converts a marker position to the antenna reference point position.
 
template<typename Derived>
Eigen::Quaternion< typename Derived::Scalar > n_Quat_b (const Eigen::MatrixBase< Derived > &rollPitchYaw)
 Quaternion for rotations from body to navigation frame.
 
template<typename Scalar>
Eigen::Quaternion< Scalar > n_Quat_b (Scalar roll, Scalar pitch, Scalar yaw)
 Quaternion for rotations from body to navigation frame.
 
template<typename Scalar>
Eigen::Quaternion< Scalar > n_Quat_e (const Scalar &latitude, const Scalar &longitude)
 Quaternion for rotations from Earth-fixed to navigation frame.
 
template<typename DerivedA, typename DerivedB>
Eigen::Vector3< typename DerivedA::Scalar > ned2ecef (const Eigen::MatrixBase< DerivedA > &n_position, const Eigen::MatrixBase< DerivedB > &lla_position_ref)
 Converts local NED coordinates into ECEF coordinates.
 
template<typename Scalar>
Eigen::Quaternion< Scalar > 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 > 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 > pz90toWGS84_pos (const Eigen::MatrixBase< Derived > &pz90_pos)
 Converts PZ-90.11 coordinates to WGS84 coordinates.
 
template<typename Derived>
Eigen::Vector3< typename Derived::Scalar > 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 > 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.
 

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)
nodiscard

Quaternion for rotations from navigation to body frame.

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

Definition at line 346 of file CoordinateFrames.hpp.

◆ b_Quat_n() [2/2]

template<typename Scalar>
Eigen::Quaternion< Scalar > NAV::trafo::b_Quat_n ( const Scalar & roll,
const Scalar & pitch,
const Scalar & yaw )
nodiscard

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

Definition at line 331 of file CoordinateFrames.hpp.

◆ b_Quat_p()

template<typename Scalar>
Eigen::Quaternion< Scalar > NAV::trafo::b_Quat_p ( Scalar mountingAngleX,
Scalar mountingAngleY,
Scalar mountingAngleZ )
nodiscard

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

Definition at line 377 of file CoordinateFrames.hpp.

◆ covQuat2QuatJacobian()

template<typename Derived>
Eigen::Matrix< typename Derived::Scalar, 4, 4 > NAV::trafo::covQuat2QuatJacobian ( const Eigen::QuaternionBase< Derived > & beta_quat_alpha)
nodiscard

Calculates the Jacobian to convert an attitude represented in quaternions from one frame into another. Multiply: cov_beta = J * cov_alpha * J^T.

Parameters
beta_quat_alphaQuaternion for rotations from frame alpha to frame beta. e.g. n_q_e if converting e_cov_b to n_cov_b

Definition at line 250 of file CoordinateFrames.hpp.

◆ covQuat2RPY()

template<typename Derived, typename DerivedQ>
Eigen::Matrix3< typename Derived::Scalar > NAV::trafo::covQuat2RPY ( const Eigen::MatrixBase< Derived > & covQuat,
const Eigen::QuaternionBase< DerivedQ > & n_quat_b )
nodiscard

Converts a covariance for an attitude represented in quaternion form into a covariance for Euler angels (yaw, pitch, roll)

Parameters
covQuatCovariance for the quaternion
n_quat_bQuaternion for rotations from body to navigation frame
Returns
Covariance for the Euler angels (roll, pitch, yaw)

Definition at line 241 of file CoordinateFrames.hpp.

◆ covQuat2RPYJacobian()

template<typename Derived>
Eigen::Matrix< typename Derived::Scalar, 3, 4 > NAV::trafo::covQuat2RPYJacobian ( const Eigen::QuaternionBase< Derived > & n_quat_b)
nodiscard

Calculates the Jacobian to convert an attitude represented in quaternions into a covariance in Euler angels (roll, pitch, yaw)

Parameters
n_quat_bQuaternion for rotations from body to navigation frame

Definition at line 204 of file CoordinateFrames.hpp.

◆ covQuatDiffJacobian()

template<typename Derived>
Eigen::Matrix< typename Derived::Scalar, 3, 4 > NAV::trafo::covQuatDiffJacobian ( const Eigen::QuaternionBase< Derived > & quat)
nodiscard

Calculates the Jacobian to convert an attitude represented in quaternions into the difference of the vector part of two quaternions.

Parameters
quatQuaternion for which the Jacobian is wanted

Definition at line 266 of file CoordinateFrames.hpp.

◆ covRPY2quat()

template<typename Derived, typename DerivedQ>
Eigen::Matrix4< typename Derived::Scalar > NAV::trafo::covRPY2quat ( const Eigen::MatrixBase< Derived > & covRPY,
const Eigen::QuaternionBase< DerivedQ > & n_quat_b )
nodiscard

Converts a covariance for an attitude represented in Euler angels (roll, pitch, yaw) into a covariance for a quaternion.

Parameters
covRPYCovariance for the Euler angles
n_quat_bQuaternion for rotations from body to navigation frame
Returns
Covariance for the quaternion

Definition at line 195 of file CoordinateFrames.hpp.

◆ covRPY2quatJacobian()

template<typename Derived>
Eigen::Matrix< typename Derived::Scalar, 4, 3 > NAV::trafo::covRPY2quatJacobian ( const Eigen::QuaternionBase< Derived > & n_quat_b)
nodiscard

Calculates the Jacobian to convert an attitude represented in Euler angels (roll, pitch, yaw) into a covariance for a quaternion.

Parameters
n_quat_bQuaternion for rotations from body to navigation frame

Definition at line 162 of file CoordinateFrames.hpp.

◆ e_posARP2APC()

template<typename Derived>
Eigen::Vector3< typename Derived::Scalar > NAV::trafo::e_posARP2APC ( const Eigen::MatrixBase< Derived > & e_posARP,
const std::shared_ptr< const GnssObs > & gnssObs,
Frequency freq,
const std::string & antennaType,
const std::string & nameId )
nodiscard

Converts a antenna reference point position position to the antenna phase center position.

Parameters
[in]e_posARPAntenna reference point position in ECEF coordinates [m]
[in]gnssObsGNSS observation with antenna info
[in]freqFrequency of the observation
[in]antennaTypeAntenna type
[in]nameIdNameId of the calling node for Log output
Returns
Antenna phase center position in ECEF frame [m] (ARP + antenna phase center)

Definition at line 89 of file Antenna.hpp.

◆ e_posMarker2ARP()

template<typename Derived>
Eigen::Vector3< typename Derived::Scalar > NAV::trafo::e_posMarker2ARP ( const Eigen::MatrixBase< Derived > & e_posMarker,
const std::shared_ptr< const GnssObs > & gnssObs,
const Eigen::Vector3d & hen_delta = Eigen::Vector3d::Zero() )
nodiscard

Converts a marker position to the antenna reference point position.

Parameters
[in]e_posMarkerMarker position in ECEF coordinates [m]
[in]gnssObsGNSS observation with antenna info
[in]hen_deltaAdditional height, east, north in [m]
Returns
Antenna Reference Point position in ECEF frame [m] (Marker + antennaDeltaNEU)

Definition at line 33 of file Antenna.hpp.

◆ e_Quat_i()

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

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

Definition at line 282 of file CoordinateFrames.hpp.

◆ e_Quat_n()

template<typename Scalar>
Eigen::Quaternion< Scalar > NAV::trafo::e_Quat_n ( const Scalar & latitude,
const Scalar & longitude )
nodiscard

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

Definition at line 305 of file CoordinateFrames.hpp.

◆ ecef2lla_GRS80()

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

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]

Definition at line 432 of file CoordinateFrames.hpp.

◆ ecef2lla_WGS84()

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

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]

Definition at line 420 of file CoordinateFrames.hpp.

◆ 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 )
nodiscard

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

Definition at line 447 of file CoordinateFrames.hpp.

◆ i_Quat_e()

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

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

Definition at line 295 of file CoordinateFrames.hpp.

◆ lla2ecef_GRS80()

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

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]

Definition at line 411 of file CoordinateFrames.hpp.

◆ lla2ecef_WGS84()

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

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]

Definition at line 402 of file CoordinateFrames.hpp.

◆ lla_posARP2APC()

template<typename Derived>
Eigen::Vector3< typename Derived::Scalar > NAV::trafo::lla_posARP2APC ( const Eigen::MatrixBase< Derived > & lla_posARP,
const std::shared_ptr< const GnssObs > & gnssObs,
Frequency freq,
const std::string & antennaType,
const std::string & nameId )
nodiscard

Converts a antenna reference point position to the antenna phase center position.

Parameters
[in]lla_posARPAntenna reference point position in LLA coordinates [rad, rad, m]
[in]gnssObsGNSS observation with antenna info
[in]freqFrequency of the observation
[in]antennaTypeAntenna type
[in]nameIdNameId of the calling node for Log output
Returns
Antenna phase center position in LLA coordinates [rad, rad, m] (ARP + antenna phase center)

Definition at line 125 of file Antenna.hpp.

◆ lla_posMarker2ARP()

template<typename Derived>
Eigen::Vector3< typename Derived::Scalar > NAV::trafo::lla_posMarker2ARP ( const Eigen::MatrixBase< Derived > & lla_posMarker,
const std::shared_ptr< const GnssObs > & gnssObs,
const Eigen::Vector3d & hen_delta = Eigen::Vector3d::Zero() )
nodiscard

Converts a marker position to the antenna reference point position.

Parameters
[in]lla_posMarkerMarker position in LLA coordinates [rad, rad, m]
[in]gnssObsGNSS observation with antenna info
[in]hen_deltaAdditional height, east, north in [m]
Returns
Antenna Reference Point position in LLA coordinates [rad, rad, m] (Marker + antennaDeltaNEU)

Definition at line 63 of file Antenna.hpp.

◆ n_Quat_b() [1/2]

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

Quaternion for rotations from body to navigation frame.

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

Definition at line 366 of file CoordinateFrames.hpp.

◆ n_Quat_b() [2/2]

template<typename Scalar>
Eigen::Quaternion< Scalar > NAV::trafo::n_Quat_b ( Scalar roll,
Scalar pitch,
Scalar yaw )
nodiscard

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

Definition at line 357 of file CoordinateFrames.hpp.

◆ n_Quat_e()

template<typename Scalar>
Eigen::Quaternion< Scalar > NAV::trafo::n_Quat_e ( const Scalar & latitude,
const Scalar & longitude )
nodiscard

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

Definition at line 320 of file CoordinateFrames.hpp.

◆ 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 )
nodiscard

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

Definition at line 471 of file CoordinateFrames.hpp.

◆ p_Quat_b()

template<typename Scalar>
Eigen::Quaternion< Scalar > NAV::trafo::p_Quat_b ( Scalar mountingAngleX,
Scalar mountingAngleY,
Scalar mountingAngleZ )
nodiscard

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

Definition at line 393 of file CoordinateFrames.hpp.

◆ 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 )
nodiscard

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

Definition at line 514 of file CoordinateFrames.hpp.

◆ pz90toWGS84_pos()

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

Converts PZ-90.11 coordinates to WGS84 coordinates.

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

Definition at line 493 of file CoordinateFrames.hpp.

◆ quat2eulerZYX()

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

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]

Definition at line 141 of file CoordinateFrames.hpp.

◆ 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 )
nodiscard

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]

Definition at line 525 of file CoordinateFrames.hpp.