Browse Source

Sub: update calibration if reading is above water level

master
Willian Galvani 6 years ago committed by Jacob Walser
parent
commit
adcf0d398d
  1. 5
      ArduSub/sensors.cpp

5
ArduSub/sensors.cpp

@ -4,6 +4,11 @@ @@ -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);

Loading…
Cancel
Save