AC_Fence: shorten calculation of return value

This commit is contained in:
murata 2016-12-14 23:59:20 +09:00 committed by Randy Mackay
parent b7b56b94a3
commit 0f486aeecb

View File

@ -156,7 +156,7 @@ uint8_t AC_Fence::check_fence(float curr_alt)
// record that we have breached the upper limit // record that we have breached the upper limit
record_breach(AC_FENCE_TYPE_ALT_MAX); 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 // create a backup fence 20m higher up
_alt_max_backup = curr_alt + AC_FENCE_ALT_MAX_BACKUP_DISTANCE; _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 that we have breached the circular distance limit
record_breach(AC_FENCE_TYPE_CIRCLE); record_breach(AC_FENCE_TYPE_CIRCLE);
ret = ret | AC_FENCE_TYPE_CIRCLE; ret |= AC_FENCE_TYPE_CIRCLE;
// create a backup fence 20m further out // create a backup fence 20m further out
_circle_radius_backup = _home_distance + AC_FENCE_CIRCLE_RADIUS_BACKUP_DISTANCE; _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) { if ((_breached_fences & AC_FENCE_TYPE_POLYGON) == 0) {
// record that we have breached the polygon // record that we have breached the polygon
record_breach(AC_FENCE_TYPE_POLYGON); record_breach(AC_FENCE_TYPE_POLYGON);
ret = ret | AC_FENCE_TYPE_POLYGON; ret |= AC_FENCE_TYPE_POLYGON;
} }
} else { } else {
// clear breach if present // clear breach if present