From f30ad1d2dce8f3762b7b1d4e7cd29c72456fca6a Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Sat, 15 May 2021 13:45:43 +1000 Subject: [PATCH] AP_Logger: log which RC channels are being overridden --- libraries/AP_Logger/AP_Logger.h | 2 +- libraries/AP_Logger/LogFile.cpp | 18 +++++++++++++----- libraries/AP_Logger/LogStructure.h | 3 ++- 3 files changed, 16 insertions(+), 7 deletions(-) diff --git a/libraries/AP_Logger/AP_Logger.h b/libraries/AP_Logger/AP_Logger.h index 65e111d5e4..8e1e0e4730 100644 --- a/libraries/AP_Logger/AP_Logger.h +++ b/libraries/AP_Logger/AP_Logger.h @@ -488,7 +488,7 @@ private: bool _armed; // state to help us not log unneccesary RCIN values: - bool seen_nonzero_rcin15_or_rcin16; + bool should_log_rcin2; void Write_Compass_instance(uint64_t time_us, uint8_t mag_instance); diff --git a/libraries/AP_Logger/LogFile.cpp b/libraries/AP_Logger/LogFile.cpp index 9f3ecb893f..7d76ee255d 100644 --- a/libraries/AP_Logger/LogFile.cpp +++ b/libraries/AP_Logger/LogFile.cpp @@ -149,20 +149,28 @@ void AP_Logger::Write_RCIN(void) }; WriteBlock(&pkt, sizeof(pkt)); + const uint16_t override_mask = rc().get_override_mask(); + // don't waste logging bandwidth if we haven't seen non-zero // channels 15/16: - if (!seen_nonzero_rcin15_or_rcin16) { - if (!values[14] && !values[15]) { - return; + if (!should_log_rcin2) { + if (values[14] || values[15]) { + should_log_rcin2 = true; + } else if (override_mask != 0) { + should_log_rcin2 = true; } - seen_nonzero_rcin15_or_rcin16 = true; + } + + if (!should_log_rcin2) { + return; } const struct log_RCIN2 pkt2{ LOG_PACKET_HEADER_INIT(LOG_RCIN2_MSG), time_us : AP_HAL::micros64(), chan15 : values[14], - chan16 : values[15] + chan16 : values[15], + override_mask : override_mask, }; WriteBlock(&pkt2, sizeof(pkt2)); } diff --git a/libraries/AP_Logger/LogStructure.h b/libraries/AP_Logger/LogStructure.h index 47b8da22ad..f42eb1c809 100644 --- a/libraries/AP_Logger/LogStructure.h +++ b/libraries/AP_Logger/LogStructure.h @@ -247,6 +247,7 @@ struct PACKED log_RCIN2 { uint64_t time_us; uint16_t chan15; uint16_t chan16; + uint16_t override_mask; }; struct PACKED log_RCOUT { @@ -1223,7 +1224,7 @@ LOG_STRUCTURE_FROM_GPS \ { LOG_RCIN_MSG, sizeof(log_RCIN), \ "RCIN", "QHHHHHHHHHHHHHH", "TimeUS,C1,C2,C3,C4,C5,C6,C7,C8,C9,C10,C11,C12,C13,C14", "sYYYYYYYYYYYYYY", "F--------------" }, \ { LOG_RCIN2_MSG, sizeof(log_RCIN2), \ - "RCI2", "QHH", "TimeUS,C15,C16", "sYY", "F--" }, \ + "RCI2", "QHHH", "TimeUS,C15,C16,OMask", "sYY-", "F---" }, \ { LOG_RCOUT_MSG, sizeof(log_RCOUT), \ "RCOU", "QHHHHHHHHHHHHHH", "TimeUS,C1,C2,C3,C4,C5,C6,C7,C8,C9,C10,C11,C12,C13,C14", "sYYYYYYYYYYYYYY", "F--------------" }, \ { LOG_RSSI_MSG, sizeof(log_RSSI), \