diff --git a/ArduPlane/Log.cpp b/ArduPlane/Log.cpp index 36b56a2ad4..30e9bb86c9 100644 --- a/ArduPlane/Log.cpp +++ b/ArduPlane/Log.cpp @@ -16,11 +16,15 @@ void Plane::Log_Write_Attitude(void) //Plane does not have the concept of navyaw. This is a placeholder. targets.z = 0; } - + if (quadplane.tailsitter_active() || quadplane.in_vtol_mode()) { // we need the attitude targets from the AC_AttitudeControl controller, as they - // account for the acceleration limits - targets = quadplane.attitude_control->get_att_target_euler_cd(); + // account for the acceleration limits. + // Also, for bodyframe roll input types, _attitude_target_euler_angle is not maintained + // since Euler angles are not used and it is a waste of cpu to compute them at the loop rate. + // Get them from the quaternion instead: + quadplane.attitude_control->get_attitude_target_quat().to_euler(targets.x, targets.y, targets.z); + targets *= degrees(100.0f); logger.Write_AttitudeView(*quadplane.ahrs_view, targets); } else { logger.Write_Attitude(ahrs, targets);