Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Use NET_ENABLE instead of NET_ENABLED for consistency with other _ENABLE parameters #26562

Merged
merged 4 commits into from
Mar 20, 2024
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
4 changes: 2 additions & 2 deletions Tools/autotest/rover.py
Original file line number Diff line number Diff line change
Expand Up @@ -6654,7 +6654,7 @@ def NetworkingWebServer(self):
"SCR_ENABLE": 1,
"SCR_VM_I_COUNT": 1000000,
"SIM_SPEEDUP": 20,
"NET_ENABLED": 1,
"NET_ENABLE": 1,
})

self.reboot_sitl()
Expand Down Expand Up @@ -6688,7 +6688,7 @@ def NetworkingWebServerPPP(self):
"SCR_ENABLE": 1,
"SCR_VM_I_COUNT": 1000000,
"SIM_SPEEDUP": 20,
"NET_ENABLED": 1,
"NET_ENABLE": 1,
"SERIAL5_PROTOCOL": 48,
})

Expand Down
2 changes: 1 addition & 1 deletion Tools/autotest/vehicle_test_suite.py
Original file line number Diff line number Diff line change
Expand Up @@ -4371,7 +4371,7 @@ def TestLogDownloadMAVProxyNetwork(self, upload_logs=False):
"""Download latest log over network port"""
self.context_push()
self.set_parameters({
"NET_ENABLED": 1,
"NET_ENABLE": 1,
"LOG_DISARMED": 0,
"LOG_DARM_RATEMAX": 1, # make small logs
# UDP client
Expand Down
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
NET_ENABLED 1
NET_ENABLE 1
NET_OPTIONS 1

# enable hw flow control
Expand Down
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
NET_ENABLED 1
NET_ENABLE 1
NET_OPTIONS 1

# enable hw flow control
Expand Down
4 changes: 2 additions & 2 deletions libraries/AP_Networking/AP_Networking.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -32,13 +32,13 @@ extern const AP_HAL::HAL& hal;
#endif

const AP_Param::GroupInfo AP_Networking::var_info[] = {
// @Param: ENABLED
// @Param: ENABLE
// @DisplayName: Networking Enable
// @Description: Networking Enable
// @Values: 0:Disable,1:Enable
// @RebootRequired: True
// @User: Advanced
AP_GROUPINFO_FLAGS("ENABLED", 1, AP_Networking, param.enabled, 0, AP_PARAM_FLAG_ENABLE),
AP_GROUPINFO_FLAGS("ENABLE", 1, AP_Networking, param.enabled, 0, AP_PARAM_FLAG_ENABLE),

#if AP_NETWORKING_CONTROLS_HOST_IP_SETTINGS_ENABLED
// @Group: IPADDR
Expand Down
Loading