mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-09 17:34:01 -04:00
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
80c87f3d48
commit
89a585e378
@ -6,7 +6,7 @@ void Sub::read_barometer()
|
|||||||
barometer.update();
|
barometer.update();
|
||||||
// If we are reading a positive altitude, the sensor needs calibration
|
// 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
|
// 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();
|
barometer.update_calibration();
|
||||||
}
|
}
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user