mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-21 23:33:57 -04:00
AP_NavEKF3: remove storedRange member variable if rangefinder measurements disabled
This commit is contained in:
parent
3dff46b2b2
commit
ce48932f4d
@ -394,7 +394,9 @@ void NavEKF3_core::InitialiseVariables()
|
||||
storedGPS.reset();
|
||||
storedBaro.reset();
|
||||
storedTAS.reset();
|
||||
#if EK3_FEATURE_RANGEFINDER_MEASUREMENTS
|
||||
storedRange.reset();
|
||||
#endif
|
||||
storedOutput.reset();
|
||||
#if EK3_FEATURE_BEACON_FUSION
|
||||
rngBcn.storedRange.reset();
|
||||
|
@ -1056,7 +1056,9 @@ private:
|
||||
EKF_obs_buffer_t<mag_elements> storedMag; // Magnetometer data buffer
|
||||
EKF_obs_buffer_t<baro_elements> storedBaro; // Baro data buffer
|
||||
EKF_obs_buffer_t<tas_elements> storedTAS; // TAS data buffer
|
||||
#if EK3_FEATURE_RANGEFINDER_MEASUREMENTS
|
||||
EKF_obs_buffer_t<range_elements> storedRange; // Range finder data buffer
|
||||
#endif
|
||||
EKF_IMU_buffer_t<output_elements> storedOutput;// output state buffer
|
||||
Matrix3F prevTnb; // previous nav to body transformation used for INS earth rotation compensation
|
||||
ftype accNavMag; // magnitude of navigation accel - used to adjust GPS obs variance (m/s^2)
|
||||
|
Loading…
Reference in New Issue
Block a user