Browse Source

APM: ensure fence_total is positive

thanks to David Buzz for the suggestion
mission-4.1.18
Andrew Tridgell 13 years ago
parent
commit
b4134de550
  1. 4
      ArduPlane/geofence.pde

4
ArduPlane/geofence.pde

@ -89,6 +89,10 @@ static void geofence_load(void) @@ -89,6 +89,10 @@ static void geofence_load(void)
}
}
if (g.fence_total < 0) {
g.fence_total.set(0);
}
for (i=0; i<g.fence_total; i++) {
geofence_state->boundary[i] = get_fence_point_with_index(i);
}

Loading…
Cancel
Save