mirror of https://github.com/ArduPilot/ardupilot
Sub: update calibration if reading is above water level
This commit is contained in:
parent
5c00aa5921
commit
c660ad8a9a
|
@ -4,6 +4,11 @@
|
||||||
void Sub::read_barometer()
|
void Sub::read_barometer()
|
||||||
{
|
{
|
||||||
barometer.update();
|
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) {
|
if (ap.depth_sensor_present) {
|
||||||
sensor_health.depth = barometer.healthy(depth_sensor_idx);
|
sensor_health.depth = barometer.healthy(depth_sensor_idx);
|
||||||
|
|
Loading…
Reference in New Issue