mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-24 09:38:29 -04:00
TECS: support for units on fields
This commit is contained in:
parent
6ed0d645a3
commit
22f1b5ed6f
@ -1076,22 +1076,27 @@ void AP_TECS::update_pitch_throttle(int32_t hgt_dem_cm,
|
|||||||
_update_pitch();
|
_update_pitch();
|
||||||
|
|
||||||
// log to DataFlash
|
// log to DataFlash
|
||||||
DataFlash_Class::instance()->Log_Write("TECS", "TimeUS,h,dh,hdem,dhdem,spdem,sp,dsp,ith,iph,th,ph,dspdem,w,f", "QfffffffffffffB",
|
DataFlash_Class::instance()->Log_Write(
|
||||||
now,
|
"TECS",
|
||||||
(double)_height,
|
"TimeUS,h,dh,hdem,dhdem,spdem,sp,dsp,ith,iph,th,ph,dspdem,w,f",
|
||||||
(double)_climb_rate,
|
"smnmnnnn----o--",
|
||||||
(double)_hgt_dem_adj,
|
"F0000000----0--",
|
||||||
(double)_hgt_rate_dem,
|
"QfffffffffffffB",
|
||||||
(double)_TAS_dem_adj,
|
now,
|
||||||
(double)_TAS_state,
|
(double)_height,
|
||||||
(double)_vel_dot,
|
(double)_climb_rate,
|
||||||
(double)_integTHR_state,
|
(double)_hgt_dem_adj,
|
||||||
(double)_integSEB_state,
|
(double)_hgt_rate_dem,
|
||||||
(double)_throttle_dem,
|
(double)_TAS_dem_adj,
|
||||||
(double)_pitch_dem,
|
(double)_TAS_state,
|
||||||
(double)_TAS_rate_dem,
|
(double)_vel_dot,
|
||||||
(double)logging.SKE_weighting,
|
(double)_integTHR_state,
|
||||||
_flags_byte);
|
(double)_integSEB_state,
|
||||||
|
(double)_throttle_dem,
|
||||||
|
(double)_pitch_dem,
|
||||||
|
(double)_TAS_rate_dem,
|
||||||
|
(double)logging.SKE_weighting,
|
||||||
|
_flags_byte);
|
||||||
DataFlash_Class::instance()->Log_Write("TEC2", "TimeUS,KErr,PErr,EDelta,LF", "Qffff",
|
DataFlash_Class::instance()->Log_Write("TEC2", "TimeUS,KErr,PErr,EDelta,LF", "Qffff",
|
||||||
now,
|
now,
|
||||||
(double)logging.SKE_error,
|
(double)logging.SKE_error,
|
||||||
|
Loading…
Reference in New Issue
Block a user