mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 14:38:30 -04:00
AC_Fence: adjust fence sys_status failed based on position and parameters
This commit is contained in:
parent
6bcdab55d0
commit
c8e0ae6890
@ -588,6 +588,24 @@ bool AC_Fence::sys_status_failed() const
|
||||
return true;
|
||||
}
|
||||
}
|
||||
if (_enabled_fences & AC_FENCE_TYPE_CIRCLE) {
|
||||
if (_circle_radius < 0) {
|
||||
return true;
|
||||
}
|
||||
}
|
||||
if (_enabled_fences & AC_FENCE_TYPE_ALT_MAX) {
|
||||
if (_alt_max < 0.0f) {
|
||||
return true;
|
||||
}
|
||||
}
|
||||
if ((_enabled_fences & AC_FENCE_TYPE_CIRCLE) ||
|
||||
(_enabled_fences & AC_FENCE_TYPE_POLYGON)) {
|
||||
Vector2f position;
|
||||
if (!_ahrs.get_relative_position_NE_home(position)) {
|
||||
// both these fence types require position
|
||||
return true;
|
||||
}
|
||||
}
|
||||
|
||||
return false;
|
||||
}
|
||||
|
Loading…
Reference in New Issue
Block a user