mirror of https://github.com/ArduPilot/ardupilot
AP_ADSB: revert default enable = 0
This commit is contained in:
parent
b5ec37b9d8
commit
282817eeb9
|
@ -49,10 +49,9 @@ const AP_Param::GroupInfo AP_ADSB::var_info[] = {
|
||||||
// @Description: Enable ADS-B
|
// @Description: Enable ADS-B
|
||||||
// @Values: 0:Disabled,1:Enabled
|
// @Values: 0:Disabled,1:Enabled
|
||||||
// @User: Standard
|
// @User: Standard
|
||||||
AP_GROUPINFO_FLAGS("ENABLE", 0, AP_ADSB, _enabled, 1, AP_PARAM_FLAG_ENABLE),
|
AP_GROUPINFO_FLAGS("ENABLE", 0, AP_ADSB, _enabled, 0, AP_PARAM_FLAG_ENABLE),
|
||||||
|
|
||||||
|
// index 1 is reserved - was BEHAVIOR
|
||||||
// index 2 is reserved - was BEHAVIOR
|
|
||||||
|
|
||||||
// @Param: LIST_MAX
|
// @Param: LIST_MAX
|
||||||
// @DisplayName: ADSB vehicle list size
|
// @DisplayName: ADSB vehicle list size
|
||||||
|
|
Loading…
Reference in New Issue