AP_Logger: move EKF timing logging out to EKF

This commit is contained in:
Peter Barker 2019-08-28 14:09:59 +10:00 committed by Andrew Tridgell
parent 9e0f525f69
commit 6d71ef5cf8
2 changed files with 0 additions and 27 deletions

View File

@ -23,7 +23,6 @@
class AP_Logger_Backend;
class AP_AHRS;
class AP_AHRS_View;
struct ekf_timing;
// do not do anything here apart from add stuff; maintaining older
// entries means log analysis is easier
@ -242,7 +241,6 @@ public:
void Write_Power(void);
void Write_AHRS2(AP_AHRS &ahrs);
void Write_POS(AP_AHRS &ahrs);
void Write_EKF_Timing(const char *name, uint64_t time_us, const struct ekf_timing &timing);
void Write_Radio(const mavlink_radio_t &packet);
void Write_Message(const char *message);
void Write_MessageF(const char *fmt, ...);

View File

@ -533,31 +533,6 @@ void AP_Logger::Write_POS(AP_AHRS &ahrs)
WriteBlock(&pkt, sizeof(pkt));
}
#if AP_AHRS_NAVEKF_AVAILABLE
/*
write an EKF timing message
*/
void AP_Logger::Write_EKF_Timing(const char *name, uint64_t time_us, const struct ekf_timing &timing)
{
Write(name,
"TimeUS,Cnt,IMUMin,IMUMax,EKFMin,EKFMax,AngMin,AngMax,VMin,VMax",
"QIffffffff",
time_us,
timing.count,
(double)timing.dtIMUavg_min,
(double)timing.dtIMUavg_max,
(double)timing.dtEKFavg_min,
(double)timing.dtEKFavg_max,
(double)timing.delAngDT_min,
(double)timing.delAngDT_max,
(double)timing.delVelDT_min,
(double)timing.delVelDT_max);
}
#endif
void AP_Logger::Write_Radio(const mavlink_radio_t &packet)
{
const struct log_Radio pkt{