AP_NavEKF: reorder declation to fix compiler warning

No functional change
This commit is contained in:
Randy Mackay 2014-12-11 15:37:56 +09:00
parent ddda0d52ce
commit e581e81da5

View File

@ -368,6 +368,8 @@ NavEKF::NavEKF(const AP_AHRS *ahrs, AP_Baro &baro) :
_ahrs(ahrs),
_baro(baro),
state(*reinterpret_cast<struct state_elements *>(&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")),