mirror of https://github.com/ArduPilot/ardupilot
AC_Avoid: hide params with enable flag
This commit is contained in:
parent
f78a09ba2a
commit
f5172cdecf
|
@ -35,7 +35,7 @@ const AP_Param::GroupInfo AC_Avoid::var_info[] = {
|
|||
// @Values: 0:None,1:UseFence,2:UseProximitySensor,3:UseFence and UseProximitySensor,4:UseBeaconFence,7:All
|
||||
// @Bitmask: 0:UseFence,1:UseProximitySensor,2:UseBeaconFence
|
||||
// @User: Standard
|
||||
AP_GROUPINFO("ENABLE", 1, AC_Avoid, _enabled, AC_AVOID_DEFAULT),
|
||||
AP_GROUPINFO_FLAGS("ENABLE", 1, AC_Avoid, _enabled, AC_AVOID_DEFAULT, AP_PARAM_FLAG_ENABLE),
|
||||
|
||||
// @Param{Copter}: ANGLE_MAX
|
||||
// @DisplayName: Avoidance max lean angle in non-GPS flight modes
|
||||
|
|
Loading…
Reference in New Issue