AP_TECS: Log input height demands.

This commit is contained in:
Samuel Tabor 2019-11-06 08:59:50 -05:00 committed by Andrew Tridgell
parent 494dcc6ba3
commit 27078bccda

View File

@ -1222,15 +1222,19 @@ void AP_TECS::update_pitch_throttle(int32_t hgt_dem_cm,
// @Field: PErr: difference between estimated potential energy and desired potential energy
// @Field: EDelta: current error in speed/balance weighting
// @Field: LF: aerodynamic load factor
AP::logger().WriteStreaming("TEC2", "TimeUS,pmax,pmin,KErr,PErr,EDelta,LF",
"s------",
"F------",
"Qffffff",
// @Field: hdem1: demanded height input
// @Field: hdem2: rate-limited height demand
AP::logger().WriteStreaming("TEC2", "TimeUS,pmax,pmin,KErr,PErr,EDelta,LF,hdem1,hdem2",
"s------mm",
"F--------",
"Qffffffff",
now,
(double)degrees(_PITCHmaxf),
(double)degrees(_PITCHminf),
(double)logging.SKE_error,
(double)logging.SPE_error,
(double)logging.SEB_delta,
(double)load_factor);
(double)load_factor,
(double)hgt_dem_cm*0.01,
(double)_hgt_dem);
}