Skip to content

Commit

Permalink
Tools: added autotest for networking over UDP
Browse files Browse the repository at this point in the history
downloads a log with mavlink over UDP from NET_P1 port
  • Loading branch information
tridge authored and magicrub committed Nov 17, 2023
1 parent 2ba4bf1 commit f175cb1
Show file tree
Hide file tree
Showing 2 changed files with 35 additions and 2 deletions.
1 change: 1 addition & 0 deletions Tools/autotest/ardusub.py
Original file line number Diff line number Diff line change
Expand Up @@ -530,6 +530,7 @@ def tests(self):
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,
Expand Down
36 changes: 34 additions & 2 deletions Tools/autotest/vehicle_test_suite.py
Original file line number Diff line number Diff line change
Expand Up @@ -4137,6 +4137,35 @@ def TestLogDownloadMAVProxy(self, upload_logs=False):
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:
Expand Down Expand Up @@ -8123,7 +8152,7 @@ def run_one_test_attempt(self, test, interact=False, attempt=1, suppress_stdout=
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
Expand All @@ -8138,9 +8167,12 @@ def start_mavproxy(self, sitl_rcin_port=None):
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,
Expand Down

0 comments on commit f175cb1

Please sign in to comment.