mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-21 16:18:29 -04:00
Plane: Don't lock home altitude to AHRS origin
This commit is contained in:
parent
7a1cbf76d3
commit
f183a2618f
@ -137,16 +137,9 @@ void Plane::update_home()
|
||||
}
|
||||
if (home_is_set == HOME_SET_NOT_LOCKED) {
|
||||
Location loc = gps.location();
|
||||
Location origin;
|
||||
// if an EKF origin is available then we leave home equal to
|
||||
// the height of that origin. This ensures that our relative
|
||||
// height calculations are using the same origin
|
||||
if (ahrs.get_origin(origin)) {
|
||||
loc.alt = origin.alt;
|
||||
}
|
||||
ahrs.set_home(loc);
|
||||
Log_Write_Home_And_Origin();
|
||||
GCS_MAVLINK::send_home_all(gps.location());
|
||||
GCS_MAVLINK::send_home_all(loc);
|
||||
}
|
||||
barometer.update_calibration();
|
||||
}
|
||||
|
Loading…
Reference in New Issue
Block a user