|
|
@ -432,10 +432,10 @@ private: |
|
|
|
AP_Int8 _flowUse; // Controls if the optical flow data is fused into the main navigation estimator and/or the terrain estimator.
|
|
|
|
AP_Int8 _flowUse; // Controls if the optical flow data is fused into the main navigation estimator and/or the terrain estimator.
|
|
|
|
AP_Int16 _mag_ef_limit; // limit on difference between WMM tables and learned earth field.
|
|
|
|
AP_Int16 _mag_ef_limit; // limit on difference between WMM tables and learned earth field.
|
|
|
|
AP_Float _hrt_filt_freq; // frequency of output observer height rate complementary filter in Hz
|
|
|
|
AP_Float _hrt_filt_freq; // frequency of output observer height rate complementary filter in Hz
|
|
|
|
AP_Int8 _gsfRunMask; // mask controlling which EKF3 instances run a separate EKF-GSF yaw estimator
|
|
|
|
AP_Int8 _gsfRunMask; // mask controlling which EKF2 instances run a separate EKF-GSF yaw estimator
|
|
|
|
AP_Int8 _gsfUseMask; // mask controlling which EKF3 instances will use EKF-GSF yaw estimator data to assit with yaw resets
|
|
|
|
AP_Int8 _gsfUseMask; // mask controlling which EKF2 instances will use EKF-GSF yaw estimator data to assit with yaw resets
|
|
|
|
AP_Int16 _gsfResetDelay; // number of mSec from loss of navigation to requesting a reset using EKF-GSF yaw estimator data
|
|
|
|
AP_Int16 _gsfResetDelay; // number of mSec from loss of navigation to requesting a reset using EKF-GSF yaw estimator data
|
|
|
|
AP_Int8 _gsfResetMaxCount; // maximum number of times the EKF3 is allowed to reset it's yaw to the EKF-GSF estimate
|
|
|
|
AP_Int8 _gsfResetMaxCount; // maximum number of times the EKF2 is allowed to reset it's yaw to the EKF-GSF estimate
|
|
|
|
|
|
|
|
|
|
|
|
// Possible values for _flowUse
|
|
|
|
// Possible values for _flowUse
|
|
|
|
#define FLOW_USE_NONE 0 |
|
|
|
#define FLOW_USE_NONE 0 |
|
|
|