mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-06 07:58:28 -04:00
AC_Fence: reset fences breach on disable
Also rename enable function parameter
This commit is contained in:
parent
c25bd13b78
commit
93fdbf1573
libraries/AC_Fence
@ -97,6 +97,14 @@ AC_Fence::AC_Fence(const AP_AHRS& ahrs, const AP_InertialNav& inav) :
|
||||
}
|
||||
}
|
||||
|
||||
void AC_Fence::enable(bool value)
|
||||
{
|
||||
_enabled = value;
|
||||
if (!value) {
|
||||
clear_breach(AC_FENCE_TYPE_ALT_MAX | AC_FENCE_TYPE_CIRCLE | AC_FENCE_TYPE_POLYGON);
|
||||
}
|
||||
}
|
||||
|
||||
/// get_enabled_fences - returns bitmask of enabled fences
|
||||
uint8_t AC_Fence::get_enabled_fences() const
|
||||
{
|
||||
|
@ -40,7 +40,7 @@ public:
|
||||
AC_Fence(const AP_AHRS& ahrs, const AP_InertialNav& inav);
|
||||
|
||||
/// enable - allows fence to be enabled/disabled. Note: this does not update the eeprom saved value
|
||||
void enable(bool true_false) { _enabled = true_false; }
|
||||
void enable(bool value);
|
||||
|
||||
/// enabled - returns true if fence is enabled
|
||||
bool enabled() const { return _enabled; }
|
||||
|
Loading…
Reference in New Issue
Block a user