From f9ca319aadb45ed1176a50d4139ab570ead4576e Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Fri, 28 Feb 2025 09:48:18 +1100 Subject: [PATCH] Plane: log throttle throttle suppressed into STAT message --- ArduPlane/Log.cpp | 5 ++++- 1 file changed, 4 insertions(+), 1 deletion(-) diff --git a/ArduPlane/Log.cpp b/ArduPlane/Log.cpp index 184dfc611a..7fba411d46 100644 --- a/ArduPlane/Log.cpp +++ b/ArduPlane/Log.cpp @@ -210,6 +210,7 @@ struct PACKED log_Status { bool is_still; uint8_t stage; bool impact; + bool throttle_supressed; }; void Plane::Log_Write_Status() @@ -225,6 +226,7 @@ void Plane::Log_Write_Status() ,is_still : AP::ins().is_still() ,stage : static_cast(flight_stage) ,impact : crash_state.impact_detected + ,throttle_supressed : throttle_suppressed }; logger.WriteBlock(&pkt, sizeof(pkt)); @@ -382,8 +384,9 @@ const struct LogStructure Plane::log_structure[] = { // @Field: Still: True when vehicle is not moving in any axis // @Field: Stage: Current stage of the flight // @Field: Hit: True if impact is detected +// @Field: Sup: True if throttle is suppressed { LOG_STATUS_MSG, sizeof(log_Status), - "STAT", "QBfBBBBBB", "TimeUS,isFlying,isFlyProb,Armed,Safety,Crash,Still,Stage,Hit", "s--------", "F--------" , true }, + "STAT", "QBfBBBBBBB", "TimeUS,isFlying,isFlyProb,Armed,Safety,Crash,Still,Stage,Hit,Sup", "s---------", "F---------" , true }, // @LoggerMessage: QTUN // @Description: QuadPlane vertical tuning message