AP_Baro: notify GCS of all barometer ground pressures

This commit is contained in:
Peter Barker 2018-10-10 13:02:48 +11:00 committed by Peter Barker
parent 4f35992049
commit d05ab1b983
1 changed files with 6 additions and 3 deletions

View File

@ -263,6 +263,11 @@ void AP_Baro::calibrate(bool save)
*/
void AP_Baro::update_calibration()
{
const uint32_t now = AP_HAL::millis();
const bool do_notify = now - _last_notify_ms > 10000;
if (do_notify) {
_last_notify_ms = now;
}
for (uint8_t i=0; i<_num_sensors; i++) {
if (healthy(i)) {
float corrected_pressure = get_pressure(i) + sensors[i].p_correction;
@ -270,10 +275,8 @@ void AP_Baro::update_calibration()
}
// don't notify the GCS too rapidly or we flood the link
uint32_t now = AP_HAL::millis();
if (now - _last_notify_ms > 10000) {
if (do_notify) {
sensors[i].ground_pressure.notify();
_last_notify_ms = now;
}
}