@ -31,9 +31,11 @@ public:
// set the gyro bias in rad/sec
// set the gyro bias in rad/sec
void setGyroBias ( Vector3f & gyroBias ) ;
void setGyroBias ( Vector3f & gyroBias ) ;
// get yaw estimated and corresponding variance
// get yaw estimated and corresponding variance return false if
// return false if yaw estimation is inactive
// yaw estimation is inactive. n_clips will contain the number of
bool getYawData ( ftype & yaw , ftype & yawVariance ) const ;
// models which were *not* used to create the yaw and yawVariance
// return values.
bool getYawData ( ftype & yaw , ftype & yawVariance , uint8_t * n_clips = nullptr ) const ;
// get the length of the weighted average velocity innovation vector
// get the length of the weighted average velocity innovation vector
// return false if not available
// return false if not available
@ -136,4 +138,8 @@ private:
// Returns the probability for a selected model assuming a Gaussian error distribution
// Returns the probability for a selected model assuming a Gaussian error distribution
// Used by the Guassian Sum Filter to calculate the weightings when combining the outputs from the bank of EKF's
// Used by the Guassian Sum Filter to calculate the weightings when combining the outputs from the bank of EKF's
ftype gaussianDensity ( const uint8_t mdl_idx ) const ;
ftype gaussianDensity ( const uint8_t mdl_idx ) const ;
// number of models whose weights underflowed due to excessive
// innovation variances:
uint8_t n_clips ;
} ;
} ;