mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-10 18:08:30 -04:00
APM: ensure fence_total is positive
thanks to David Buzz for the suggestion
This commit is contained in:
parent
989b799130
commit
1e6ce649ad
@ -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…
Reference in New Issue
Block a user