From 54cff29fc283c408a9b9a4154c52a685980b22a1 Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Fri, 2 Jan 2015 17:08:18 +0900 Subject: [PATCH] DataFlash: EKF logging uses nav_filter_status --- libraries/DataFlash/LogFile.cpp | 5 +++-- 1 file changed, 3 insertions(+), 2 deletions(-) diff --git a/libraries/DataFlash/LogFile.cpp b/libraries/DataFlash/LogFile.cpp index 0512f6cba0..00fd056078 100644 --- a/libraries/DataFlash/LogFile.cpp +++ b/libraries/DataFlash/LogFile.cpp @@ -982,7 +982,8 @@ void DataFlash_Class::Log_Write_EKF(AP_AHRS_NavEKF &ahrs, bool optFlowEnabled) Vector3f magVar; float tasVar; 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().getFilterFaults(faultStatus); 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), faults : (uint8_t)(faultStatus), timeouts : (uint8_t)(timeoutStatus), - solution : (uint8_t)(solutionStatus) + solution : (uint8_t)(solutionStatus.value) }; WriteBlock(&pkt4, sizeof(pkt4));