diff --git a/ArduPlane/Log.cpp b/ArduPlane/Log.cpp index 85b88c7e66..8862992092 100644 --- a/ArduPlane/Log.cpp +++ b/ArduPlane/Log.cpp @@ -371,9 +371,10 @@ 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 +// @Field: Trn: Transistion state +// @Field: Ast: Q assist active state { LOG_QTUN_MSG, sizeof(QuadPlane::log_QControl_Tuning), - "QTUN", "QffffffeccffB", "TimeUS,ThI,ABst,ThO,ThH,DAlt,Alt,BAlt,DCRt,CRt,TMix,Sscl,Trans", "s----mmmnn---", "F----00000-0-" }, + "QTUN", "QffffffeccffBB", "TimeUS,ThI,ABst,ThO,ThH,DAlt,Alt,BAlt,DCRt,CRt,TMix,Sscl,Trn,Ast", "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 1b1d58b42f..b8e144684d 100644 --- a/ArduPlane/quadplane.cpp +++ b/ArduPlane/quadplane.cpp @@ -2946,7 +2946,8 @@ void QuadPlane::Log_Write_QControl_Tuning() climb_rate : int16_t(inertial_nav.get_velocity_z()), throttle_mix : attitude_control->get_throttle_mix(), speed_scaler : log_spd_scaler, - transition_state : static_cast(transition_state) + transition_state : static_cast(transition_state), + assist : assisted_flight, }; plane.logger.WriteBlock(&pkt, sizeof(pkt)); diff --git a/ArduPlane/quadplane.h b/ArduPlane/quadplane.h index 25829bb9ba..d21ac91203 100644 --- a/ArduPlane/quadplane.h +++ b/ArduPlane/quadplane.h @@ -163,6 +163,7 @@ public: float throttle_mix; float speed_scaler; uint8_t transition_state; + uint8_t assist; }; MAV_TYPE get_mav_type(void) const;