mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-03-03 04:03:59 -04:00
AP_Baro: don't notify the GCS of new pressure reference too often
This commit is contained in:
parent
e873ff1e5f
commit
840c9e65bb
@ -164,10 +164,18 @@ void AP_Baro::update_calibration()
|
||||
{
|
||||
for (uint8_t i=0; i<_num_sensors; i++) {
|
||||
if (healthy(i)) {
|
||||
sensors[i].ground_pressure.set_and_notify(get_pressure(i));
|
||||
sensors[i].ground_pressure.set(get_pressure(i));
|
||||
}
|
||||
float last_temperature = sensors[i].ground_temperature;
|
||||
sensors[i].ground_temperature.set_and_notify(get_calibration_temperature(i));
|
||||
sensors[i].ground_temperature.set(get_calibration_temperature(i));
|
||||
|
||||
// don't notify the GCS too rapidly or we flood the link
|
||||
uint32_t now = hal.scheduler->millis();
|
||||
if (now - _last_notify_ms > 10000) {
|
||||
sensors[i].ground_pressure.notify();
|
||||
sensors[i].ground_temperature.notify();
|
||||
_last_notify_ms = now;
|
||||
}
|
||||
if (fabsf(last_temperature - sensors[i].ground_temperature) > 3) {
|
||||
// reset _EAS2TAS to force it to recalculate. This happens
|
||||
// when a digital airspeed sensor comes online
|
||||
|
@ -158,6 +158,9 @@ private:
|
||||
DerivativeFilterFloat_Size7 _climb_rate_filter;
|
||||
bool _hil_mode:1;
|
||||
|
||||
// when did we last notify the GCS of new pressure reference?
|
||||
uint32_t _last_notify_ms;
|
||||
|
||||
void SimpleAtmosphere(const float alt, float &sigma, float &delta, float &theta);
|
||||
};
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user