From 6a90257d2a6ea302f13d5336fd9f5898918ba912 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Fri, 31 Mar 2017 10:37:47 +1100 Subject: [PATCH] Plane: fixed attitude logging for tailsitters --- ArduPlane/Log.cpp | 6 +++++- 1 file changed, 5 insertions(+), 1 deletion(-) diff --git a/ArduPlane/Log.cpp b/ArduPlane/Log.cpp index 9c5a1fc84f..c7db4badd4 100644 --- a/ArduPlane/Log.cpp +++ b/ArduPlane/Log.cpp @@ -162,7 +162,11 @@ void Plane::Log_Write_Attitude(void) targets.y = nav_pitch_cd; targets.z = 0; //Plane does not have the concept of navyaw. This is a placeholder. - DataFlash.Log_Write_Attitude(ahrs, targets); + if (quadplane.tailsitter_active()) { + DataFlash.Log_Write_AttitudeView(*quadplane.ahrs_view, targets); + } else { + DataFlash.Log_Write_Attitude(ahrs, targets); + } if (quadplane.in_vtol_mode() || quadplane.in_assisted_flight()) { // log quadplane PIDs separately from fixed wing PIDs DataFlash.Log_Write_PID(LOG_PIQR_MSG, quadplane.attitude_control->get_rate_roll_pid().get_pid_info());