// Attitude, velocity and position corrections are averaged across multiple prediction cycles between now and the anticipated time for the next measurement.
// Don't do averaging of quaternion state corrections if total angle change across predicted interval is going to exceed 0.1 rad
// Calculate the number of averaging frames left to go. This is required becasue magnetometer fusion is applied across three consecutive prediction cycles
floatgpsIncrStateDelta[10];// vector of corrections to attitude, velocity and position to be applied over the period between the current and next GPS measurement
floathgtIncrStateDelta[10];// vector of corrections to attitude, velocity and position to be applied over the period between the current and next height measurement
floatflowIncrStateDelta[10];// vector of corrections to attitude, velocity and position to be applied over the period between the current and next magnetometer measurement
floatmagIncrStateDelta[10];// vector of corrections to attitude, velocity and position to be applied over the period between the current and next magnetometer measurement
uint8_tgpsUpdateCount;// count of the number of minor state corrections using GPS data
uint8_tgpsUpdateCountMax;// limit on the number of minor state corrections using GPS data
floatgpsUpdateCountMaxInv;// floating point inverse of gpsFilterCountMax
floatR_LOS;// variance of optical flow rate measurements (rad/sec)^2
floatauxRngTestRatio;// square of range finder innovations divided by fail threshold used by main filter where >1.0 is a fail
Vector2fflowGyroBias;// bias error of optical flow sensor gyro output
floatmagIncrStateDelta[10];// vector of corrections to attitude, velocity and position to be applied over the period between the current and next magnetometer measurement
uint8_tflowUpdateCount;// count of the number of minor state corrections using optical flow data
uint8_tflowUpdateCountMax;// limit on the number of minor state corrections using optical flow data
floatflowUpdateCountMaxInv;// floating point inverse of flowUpdateCountMax
floatflowIncrStateDelta[10];// vector of corrections to attitude, velocity and position to be applied over the period between the current and next magnetometer measurement
boolnewDataRng;// true when new valid range finder data has arrived.
boolvelHoldMode;// true when holding velocity in optical flow mode when no flow measurements are available
boolvelHoldMode;// true when holding velocity in optical flow mode when no flow measurements are available
boollastHoldVelocity;// last value of holdVelocity
Vector2fheldVelNE;// velocity held when no aiding is available
uint16_t_msecFlowAvg;// average number of msec between synthetic sideslip measurements
// states held by optical flow fusion across time steps
// optical flow X,Y motion compensated rate measurements are fused across two time steps