mirror of https://github.com/ArduPilot/ardupilot
AP_NavEKF2: move log message metadata to be above the structure
This is the pattern we are adopting elsewhere to try to keep things related as much as possible.
This commit is contained in:
parent
c4a644100d
commit
f94f51d9d3
|
@ -5,6 +5,20 @@
|
||||||
#define LOG_IDS_FROM_NAVEKF2 \
|
#define LOG_IDS_FROM_NAVEKF2 \
|
||||||
LOG_NKT_MSG
|
LOG_NKT_MSG
|
||||||
|
|
||||||
|
|
||||||
|
// @LoggerMessage: NKT
|
||||||
|
// @Description: EKF2 timing information
|
||||||
|
// @Field: TimeUS: Time 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)
|
||||||
struct PACKED log_NKT {
|
struct PACKED log_NKT {
|
||||||
LOG_PACKET_HEADER;
|
LOG_PACKET_HEADER;
|
||||||
uint64_t time_us;
|
uint64_t time_us;
|
||||||
|
@ -20,20 +34,6 @@ struct PACKED log_NKT {
|
||||||
float delVelDT_max;
|
float delVelDT_max;
|
||||||
};
|
};
|
||||||
|
|
||||||
// @LoggerMessage: NKT
|
|
||||||
// @Description: EKF2 timing information
|
|
||||||
// @Field: TimeUS: Time 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)
|
|
||||||
|
|
||||||
#define LOG_STRUCTURE_FROM_NAVEKF2 \
|
#define LOG_STRUCTURE_FROM_NAVEKF2 \
|
||||||
{ LOG_NKT_MSG, sizeof(log_NKT), \
|
{ LOG_NKT_MSG, sizeof(log_NKT), \
|
||||||
"NKT", "QBIffffffff", "TimeUS,C,Cnt,IMUMin,IMUMax,EKFMin,EKFMax,AngMin,AngMax,VMin,VMax", "s#sssssssss", "F-000000000"},
|
"NKT", "QBIffffffff", "TimeUS,C,Cnt,IMUMin,IMUMax,EKFMin,EKFMax,AngMin,AngMax,VMin,VMax", "s#sssssssss", "F-000000000"},
|
||||||
|
|
Loading…
Reference in New Issue