From 25a2c77782f078d55a96ed1c2d179dd07fae79ba Mon Sep 17 00:00:00 2001 From: Michael du Breuil Date: Wed, 20 Feb 2019 16:39:33 -0700 Subject: [PATCH] Plane: Fix not logging quadplane control, and over logging attitude control --- ArduPlane/quadplane.cpp | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/ArduPlane/quadplane.cpp b/ArduPlane/quadplane.cpp index e79aadea5e..48f2ca9341 100644 --- a/ArduPlane/quadplane.cpp +++ b/ArduPlane/quadplane.cpp @@ -1670,11 +1670,12 @@ void QuadPlane::motors_output(bool run_rate_controller) check_throttle_suppression(); motors->output(); - if (motors->armed() && motors->get_throttle() > 0) { + if (motors->armed() && motors->get_spool_mode() != AP_Motors::spool_up_down_mode::SHUT_DOWN) { plane.logger.Write_Rate(ahrs_view, *motors, *attitude_control, *pos_control); Log_Write_QControl_Tuning(); const uint32_t now = AP_HAL::millis(); if (now - last_ctrl_log_ms > 100) { + last_ctrl_log_ms = now; attitude_control->control_monitor_log(); } }