PX4 ROS 2 Interface Library
Library to interface with PX4 from a companion computer using ROS 2
Geometry
template<typename Type >
Type px4_ros2::radToDeg (Type rad)
 Converts radians to degrees.
 
template<typename Type >
Type px4_ros2::degToRad (Type deg)
 Converts degrees to radians.
 
template<typename Type >
Type px4_ros2::wrapPi (Type angle)
 Wraps an angle to the range [-pi, pi). More...
 
template<typename Type >
Eigen::Matrix< Type, 3, 1 > px4_ros2::quaternionToEulerRpy (const Eigen::Quaternion< Type > &q)
 Converts a quaternion to RPY extrinsic Tait-Bryan Euler angles (YPR intrinsic) XYZ axes correspond to RPY angles respectively. More...
 
template<typename Type >
Eigen::Quaternion< Type > px4_ros2::eulerRpyToQuaternion (const Eigen::Matrix< Type, 3, 1 > &euler)
 Converts RPY extrinsic Tait-Bryan Euler angles (YPR intrinsic) to quaternion. More...
 
template<typename Type >
Eigen::Quaternion< Type > px4_ros2::eulerRpyToQuaternion (const Type roll, const Type pitch, const Type yaw)
 Converts RPY extrinsic Tait-Bryan Euler angles (YPR intrinsic) to quaternion. More...
 
template<typename Type >
Type px4_ros2::quaternionToRoll (const Eigen::Quaternion< Type > &q)
 Convert quaternion to roll angle in extrinsic RPY order (intrinsic YPR) More...
 
template<typename Type >
Type px4_ros2::quaternionToPitch (const Eigen::Quaternion< Type > &q)
 Convert quaternion to pitch angle in extrinsic RPY order (intrinsic YPR) More...
 
template<typename Type >
Type px4_ros2::quaternionToYaw (const Eigen::Quaternion< Type > &q)
 Convert quaternion to yaw angle in extrinsic RPY order (intrinsic YPR) More...
 

Detailed Description

All rotations and axis systems follow the right-hand rule

Euler angles follow the convention of a 1-2-3 extrinsic Tait-Bryan rotation sequence. In order to go from frame 1 to frame 2 we apply the following rotations consecutively. 1) We rotate about our fixed X axis by an angle of "roll" 2) We rotate about our fixed Y axis by an angle of "pitch" 3) We rotate abour our fixed Z axis by an angle of "yaw"

Note that this convention is equivalent to that of a 3-2-1 intrinsic Tait-Bryan rotation sequence, i.e. 1) We rotate about our initial Z axis by an angle of "yaw" 2) We rotate about the newly created Y' axis by an angle of "pitch" 3) We rotate about the newly created X'' axis by an angle of "roll"

Function Documentation

◆ eulerRpyToQuaternion() [1/2]

template<typename Type >
Eigen::Quaternion<Type> px4_ros2::eulerRpyToQuaternion ( const Eigen::Matrix< Type, 3, 1 > &  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]

template<typename Type >
Eigen::Quaternion<Type> px4_ros2::eulerRpyToQuaternion ( const Type  roll,
const Type  pitch,
const Type  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.

◆ quaternionToEulerRpy()

template<typename Type >
Eigen::Matrix<Type, 3, 1> px4_ros2::quaternionToEulerRpy ( const Eigen::Quaternion< Type > &  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/2], [-pi, pi].

◆ quaternionToPitch()

template<typename Type >
Type px4_ros2::quaternionToPitch ( const Eigen::Quaternion< Type > &  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()

template<typename Type >
Type px4_ros2::quaternionToRoll ( const Eigen::Quaternion< Type > &  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()

template<typename Type >
Type px4_ros2::quaternionToYaw ( const Eigen::Quaternion< Type > &  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]

◆ wrapPi()

template<typename Type >
Type px4_ros2::wrapPi ( Type  angle)

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

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