mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-21 23:33:57 -04:00
AP_NavEKF: add onboard LogMessage documentation
This commit is contained in:
parent
7f0e722a33
commit
051a7dc298
@ -6,6 +6,20 @@
|
||||
/*
|
||||
write an EKF timing message
|
||||
*/
|
||||
|
||||
// @LoggerMessage: NKT,XKT
|
||||
// @Description: EKF timing information
|
||||
// @Field: TimeUS: microseconds since system startup
|
||||
// @Field: C: EKF core this message instance applies to
|
||||
// @Field: Cnt: count of samples used to create this message
|
||||
// @Field: IMUMin: smallest IMU sample interval
|
||||
// @Field: IMUMax: largest IMU sample interval
|
||||
// @Field: EKFMin: low-passed achieved average time step rate for the EKF (minimum)
|
||||
// @Field: EKFMax: low-passed achieved average time step rate for the EKF (maximum)
|
||||
// @Field: AngMin: accumulated measurement time interval for the delta angle (minimum)
|
||||
// @Field: AngMax: accumulated measurement time interval for the delta angle (maximum)
|
||||
// @Field: VMin: accumulated measurement time interval for the delta velocity (minimum)
|
||||
// @Field: VMax: accumulated measurement time interval for the delta velocity (maximum)
|
||||
void Log_EKF_Timing(const char * name, const uint8_t core, uint64_t time_us, const struct ekf_timing &timing)
|
||||
{
|
||||
AP::logger().Write(
|
||||
|
Loading…
Reference in New Issue
Block a user