mirror of https://github.com/ArduPilot/ardupilot
AC_Fence: params always use set method
This commit is contained in:
parent
e78d5cd793
commit
e141731146
|
@ -141,7 +141,7 @@ void AC_Fence::enable(bool value)
|
|||
} else if (!_enabled && value) {
|
||||
AP::logger().Write_Event(LogEvent::FENCE_ENABLE);
|
||||
}
|
||||
_enabled = value;
|
||||
_enabled.set(value);
|
||||
if (!value) {
|
||||
clear_breach(AC_FENCE_TYPE_ALT_MIN | AC_FENCE_TYPE_ALT_MAX | AC_FENCE_TYPE_CIRCLE | AC_FENCE_TYPE_POLYGON);
|
||||
disable_floor();
|
||||
|
|
|
@ -296,7 +296,7 @@ bool AC_PolyFence_loader::format()
|
|||
bool AC_PolyFence_loader::convert_to_new_storage()
|
||||
{
|
||||
// sanity check total
|
||||
_total = constrain_int16(_total, 0, max_items());
|
||||
_total.set(constrain_int16(_total, 0, max_items()));
|
||||
// FIXME: ensure the fence was closed and don't load it if it was not
|
||||
if (_total < 5) {
|
||||
// fence was invalid. Just format it and move on
|
||||
|
|
Loading…
Reference in New Issue