Plane: log Qassist state

This commit is contained in:
Iampete1 2020-11-16 17:28:09 +00:00 committed by Andrew Tridgell
parent 5385f25868
commit c03de6bdbe
3 changed files with 6 additions and 3 deletions

View File

@ -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

View File

@ -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<uint8_t>(transition_state)
transition_state : static_cast<uint8_t>(transition_state),
assist : assisted_flight,
};
plane.logger.WriteBlock(&pkt, sizeof(pkt));

View File

@ -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;