Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

AP_NavEKF3: remove storedRange member variable if rangefinder measure… #27448

Merged
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
2 changes: 2 additions & 0 deletions libraries/AP_NavEKF3/AP_NavEKF3_core.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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();
Expand Down
2 changes: 2 additions & 0 deletions libraries/AP_NavEKF3/AP_NavEKF3_core.h
Original file line number Diff line number Diff line change
Expand Up @@ -1056,7 +1056,9 @@ class NavEKF3_core : public NavEKF_core_common
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)
Expand Down
Loading