mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-23 08:13:56 -04:00
DataFlash: EKF logging uses nav_filter_status
This commit is contained in:
parent
f4d8bc586c
commit
54cff29fc2
@ -982,7 +982,8 @@ void DataFlash_Class::Log_Write_EKF(AP_AHRS_NavEKF &ahrs, bool optFlowEnabled)
|
|||||||
Vector3f magVar;
|
Vector3f magVar;
|
||||||
float tasVar;
|
float tasVar;
|
||||||
Vector2f offset;
|
Vector2f offset;
|
||||||
uint8_t faultStatus, timeoutStatus, solutionStatus;
|
uint8_t faultStatus, timeoutStatus;
|
||||||
|
nav_filter_status solutionStatus;
|
||||||
ahrs.get_NavEKF().getVariances(velVar, posVar, hgtVar, magVar, tasVar, offset);
|
ahrs.get_NavEKF().getVariances(velVar, posVar, hgtVar, magVar, tasVar, offset);
|
||||||
ahrs.get_NavEKF().getFilterFaults(faultStatus);
|
ahrs.get_NavEKF().getFilterFaults(faultStatus);
|
||||||
ahrs.get_NavEKF().getFilterTimeouts(timeoutStatus);
|
ahrs.get_NavEKF().getFilterTimeouts(timeoutStatus);
|
||||||
@ -1001,7 +1002,7 @@ void DataFlash_Class::Log_Write_EKF(AP_AHRS_NavEKF &ahrs, bool optFlowEnabled)
|
|||||||
offsetEast : (int8_t)(offset.y),
|
offsetEast : (int8_t)(offset.y),
|
||||||
faults : (uint8_t)(faultStatus),
|
faults : (uint8_t)(faultStatus),
|
||||||
timeouts : (uint8_t)(timeoutStatus),
|
timeouts : (uint8_t)(timeoutStatus),
|
||||||
solution : (uint8_t)(solutionStatus)
|
solution : (uint8_t)(solutionStatus.value)
|
||||||
};
|
};
|
||||||
WriteBlock(&pkt4, sizeof(pkt4));
|
WriteBlock(&pkt4, sizeof(pkt4));
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user