mirror of https://github.com/ArduPilot/ardupilot
Plane: fixed home reset alt bias
this fixes a bug in the set of home alt while disarmed. The set had a circular dependency which could cause a large bias to build up between home alt and gps alt due to small fluctuations in barometer data Thanks to Nick Allen for spotting this
This commit is contained in:
parent
a38b030c41
commit
ff08de033e
|
@ -122,7 +122,13 @@ void Plane::update_home()
|
|||
}
|
||||
if (ahrs.home_is_set() && !ahrs.home_is_locked()) {
|
||||
Location loc;
|
||||
if(ahrs.get_position(loc)) {
|
||||
if(ahrs.get_position(loc) && gps.status() >= AP_GPS::GPS_OK_FIX_3D) {
|
||||
// we take the altitude directly from the GPS as we are
|
||||
// about to reset the baro calibration. We can't use AHRS
|
||||
// altitude or we can end up perpetuating a bias in
|
||||
// altitude, as AHRS alt depends on home alt, which means
|
||||
// we would have a circular dependency
|
||||
loc.alt = gps.location().alt;
|
||||
if (!AP::ahrs().set_home(loc)) {
|
||||
// silently fail
|
||||
}
|
||||
|
|
Loading…
Reference in New Issue