Mavlink receiver ODOMETRY fix code style

This commit is contained in:
Daniel Agar 2019-08-02 21:36:20 -04:00
parent b203bc15df
commit dcccbbe584
No known key found for this signature in database
GPG Key ID: FD3CBA98017A69DE

View File

@ -1160,7 +1160,7 @@ MavlinkReceiver::handle_message_odometry(mavlink_message_t *msg)
}
if (odom.child_frame_id == MAV_FRAME_BODY_FRD) { /* WRT to estimated vehicle body-fixed frame */
/* Get quaternion from the msg quaternion itself and build DCM matrix from it
/* Get quaternion from the msg quaternion itself and build DCM matrix from it
* Note that the msg quaternion represents the rotation of the msg frame to the msg child frame
* but rotates msg child frame *data* into the msg frame */
const matrix::Dcmf Rbl = matrix::Dcmf(matrix::Quatf(odometry.q));