Auterion App SDK
Auterion SDK is a library that can be used by AuterionOS apps to communicate with the system.
Utils

Utility methods (such as coordinate transformations) More...

Classes

class  auterion::MapProjection
 Provides methods to convert between the geographical coordinate system ("global") and the ENU local azimuthal equidistant plane ("local"). More...
 
Eigen::Quaternionf auterion::attitudeNedToEnu (const Eigen::Quaternionf &q_ned)
 Converts attitude from NED to ENU frame. Performs reference frame change and quaternion rotation s.t. the identity quaternion points along the x-axis within its reference frame. More...
 
Eigen::Quaterniond auterion::attitudeNedToEnu (const Eigen::Quaterniond &q_ned)
 
Eigen::Quaternionf auterion::attitudeEnuToNed (const Eigen::Quaternionf &q_enu)
 Converts attitude from ENU to NED frame. Performs reference frame change and quaternion rotation s.t. the identity quaternion points along the x-axis within its reference frame. More...
 
Eigen::Quaterniond auterion::attitudeEnuToNed (const Eigen::Quaterniond &q_enu)
 
Eigen::Vector3f auterion::yawBodyToWorld (float yaw, const Eigen::Vector3f &point_body)
 Transforms a point from body frame to world frame given the yaw of the body's attitude. The transformation only applies a yaw rotation, and therefore assumes that the body and world frame are only yaw rotated, and that they share the same handedness. More...
 
Eigen::Vector3d auterion::yawBodyToWorld (double yaw, const Eigen::Vector3d &point_body)
 
float auterion::yawNedToEnu (const float yaw_ned_rad)
 Converts yaw from NED to ENU frame. More...
 
double auterion::yawNedToEnu (const double yaw_ned_rad)
 
float auterion::yawEnuToNed (const float yaw_enu_rad)
 Converts yaw from ENU to NED frame. More...
 
double auterion::yawEnuToNed (const double yaw_enu_rad)
 
float auterion::yawRateNedToEnu (const float yaw_rate_ned)
 Converts yaw rate from NED to ENU frame. More...
 
double auterion::yawRateNedToEnu (const double yaw_rate_ned)
 
float auterion::yawRateEnuToNed (const float yaw_rate_enu)
 Converts yaw rate from ENU to NED frame. More...
 
double auterion::yawRateEnuToNed (const double yaw_rate_enu)
 
Eigen::Vector3f auterion::positionNedToEnu (const Eigen::Vector3f &ned)
 Converts coordinates from NED to ENU frame. More...
 
Eigen::Vector3d auterion::positionNedToEnu (const Eigen::Vector3d &ned)
 
Eigen::Vector2f auterion::positionNedToEnu (const Eigen::Vector2f &ne)
 
Eigen::Vector2d auterion::positionNedToEnu (const Eigen::Vector2d &ne)
 
Eigen::Vector3f auterion::positionEnuToNed (const Eigen::Vector3f &enu)
 Converts coordinates from ENU to NED frame. More...
 
Eigen::Vector3d auterion::positionEnuToNed (const Eigen::Vector3d &enu)
 
Eigen::Vector2f auterion::positionEnuToNed (const Eigen::Vector2f &en)
 
Eigen::Vector2d auterion::positionEnuToNed (const Eigen::Vector2d &en)
 
Eigen::Vector3f auterion::frdToFlu (const Eigen::Vector3f &frd)
 Converts coordinates from FRD to FLU frame. More...
 
Eigen::Vector3d auterion::frdToFlu (const Eigen::Vector3d &frd)
 
Eigen::Vector3f auterion::fluToFrd (const Eigen::Vector3f &flu)
 Converts coordinates from FLU to FRD frame. More...
 
Eigen::Vector3d auterion::fluToFrd (const Eigen::Vector3d &flu)
 
Eigen::Vector3f auterion::varianceNedToEnu (const Eigen::Vector3f &v_ned)
 Converts variance from NED to ENU frame. More...
 
Eigen::Vector3d auterion::varianceNedToEnu (const Eigen::Vector3d &v_ned)
 
Eigen::Vector3f auterion::varianceEnuToNed (const Eigen::Vector3f &v_enu)
 Converts variance from ENU to NED frame. More...
 
Eigen::Vector3d auterion::varianceEnuToNed (const Eigen::Vector3d &v_enu)
 
float auterion::radToDeg (const float rad)
 Converts radians to degrees.
 
double auterion::radToDeg (const double rad)
 
float auterion::degToRad (const float deg)
 Converts degrees to radians.
 
double auterion::degToRad (const double deg)
 
float auterion::wrapAngleToPlusMinusPi (float yaw)
 Wraps an angle to the range [-pi, pi). More...
 
double auterion::wrapAngleToPlusMinusPi (double yaw)
 
Eigen::Vector3f auterion::quaternionToEulerRpy (const Eigen::Quaternionf &q)
 Converts a quaternion to RPY extrinsic Tait-Bryan Euler angles (YPR intrinsic) XYZ axes correspond to RPY angles respectively. More...
 
Eigen::Vector3d auterion::quaternionToEulerRpy (const Eigen::Quaterniond &q)
 
Eigen::Quaternionf auterion::eulerRpyToQuaternion (const Eigen::Vector3f &euler)
 Converts RPY extrinsic Tait-Bryan Euler angles (YPR intrinsic) to quaternion. More...
 
Eigen::Quaterniond auterion::eulerRpyToQuaternion (const Eigen::Vector3d &euler)
 
Eigen::Quaternionf auterion::eulerRpyToQuaternion (const float roll, const float pitch, const float yaw)
 Converts RPY extrinsic Tait-Bryan Euler angles (YPR intrinsic) to quaternion. More...
 
Eigen::Quaterniond auterion::eulerRpyToQuaternion (const double roll, const double pitch, const double yaw)
 
float auterion::quaternionToRoll (const Eigen::Quaternionf &q)
 Convert quaternion to roll angle in extrinsic RPY order (intrinsic YPR) More...
 
double auterion::quaternionToRoll (const Eigen::Quaterniond &q)
 
float auterion::quaternionToPitch (const Eigen::Quaternionf &q)
 Convert quaternion to pitch angle in extrinsic RPY order (intrinsic YPR) More...
 
double auterion::quaternionToPitch (const Eigen::Quaterniond &q)
 
float auterion::quaternionToYaw (const Eigen::Quaternionf &q)
 Convert quaternion to yaw angle in extrinsic RPY order (intrinsic YPR) More...
 
double auterion::quaternionToYaw (const Eigen::Quaterniond &q)
 

Detailed Description

Utility methods (such as coordinate transformations)

Function Documentation

◆ attitudeEnuToNed()

Eigen::Quaternionf auterion::attitudeEnuToNed ( const Eigen::Quaternionf &  q_enu)

Converts attitude from ENU to NED frame. Performs reference frame change and quaternion rotation s.t. the identity quaternion points along the x-axis within its reference frame.

Parameters
q_enuAttitude quaternion in ENU frame.
Returns
Attitude quaternion in NED frame.

◆ attitudeNedToEnu()

Eigen::Quaternionf auterion::attitudeNedToEnu ( const Eigen::Quaternionf &  q_ned)

Converts attitude from NED to ENU frame. Performs reference frame change and quaternion rotation s.t. the identity quaternion points along the x-axis within its reference frame.

Parameters
q_nedAttitude quaternion in NED frame.
Returns
Attitude quaternion in ENU frame.

◆ eulerRpyToQuaternion() [1/2]

Eigen::Quaternionf auterion::eulerRpyToQuaternion ( const Eigen::Vector3f &  euler)

Converts RPY extrinsic Tait-Bryan Euler angles (YPR intrinsic) to quaternion.

Parameters
eulerThe euler angles [rad]
Returns
Quaternion corresponding to the given euler angles.

◆ eulerRpyToQuaternion() [2/2]

Eigen::Quaternionf auterion::eulerRpyToQuaternion ( const float  roll,
const float  pitch,
const float  yaw 
)

Converts RPY extrinsic Tait-Bryan Euler angles (YPR intrinsic) to quaternion.

Parameters
rollThe roll angle [rad].
pitchThe pitch angle [rad].
yawThe yaw angle [rad].
Returns
Quaternion corresponding to the given euler angles.

◆ fluToFrd()

Eigen::Vector3f auterion::fluToFrd ( const Eigen::Vector3f &  flu)

Converts coordinates from FLU to FRD frame.

Parameters
fluCoordinates in FLU frame.
Returns
Coordinates in FRD frame.

◆ frdToFlu()

Eigen::Vector3f auterion::frdToFlu ( const Eigen::Vector3f &  frd)

Converts coordinates from FRD to FLU frame.

Parameters
frdCoordinates in FRD frame.
Returns
Coordinates in FLU frame.

◆ positionEnuToNed()

Eigen::Vector3f auterion::positionEnuToNed ( const Eigen::Vector3f &  enu)

Converts coordinates from ENU to NED frame.

Parameters
enuCoordinates in ENU frame.
Returns
Coordinates in NED frame.

◆ positionNedToEnu()

Eigen::Vector3f auterion::positionNedToEnu ( const Eigen::Vector3f &  ned)

Converts coordinates from NED to ENU frame.

Parameters
nedCoordinates in NED frame.
Returns
Coordinates in ENU frame.

◆ quaternionToEulerRpy()

Eigen::Vector3f auterion::quaternionToEulerRpy ( const Eigen::Quaternionf &  q)

Converts a quaternion to RPY extrinsic Tait-Bryan Euler angles (YPR intrinsic) XYZ axes correspond to RPY angles respectively.

Parameters
qThe input quaternion.
Returns
Euler angles corresponding to the given quaternion in range R, P, Y = [-pi, pi], [-pi/2, pi], [-pi, pi].

◆ quaternionToPitch()

float auterion::quaternionToPitch ( const Eigen::Quaternionf &  q)

Convert quaternion to pitch angle in extrinsic RPY order (intrinsic YPR)

Parameters
qThe input quaternion
Returns
Pitch angle corresponding to the given quaternion in range [-pi, pi]

◆ quaternionToRoll()

float auterion::quaternionToRoll ( const Eigen::Quaternionf &  q)

Convert quaternion to roll angle in extrinsic RPY order (intrinsic YPR)

Parameters
qThe input quaternion
Returns
Roll angle corresponding to the given quaternion in range [-pi, pi]

◆ quaternionToYaw()

float auterion::quaternionToYaw ( const Eigen::Quaternionf &  q)

Convert quaternion to yaw angle in extrinsic RPY order (intrinsic YPR)

Parameters
qThe input quaternion
Returns
Yaw angle corresponding to the given quaternion in range [-pi, pi]

◆ varianceEnuToNed()

Eigen::Vector3f auterion::varianceEnuToNed ( const Eigen::Vector3f &  v_enu)

Converts variance from ENU to NED frame.

Parameters
v_enuVariance vector in ENU frame.
Returns
Variance vector in NED frame.

◆ varianceNedToEnu()

Eigen::Vector3f auterion::varianceNedToEnu ( const Eigen::Vector3f &  v_ned)

Converts variance from NED to ENU frame.

Parameters
v_nedVariance vector in NED frame.
Returns
Variance vector in ENU frame.

◆ wrapAngleToPlusMinusPi()

float auterion::wrapAngleToPlusMinusPi ( float  yaw)

Wraps an angle to the range [-pi, pi).

Parameters
yawThe input angle [rad].
Returns
The wrapped angle in the range [-pi, pi).

◆ yawBodyToWorld()

Eigen::Vector3f auterion::yawBodyToWorld ( float  yaw,
const Eigen::Vector3f &  point_body 
)

Transforms a point from body frame to world frame given the yaw of the body's attitude. The transformation only applies a yaw rotation, and therefore assumes that the body and world frame are only yaw rotated, and that they share the same handedness.

Parameters
yawThe yaw of the body's attitude [rad].
point_bodyThe point coordinates in the body frame.
Returns
The yaw rotated point in the world frame.

◆ yawEnuToNed()

float auterion::yawEnuToNed ( const float  yaw_enu_rad)

Converts yaw from ENU to NED frame.

Parameters
yaw_enu_radYaw angle in ENU frame [rad].
Returns
Yaw angle in NED frame [rad], wrapped to [-pi, pi].

◆ yawNedToEnu()

float auterion::yawNedToEnu ( const float  yaw_ned_rad)

Converts yaw from NED to ENU frame.

Parameters
yaw_ned_radYaw angle in NED frame [rad].
Returns
Yaw angle in ENU frame [rad], wrapped to [-pi, pi].

◆ yawRateEnuToNed()

float auterion::yawRateEnuToNed ( const float  yaw_rate_enu)

Converts yaw rate from ENU to NED frame.

Parameters
yaw_rate_enuYaw rate in ENU frame.
Returns
Yaw rate in NED frame.

◆ yawRateNedToEnu()

float auterion::yawRateNedToEnu ( const float  yaw_rate_ned)

Converts yaw rate from NED to ENU frame.

Parameters
yaw_rate_nedYaw rate in NED frame.
Returns
Yaw rate in ENU frame.