mirror of https://github.com/ArduPilot/ardupilot
Tools: added autotest for networking over UDP
downloads a log with mavlink over UDP from NET_P1 port
This commit is contained in:
parent
2ba4bf1478
commit
f175cb19a1
|
@ -530,6 +530,7 @@ class AutoTestSub(vehicle_test_suite.TestSuite):
|
|||
self.MotorThrustHoverParameterIgnore,
|
||||
self.SET_POSITION_TARGET_GLOBAL_INT,
|
||||
self.TestLogDownloadMAVProxy,
|
||||
self.TestLogDownloadMAVProxyNetwork,
|
||||
self.MAV_CMD_NAV_LOITER_UNLIM,
|
||||
self.MAV_CMD_NAV_LAND,
|
||||
self.MAV_CMD_MISSION_START,
|
||||
|
|
|
@ -4137,6 +4137,35 @@ class TestSuite(ABC):
|
|||
self.mavproxy_unload_module(mavproxy, 'log')
|
||||
self.stop_mavproxy(mavproxy)
|
||||
|
||||
def TestLogDownloadMAVProxyNetwork(self, upload_logs=False):
|
||||
"""Download latest log over network port"""
|
||||
self.context_push()
|
||||
self.set_parameters({
|
||||
"NET_ENABLED": 1,
|
||||
"NET_DHCP": 0,
|
||||
"NET_P1_TYPE": 1,
|
||||
"NET_P1_PROTOCOL": 2,
|
||||
"NET_P1_PORT": 15004,
|
||||
"NET_P1_IP0": 127,
|
||||
"NET_P1_IP1": 0,
|
||||
"NET_P1_IP2": 0,
|
||||
"NET_P1_IP3": 1
|
||||
})
|
||||
self.reboot_sitl()
|
||||
filename = "MAVProxy-downloaded-net-log.BIN"
|
||||
mavproxy = self.start_mavproxy(master=':15004')
|
||||
self.mavproxy_load_module(mavproxy, 'log')
|
||||
mavproxy.send("log list\n")
|
||||
mavproxy.expect("numLogs")
|
||||
self.wait_heartbeat()
|
||||
self.wait_heartbeat()
|
||||
mavproxy.send("set shownoise 0\n")
|
||||
mavproxy.send("log download latest %s\n" % filename)
|
||||
mavproxy.expect("Finished downloading", timeout=120)
|
||||
self.mavproxy_unload_module(mavproxy, 'log')
|
||||
self.stop_mavproxy(mavproxy)
|
||||
self.context_pop()
|
||||
|
||||
def show_gps_and_sim_positions(self, on_off):
|
||||
"""Allow to display gps and actual position on map."""
|
||||
if on_off is True:
|
||||
|
@ -8123,7 +8152,7 @@ Also, ignores heartbeats not from our target system'''
|
|||
def defaults_filepath(self):
|
||||
return None
|
||||
|
||||
def start_mavproxy(self, sitl_rcin_port=None):
|
||||
def start_mavproxy(self, sitl_rcin_port=None, master=None):
|
||||
self.start_mavproxy_count += 1
|
||||
if self.mavproxy is not None:
|
||||
return self.mavproxy
|
||||
|
@ -8138,9 +8167,12 @@ Also, ignores heartbeats not from our target system'''
|
|||
if sitl_rcin_port is None:
|
||||
sitl_rcin_port = self.sitl_rcin_port()
|
||||
|
||||
if master is None:
|
||||
master = 'tcp:127.0.0.1:%u' % self.adjust_ardupilot_port(5762)
|
||||
|
||||
mavproxy = util.start_MAVProxy_SITL(
|
||||
self.vehicleinfo_key(),
|
||||
master='tcp:127.0.0.1:%u' % self.adjust_ardupilot_port(5762),
|
||||
master=master,
|
||||
logfile=self.mavproxy_logfile,
|
||||
options=self.mavproxy_options(),
|
||||
pexpect_timeout=pexpect_timeout,
|
||||
|
|
Loading…
Reference in New Issue