mirror of https://github.com/ArduPilot/ardupilot
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
0c2ea764ce
commit
e981966640
|
@ -126,6 +126,7 @@ void Plane::update_home()
|
|||
}
|
||||
}
|
||||
barometer.update_calibration();
|
||||
ahrs.resetHeightDatum();
|
||||
}
|
||||
|
||||
void Plane::set_home_persistently(const Location &loc)
|
||||
|
|
Loading…
Reference in New Issue