AP_Baro: accumulate altitude drift in place of raw calc

currently we set drift based on current boot time.  If you want to introduce it at some stage in a flight the baro alt will suddenly jump based on how long you've been up.

Instead, accumulate a delta
This commit is contained in:
Peter Barker 2024-04-29 14:30:27 +10:00 committed by Peter Barker
parent f5b062562a
commit 527e621a57
2 changed files with 7 additions and 1 deletions

View File

@ -66,7 +66,11 @@ void AP_Baro_SITL::_timer()
return; return;
} }
sim_alt += _sitl->baro[_instance].drift * now * 0.001f; const auto drift_delta_t_ms = now - last_drift_delta_t_ms;
last_drift_delta_t_ms = now;
total_alt_drift += _sitl->baro[_instance].drift * drift_delta_t_ms * 0.001f;
sim_alt += total_alt_drift;
sim_alt += _sitl->baro[_instance].noise * rand_float(); sim_alt += _sitl->baro[_instance].noise * rand_float();
// add baro glitch // add baro glitch

View File

@ -48,5 +48,7 @@ private:
float _recent_press; float _recent_press;
float _last_altitude; float _last_altitude;
uint32_t last_drift_delta_t_ms; // allows for integration of drift over time
float total_alt_drift; // integrated altitude drift in metres
}; };
#endif // AP_SIM_BARO_ENABLED #endif // AP_SIM_BARO_ENABLED