|
|
|
@ -1031,23 +1031,23 @@ void AP_TECS::update_pitch_throttle(int32_t hgt_dem_cm,
@@ -1031,23 +1031,23 @@ void AP_TECS::update_pitch_throttle(int32_t hgt_dem_cm,
|
|
|
|
|
// 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", |
|
|
|
|
now, |
|
|
|
|
_height, |
|
|
|
|
_climb_rate, |
|
|
|
|
_hgt_dem_adj, |
|
|
|
|
_hgt_rate_dem, |
|
|
|
|
_TAS_dem_adj, |
|
|
|
|
_TAS_state, |
|
|
|
|
_vel_dot, |
|
|
|
|
_integTHR_state, |
|
|
|
|
_integSEB_state, |
|
|
|
|
_throttle_dem, |
|
|
|
|
_pitch_dem, |
|
|
|
|
_TAS_rate_dem, |
|
|
|
|
logging.SKE_weighting, |
|
|
|
|
(double)_height, |
|
|
|
|
(double)_climb_rate, |
|
|
|
|
(double)_hgt_dem_adj, |
|
|
|
|
(double)_hgt_rate_dem, |
|
|
|
|
(double)_TAS_dem_adj, |
|
|
|
|
(double)_TAS_state, |
|
|
|
|
(double)_vel_dot, |
|
|
|
|
(double)_integTHR_state, |
|
|
|
|
(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", "Qfff", |
|
|
|
|
now, |
|
|
|
|
logging.SKE_error, |
|
|
|
|
logging.SPE_error, |
|
|
|
|
logging.SEB_delta); |
|
|
|
|
(double)logging.SKE_error, |
|
|
|
|
(double)logging.SPE_error, |
|
|
|
|
(double)logging.SEB_delta); |
|
|
|
|
} |
|
|
|
|