From e581e81da56dd4eb734ba5c9673cf51f209fd4ae Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Thu, 11 Dec 2014 15:37:56 +0900 Subject: [PATCH] AP_NavEKF: reorder declation to fix compiler warning No functional change --- libraries/AP_NavEKF/AP_NavEKF.cpp | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/libraries/AP_NavEKF/AP_NavEKF.cpp b/libraries/AP_NavEKF/AP_NavEKF.cpp index 3610810c13..a6de14ad42 100644 --- a/libraries/AP_NavEKF/AP_NavEKF.cpp +++ b/libraries/AP_NavEKF/AP_NavEKF.cpp @@ -368,6 +368,8 @@ NavEKF::NavEKF(const AP_AHRS *ahrs, AP_Baro &baro) : _ahrs(ahrs), _baro(baro), state(*reinterpret_cast(&states)), + onGround(true), // initialise assuming we are on ground + manoeuvring(false), // initialise assuming we are not maneouvring covTimeStepMax(0.07f), // maximum time (sec) between covariance prediction updates covDelAngMax(0.05f), // maximum delta angle between covariance prediction updates TASmsecMax(200), // maximum allowed interval between airspeed measurement updates @@ -375,9 +377,7 @@ NavEKF::NavEKF(const AP_AHRS *ahrs, AP_Baro &baro) : prevStaticMode(true), // staticMode from previous filter update yawAligned(false), // set true when heading or yaw angle has been aligned inhibitWindStates(true), // inhibit wind state updates on startup - inhibitMagStates(true), // inhibit magnetometer state updates on startup - onGround(true), // initialise assuming we are on ground - manoeuvring(false) // initialise assuming we are not maneouvring + inhibitMagStates(true) // inhibit magnetometer state updates on startup #if CONFIG_HAL_BOARD == HAL_BOARD_PX4 || CONFIG_HAL_BOARD == HAL_BOARD_VRBRAIN ,_perf_UpdateFilter(perf_alloc(PC_ELAPSED, "EKF_UpdateFilter")),