From a340d13d0145e082b4a84a622340dc7f76317629 Mon Sep 17 00:00:00 2001 From: Tom Pittenger Date: Fri, 24 Apr 2015 14:12:03 +0900 Subject: [PATCH] NavEKF: fix compile warning re member init order --- libraries/AP_NavEKF/AP_NavEKF.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/libraries/AP_NavEKF/AP_NavEKF.cpp b/libraries/AP_NavEKF/AP_NavEKF.cpp index 6ebad85366..26ac5d8dca 100644 --- a/libraries/AP_NavEKF/AP_NavEKF.cpp +++ b/libraries/AP_NavEKF/AP_NavEKF.cpp @@ -413,10 +413,10 @@ NavEKF::NavEKF(const AP_AHRS *ahrs, AP_Baro &baro, const RangeFinder &rng) : DCM33FlowMin(0.71f), // If Tbn(3,3) is less than this number, optical flow measurements will not be fused as tilt is too high. fScaleFactorPnoise(1e-10f), // Process noise added to focal length scale factor state variance at each time step flowTimeDeltaAvg_ms(100), // average interval between optical flow measurements (msec) - flowIntervalMax_ms(100), // maximum allowable time between flow fusion events gndEffectTO_ms(30000), // time in msec that baro ground effect compensation will timeout after initiation gndEffectBaroScaler(4.0f), // scaler applied to the barometer observation variance when operating in ground effect - gndEffectBaroTO_ms(5000) // time in msec that the baro measurement will be rejected if the gndEffectBaroVarLim has failed it + gndEffectBaroTO_ms(5000), // time in msec that the baro measurement will be rejected if the gndEffectBaroVarLim has failed it + flowIntervalMax_ms(100) // maximum allowable time between flow fusion events #if CONFIG_HAL_BOARD == HAL_BOARD_PX4 || CONFIG_HAL_BOARD == HAL_BOARD_VRBRAIN ,_perf_UpdateFilter(perf_alloc(PC_ELAPSED, "EKF_UpdateFilter")),