mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-24 01:28:29 -04:00
AP_TECS: log pitch limits
This commit is contained in:
parent
3c8ed3d8e1
commit
4fd3008b4e
@ -1125,10 +1125,12 @@ void AP_TECS::update_pitch_throttle(int32_t hgt_dem_cm,
|
|||||||
(double)_TAS_rate_dem,
|
(double)_TAS_rate_dem,
|
||||||
(double)logging.SKE_weighting,
|
(double)logging.SKE_weighting,
|
||||||
_flags_byte);
|
_flags_byte);
|
||||||
AP::logger().Write("TEC2", "TimeUS,KErr,PErr,EDelta,LF", "Qffff",
|
AP::logger().Write("TEC2", "TimeUS,KErr,PErr,EDelta,LF,PMax,PMin", "Qffffff",
|
||||||
now,
|
now,
|
||||||
(double)logging.SKE_error,
|
(double)logging.SKE_error,
|
||||||
(double)logging.SPE_error,
|
(double)logging.SPE_error,
|
||||||
(double)logging.SEB_delta,
|
(double)logging.SEB_delta,
|
||||||
(double)load_factor);
|
(double)load_factor,
|
||||||
|
(double)degrees(_PITCHmaxf),
|
||||||
|
(double)degrees(_PITCHminf));
|
||||||
}
|
}
|
||||||
|
Loading…
Reference in New Issue
Block a user