Browse Source

GeoFence: fixed default return altitude units

off by 100x!
mission-4.1.18
Andrew Tridgell 13 years ago
parent
commit
21f06f8a39
  1. 2
      ArduPlane/geofence.pde

2
ArduPlane/geofence.pde

@ -261,7 +261,7 @@ static void geofence_check(bool altitude_check_only) @@ -261,7 +261,7 @@ static void geofence_check(bool altitude_check_only)
// min and max
if (g.fence_minalt >= g.fence_maxalt) {
// invalid min/max, use RTL_altitude
guided_WP.alt = home.alt + (g.RTL_altitude * 100);
guided_WP.alt = home.alt + g.RTL_altitude;
} else {
guided_WP.alt = home.alt + 100*(g.fence_minalt + g.fence_maxalt)/2;
}

Loading…
Cancel
Save