mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-23 09:08:30 -04:00
AC_Fence: shorten calculation of return value
This commit is contained in:
parent
b7b56b94a3
commit
0f486aeecb
@ -156,7 +156,7 @@ uint8_t AC_Fence::check_fence(float curr_alt)
|
||||
|
||||
// record that we have breached the upper limit
|
||||
record_breach(AC_FENCE_TYPE_ALT_MAX);
|
||||
ret = ret | AC_FENCE_TYPE_ALT_MAX;
|
||||
ret |= AC_FENCE_TYPE_ALT_MAX;
|
||||
|
||||
// create a backup fence 20m higher up
|
||||
_alt_max_backup = curr_alt + AC_FENCE_ALT_MAX_BACKUP_DISTANCE;
|
||||
@ -185,7 +185,7 @@ uint8_t AC_Fence::check_fence(float curr_alt)
|
||||
|
||||
// record that we have breached the circular distance limit
|
||||
record_breach(AC_FENCE_TYPE_CIRCLE);
|
||||
ret = ret | AC_FENCE_TYPE_CIRCLE;
|
||||
ret |= AC_FENCE_TYPE_CIRCLE;
|
||||
|
||||
// create a backup fence 20m further out
|
||||
_circle_radius_backup = _home_distance + AC_FENCE_CIRCLE_RADIUS_BACKUP_DISTANCE;
|
||||
@ -217,7 +217,7 @@ uint8_t AC_Fence::check_fence(float curr_alt)
|
||||
if ((_breached_fences & AC_FENCE_TYPE_POLYGON) == 0) {
|
||||
// record that we have breached the polygon
|
||||
record_breach(AC_FENCE_TYPE_POLYGON);
|
||||
ret = ret | AC_FENCE_TYPE_POLYGON;
|
||||
ret |= AC_FENCE_TYPE_POLYGON;
|
||||
}
|
||||
} else {
|
||||
// clear breach if present
|
||||
|
Loading…
Reference in New Issue
Block a user