mirror of https://github.com/ArduPilot/ardupilot
autotest: set SIM_SPEEDUP=1 for log download
this may make the test more reliable
This commit is contained in:
parent
a79569ccf3
commit
dc97899ce8
|
@ -4356,6 +4356,7 @@ class TestSuite(ABC):
|
||||||
filename = "MAVProxy-downloaded-log.BIN"
|
filename = "MAVProxy-downloaded-log.BIN"
|
||||||
mavproxy = self.start_mavproxy()
|
mavproxy = self.start_mavproxy()
|
||||||
self.mavproxy_load_module(mavproxy, 'log')
|
self.mavproxy_load_module(mavproxy, 'log')
|
||||||
|
self.set_parameter('SIM_SPEEDUP', 1)
|
||||||
mavproxy.send("log list\n")
|
mavproxy.send("log list\n")
|
||||||
mavproxy.expect("numLogs")
|
mavproxy.expect("numLogs")
|
||||||
self.wait_heartbeat()
|
self.wait_heartbeat()
|
||||||
|
@ -4407,6 +4408,9 @@ class TestSuite(ABC):
|
||||||
"NET_P4_IP3": 0,
|
"NET_P4_IP3": 0,
|
||||||
})
|
})
|
||||||
self.reboot_sitl()
|
self.reboot_sitl()
|
||||||
|
|
||||||
|
self.set_parameter('SIM_SPEEDUP', 1)
|
||||||
|
|
||||||
endpoints = [('UDPClient', ':16001') ,
|
endpoints = [('UDPClient', ':16001') ,
|
||||||
('UDPServer', 'udpout:127.0.0.1:16002'),
|
('UDPServer', 'udpout:127.0.0.1:16002'),
|
||||||
('TCPClient', 'tcpin:0.0.0.0:16003'),
|
('TCPClient', 'tcpin:0.0.0.0:16003'),
|
||||||
|
@ -4450,6 +4454,9 @@ class TestSuite(ABC):
|
||||||
"LOG_DISARMED": 0,
|
"LOG_DISARMED": 0,
|
||||||
})
|
})
|
||||||
self.reboot_sitl()
|
self.reboot_sitl()
|
||||||
|
|
||||||
|
self.set_parameter('SIM_SPEEDUP', 1)
|
||||||
|
|
||||||
endpoints = [('UDPMulticast', 'mcast:16005') ,
|
endpoints = [('UDPMulticast', 'mcast:16005') ,
|
||||||
('UDPBroadcast', ':16006')]
|
('UDPBroadcast', ':16006')]
|
||||||
for name, e in endpoints:
|
for name, e in endpoints:
|
||||||
|
@ -4487,6 +4494,9 @@ class TestSuite(ABC):
|
||||||
"CAN_D1_UC_S1_PRO": 2,
|
"CAN_D1_UC_S1_PRO": 2,
|
||||||
})
|
})
|
||||||
self.reboot_sitl()
|
self.reboot_sitl()
|
||||||
|
|
||||||
|
self.set_parameter('SIM_SPEEDUP', 1)
|
||||||
|
|
||||||
filename = "MAVProxy-downloaded-can-log.BIN"
|
filename = "MAVProxy-downloaded-can-log.BIN"
|
||||||
# port 15550 is in SITL_Periph_State.h as SERIAL4 udpclient:127.0.0.1:15550
|
# port 15550 is in SITL_Periph_State.h as SERIAL4 udpclient:127.0.0.1:15550
|
||||||
mavproxy = self.start_mavproxy(master=':15550')
|
mavproxy = self.start_mavproxy(master=':15550')
|
||||||
|
|
Loading…
Reference in New Issue