Function navtk::navutils::rpy_to_dcm
Defined in File navigation.hpp
Function Documentation
-
Matrix3 navtk::navutils::rpy_to_dcm(const Vector3 &rpy)
Converts from Euler angles to a DCM.
This function calculates a
dcmthat rotates a vector from frame B to frame A ( \(\textbf{C}_\text{B}^\text{A}\)), when provided the yaw, pitch, and roll that correspond to a 3-2-1 frame rotation sequence frame A to frame B as follows:Rotate frame A about third axis of frame A by value of yaw to yield intermediate frame 1
Rotate intermediate frame 1 about its second axis by value of pitch to yield intermediate frame 2
Rotate intermediate frame 2 about its first axis by value of roll to yield frame B
Example: It is common to use Euler angles to describe the attitude of an aircraft relative to a local-level NED frame. In this case, “frame A” is the NED frame. Define the aircraft axes as nose-right wing-down (through the belly). Note that if the aircraft is flying straight and level heading north, then its axes are exactly aligned with the NED axes. To rotate from the NED axes to the actual aircraft attitude, imagine the aircraft starting aligned with NED, perform a yaw rotation about the down axis, a pitch rotation about (new) aircraft pitch axis, and then a roll rotation about the (new) aircraft roll axis. This is a commonly-used approach for using yaw/pitch/roll Euler angles to describe attitude of moving vehicles. In this example, the output
dcmmatrix is \(\textbf{C}_\text{P}^\text{NED}\), where \(\text{P}\) is the aircraft (“Platform”) attitude.Note that the yaw, pitch, and roll as defined above are expressed in a vector with the ordering [roll, pitch, yaw].
- Parameters
rpy – Euler angles [roll pitch yaw] (radians) that describe a frame rotation from frame A to frame B
- Returns
Direction cosine matrix ( \(\textbf{C}_\text{B}^\text{A}\)).