From 6621b6983694d07f57c31c62afd18f165a9c7184 Mon Sep 17 00:00:00 2001 From: Iampete1 Date: Fri, 25 Sep 2020 22:17:13 +0100 Subject: [PATCH] Plane: log quadplane transision state --- ArduPlane/Log.cpp | 3 ++- ArduPlane/quadplane.cpp | 1 + ArduPlane/quadplane.h | 1 + 3 files changed, 4 insertions(+), 1 deletion(-) diff --git a/ArduPlane/Log.cpp b/ArduPlane/Log.cpp index 68b5437a2f..10ea63c92a 100644 --- a/ArduPlane/Log.cpp +++ b/ArduPlane/Log.cpp @@ -375,8 +375,9 @@ const struct LogStructure Plane::log_structure[] = { // @Field: CRt: climb rate // @Field: TMix: transition throttle mix value // @Field: Sscl: speed scalar for tailsitter control surfaces +// @Field: Trans: Transistion state { LOG_QTUN_MSG, sizeof(QuadPlane::log_QControl_Tuning), - "QTUN", "Qffffffeccff", "TimeUS,ThI,ABst,ThO,ThH,DAlt,Alt,BAlt,DCRt,CRt,TMix,Sscl", "s----mmmnn--", "F----00000-0" }, + "QTUN", "QffffffeccffB", "TimeUS,ThI,ABst,ThO,ThH,DAlt,Alt,BAlt,DCRt,CRt,TMix,Sscl,Trans", "s----mmmnn---", "F----00000-0-" }, // @LoggerMessage: AOA // @Description: Angle of attack and Side Slip Angle values diff --git a/ArduPlane/quadplane.cpp b/ArduPlane/quadplane.cpp index ec1520d219..c26ac15fe9 100644 --- a/ArduPlane/quadplane.cpp +++ b/ArduPlane/quadplane.cpp @@ -2941,6 +2941,7 @@ void QuadPlane::Log_Write_QControl_Tuning() climb_rate : int16_t(inertial_nav.get_velocity_z()), throttle_mix : attitude_control->get_throttle_mix(), speed_scaler : last_spd_scaler, + transition_state : static_cast(transition_state) }; plane.logger.WriteBlock(&pkt, sizeof(pkt)); diff --git a/ArduPlane/quadplane.h b/ArduPlane/quadplane.h index c6d2724a17..713328ca31 100644 --- a/ArduPlane/quadplane.h +++ b/ArduPlane/quadplane.h @@ -159,6 +159,7 @@ public: int16_t climb_rate; float throttle_mix; float speed_scaler; + uint8_t transition_state; }; MAV_TYPE get_mav_type(void) const;