mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-23 00:04:02 -04:00
Plane: call AHRS resetHeightDatum() on baro reset
this prevents the AMSL estimate from the EKF going off badly if we disarm at a high altitude
This commit is contained in:
parent
542aa4c9e0
commit
0089e98bb6
@ -124,6 +124,7 @@ void Plane::update_home()
|
|||||||
}
|
}
|
||||||
}
|
}
|
||||||
barometer.update_calibration();
|
barometer.update_calibration();
|
||||||
|
ahrs.resetHeightDatum();
|
||||||
}
|
}
|
||||||
|
|
||||||
void Plane::set_home_persistently(const Location &loc)
|
void Plane::set_home_persistently(const Location &loc)
|
||||||
|
Loading…
Reference in New Issue
Block a user