mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-26 01:33:56 -04:00
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:
parent
8d8753b14c
commit
15e95be7d7
@ -18,7 +18,7 @@ const AP_Param::GroupInfo AC_Fence::var_info[] = {
|
||||
// @Description: Allows you to enable (1) or disable (0) the fence functionality
|
||||
// @Values: 0:Disabled,1:Enabled
|
||||
// @User: Standard
|
||||
//AP_GROUPINFO("ENABLE", 0, AC_Fence, _enabled, 0),
|
||||
AP_GROUPINFO("ENABLE", 0, AC_Fence, _enabled, 0),
|
||||
|
||||
// @Param: TYPE
|
||||
// @DisplayName: Fence Type
|
||||
|
@ -177,6 +177,7 @@ private:
|
||||
bool pre_arm_check_alt(const char* &fail_msg) const;
|
||||
|
||||
// parameters
|
||||
AP_Int8 _enabled; // fence enable/disable control
|
||||
AP_Int8 _auto_enabled; // top level flag for auto enabling fence
|
||||
AP_Int8 _enabled_fences; // bit mask holding which fences are enabled
|
||||
AP_Int8 _action; // recovery action specified by user
|
||||
@ -199,7 +200,6 @@ private:
|
||||
float _circle_breach_distance; // distance beyond the circular fence
|
||||
|
||||
// other internal variables
|
||||
bool _enabled; // fence enable/disable control
|
||||
bool _floor_enabled; // fence floor is enabled
|
||||
float _home_distance; // distance from home in meters (provided by main code)
|
||||
float _curr_alt;
|
||||
|
Loading…
Reference in New Issue
Block a user