Sub: update baro calibration even if armed

This is harmless and prevents a "bounce-back" effect when the depth
is badly calibrated. This can happen when rebooting the vehicle underwater
without a proper depth calibration.
This commit is contained in:
Willian Galvani 2022-09-27 09:04:53 -03:00
parent bd364b6169
commit 232083c4d2
1 changed files with 1 additions and 1 deletions

View File

@ -6,7 +6,7 @@ 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) {
if(barometer.get_altitude() > 0) {
barometer.update_calibration();
}