Sub: update calibration if reading is above water level

This commit is contained in:
Willian Galvani 2019-09-05 13:32:42 -03:00 committed by Andrew Tridgell
parent 5c00aa5921
commit c660ad8a9a
1 changed files with 5 additions and 0 deletions

View File

@ -4,6 +4,11 @@
void Sub::read_barometer()
{
barometer.update();
// If we are reading a positive altitude, the sensor needs calibration
// Even a few meters above the water we should have no significant depth reading
if(!motors.armed() && barometer.get_altitude() > 0) {
barometer.update_calibration();
}
if (ap.depth_sensor_present) {
sensor_health.depth = barometer.healthy(depth_sensor_idx);