mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-26 18:48:30 -04:00
AP_NavEKF: move logging in from AP_Logger
This commit is contained in:
parent
2273ffb267
commit
9e0f525f69
25
libraries/AP_NavEKF/AP_Nav_Common.cpp
Normal file
25
libraries/AP_NavEKF/AP_Nav_Common.cpp
Normal file
@ -0,0 +1,25 @@
|
||||
#include "AP_Nav_Common.h"
|
||||
|
||||
#include <AP_HAL/AP_HAL.h>
|
||||
#include <AP_Logger/AP_Logger.h>
|
||||
|
||||
/*
|
||||
write an EKF timing message
|
||||
*/
|
||||
void Log_EKF_Timing(const char *name, uint64_t time_us, const struct ekf_timing &timing)
|
||||
{
|
||||
AP::logger().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);
|
||||
}
|
@ -16,6 +16,8 @@
|
||||
*/
|
||||
#pragma once
|
||||
|
||||
#include <stdint.h>
|
||||
|
||||
union nav_filter_status {
|
||||
struct {
|
||||
bool attitude : 1; // 0 - true if attitude estimate is valid
|
||||
@ -73,3 +75,4 @@ struct ekf_timing {
|
||||
float delVelDT_max;
|
||||
float delVelDT_min;
|
||||
};
|
||||
void Log_EKF_Timing(const char *name, uint64_t time_us, const struct ekf_timing &timing);
|
||||
|
Loading…
Reference in New Issue
Block a user