mirror of https://github.com/ArduPilot/ardupilot
Tools: change NET_ENABLED to NET_ENABLE
This commit is contained in:
parent
e503bcc23f
commit
281424829e
|
@ -6653,7 +6653,7 @@ Brakes have negligible effect (with=%0.2fm without=%0.2fm delta=%0.2fm)
|
|||
"SCR_ENABLE": 1,
|
||||
"SCR_VM_I_COUNT": 1000000,
|
||||
"SIM_SPEEDUP": 20,
|
||||
"NET_ENABLED": 1,
|
||||
"NET_ENABLE": 1,
|
||||
})
|
||||
|
||||
self.reboot_sitl()
|
||||
|
@ -6687,7 +6687,7 @@ Brakes have negligible effect (with=%0.2fm without=%0.2fm delta=%0.2fm)
|
|||
"SCR_ENABLE": 1,
|
||||
"SCR_VM_I_COUNT": 1000000,
|
||||
"SIM_SPEEDUP": 20,
|
||||
"NET_ENABLED": 1,
|
||||
"NET_ENABLE": 1,
|
||||
"SERIAL5_PROTOCOL": 48,
|
||||
})
|
||||
|
||||
|
|
|
@ -4260,7 +4260,7 @@ class TestSuite(ABC):
|
|||
"""Download latest log over network port"""
|
||||
self.context_push()
|
||||
self.set_parameters({
|
||||
"NET_ENABLED": 1,
|
||||
"NET_ENABLE": 1,
|
||||
"LOG_DISARMED": 1,
|
||||
"LOG_DARM_RATEMAX": 1, # make small logs
|
||||
# UDP client
|
||||
|
|
Loading…
Reference in New Issue