AP_TECS: log pitch limits

This commit is contained in:
Andrew Tridgell 2019-04-14 06:42:47 +10:00
parent 3c8ed3d8e1
commit 4fd3008b4e

View File

@ -1125,10 +1125,12 @@ void AP_TECS::update_pitch_throttle(int32_t hgt_dem_cm,
(double)_TAS_rate_dem,
(double)logging.SKE_weighting,
_flags_byte);
AP::logger().Write("TEC2", "TimeUS,KErr,PErr,EDelta,LF", "Qffff",
now,
(double)logging.SKE_error,
(double)logging.SPE_error,
(double)logging.SEB_delta,
(double)load_factor);
AP::logger().Write("TEC2", "TimeUS,KErr,PErr,EDelta,LF,PMax,PMin", "Qffffff",
now,
(double)logging.SKE_error,
(double)logging.SPE_error,
(double)logging.SEB_delta,
(double)load_factor,
(double)degrees(_PITCHmaxf),
(double)degrees(_PITCHminf));
}