Browse Source

Plane: Don't lock home altitude to AHRS origin

mission-4.1.18
Michael du Breuil 8 years ago committed by Andrew Tridgell
parent
commit
f183a2618f
  1. 9
      ArduPlane/commands.cpp

9
ArduPlane/commands.cpp

@ -137,16 +137,9 @@ void Plane::update_home() @@ -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…
Cancel
Save