mirror of https://github.com/ArduPilot/ardupilot
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:
parent
bd364b6169
commit
232083c4d2
|
@ -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();
|
||||
}
|
||||
|
||||
|
|
Loading…
Reference in New Issue