AC_Fence: do not delete the FENCE_ENABLE parameter. It would confuse many users.

Talked to Randy about this. The consensus was not to delete the parameter
This commit is contained in:
Dr.-Ing. Amilcar do Carmo Lucas 2021-01-06 13:13:57 +01:00 committed by Peter Barker
parent 8d8753b14c
commit 15e95be7d7
2 changed files with 2 additions and 2 deletions

View File

@ -18,7 +18,7 @@ const AP_Param::GroupInfo AC_Fence::var_info[] = {
// @Description: Allows you to enable (1) or disable (0) the fence functionality // @Description: Allows you to enable (1) or disable (0) the fence functionality
// @Values: 0:Disabled,1:Enabled // @Values: 0:Disabled,1:Enabled
// @User: Standard // @User: Standard
//AP_GROUPINFO("ENABLE", 0, AC_Fence, _enabled, 0), AP_GROUPINFO("ENABLE", 0, AC_Fence, _enabled, 0),
// @Param: TYPE // @Param: TYPE
// @DisplayName: Fence Type // @DisplayName: Fence Type

View File

@ -177,6 +177,7 @@ private:
bool pre_arm_check_alt(const char* &fail_msg) const; bool pre_arm_check_alt(const char* &fail_msg) const;
// parameters // parameters
AP_Int8 _enabled; // fence enable/disable control
AP_Int8 _auto_enabled; // top level flag for auto enabling fence AP_Int8 _auto_enabled; // top level flag for auto enabling fence
AP_Int8 _enabled_fences; // bit mask holding which fences are enabled AP_Int8 _enabled_fences; // bit mask holding which fences are enabled
AP_Int8 _action; // recovery action specified by user AP_Int8 _action; // recovery action specified by user
@ -199,7 +200,6 @@ private:
float _circle_breach_distance; // distance beyond the circular fence float _circle_breach_distance; // distance beyond the circular fence
// other internal variables // other internal variables
bool _enabled; // fence enable/disable control
bool _floor_enabled; // fence floor is enabled bool _floor_enabled; // fence floor is enabled
float _home_distance; // distance from home in meters (provided by main code) float _home_distance; // distance from home in meters (provided by main code)
float _curr_alt; float _curr_alt;