Browse Source

Plane: don't auto-update home and baro on large height change

if we land at a remote location with a different height we should not
update baro and home. This also prevents us updating baro and home if
we disarm in flight
mission-4.1.18
Andrew Tridgell 9 years ago
parent
commit
9e812d3bda
  1. 7
      ArduPlane/commands.cpp

7
ArduPlane/commands.cpp

@ -130,6 +130,13 @@ void Plane::init_home() @@ -130,6 +130,13 @@ void Plane::init_home()
*/
void Plane::update_home()
{
if (fabsf(barometer.get_altitude()) > 2) {
// don't auto-update if we have changed barometer altitude
// significantly. This allows us to cope with slow baro drift
// but not re-do home and the baro if we have changed height
// significantly
return;
}
if (home_is_set == HOME_SET_NOT_LOCKED) {
Location loc = gps.location();
Location origin;

Loading…
Cancel
Save