Skip to content

Commit

Permalink
Tools: use methods to determine port numbers
Browse files Browse the repository at this point in the history
  • Loading branch information
peterbarker committed May 17, 2023
1 parent d7bcfd7 commit b90166a
Show file tree
Hide file tree
Showing 3 changed files with 67 additions and 30 deletions.
82 changes: 56 additions & 26 deletions Tools/autotest/common.py
Original file line number Diff line number Diff line change
Expand Up @@ -1653,13 +1653,27 @@ def sitl_streamrate(self):
"""Allow subclasses to override SITL streamrate."""
return 10

def adjust_ardupilot_port(self, port):
'''adjust port in case we do not wish to use the default range (5760 and 5501 etc)'''
return port

def spare_network_port(self, offset=0):
'''returns a network port which should be able to be bound'''
if offset > 2:
raise ValueError("offset too large")
return 8000 + offset

def autotest_connection_string_to_ardupilot(self):
return "tcp:127.0.0.1:5760"
return "tcp:127.0.0.1:%u" % self.adjust_ardupilot_port(5760)

def sitl_rcin_port(self, offset=0):
if offset > 2:
raise ValueError("offset too large")
return 5501 + offset

def mavproxy_options(self):
"""Returns options to be passed to MAVProxy."""
ret = [
'--sitl=127.0.0.1:5502',
'--streamrate=%u' % self.sitl_streamrate(),
'--target-system=%u' % self.sysid_thismav(),
'--target-component=1',
Expand Down Expand Up @@ -3466,7 +3480,7 @@ def HIGH_LATENCY2_links(self):
self.reboot_sitl()

mav2 = mavutil.mavlink_connection(
"tcp:localhost:5763",
"tcp:localhost:%u" % self.adjust_ardupilot_port(5763),
robust_parsing=True,
source_system=7,
source_component=7,
Expand Down Expand Up @@ -4871,7 +4885,7 @@ def set_rc_from_map(self, _map, timeout=20):
def rc_thread_main(self):
chan16 = [1000] * 16

sitl_output = mavutil.mavudp("127.0.0.1:5501", input=False)
sitl_output = mavutil.mavudp("127.0.0.1:%u" % self.sitl_rcin_port(), input=False)
buf = None

while True:
Expand Down Expand Up @@ -8017,7 +8031,7 @@ def run_one_test_attempt(self, test, interact=False, attempt=1, suppress_stdout=
def defaults_filepath(self):
return None

def start_mavproxy(self):
def start_mavproxy(self, sitl_rcin_port=None):
self.start_mavproxy_count += 1
if self.mavproxy is not None:
return self.mavproxy
Expand All @@ -8029,11 +8043,17 @@ def start_mavproxy(self):
if self.valgrind or self.callgrind:
pexpect_timeout *= 10

if sitl_rcin_port is None:
sitl_rcin_port = self.sitl_rcin_port()

mavproxy = util.start_MAVProxy_SITL(
self.vehicleinfo_key(),
master='tcp:127.0.0.1:%u' % self.adjust_ardupilot_port(5762),
logfile=self.mavproxy_logfile,
options=self.mavproxy_options(),
pexpect_timeout=pexpect_timeout)
pexpect_timeout=pexpect_timeout,
sitl_rcin_port=sitl_rcin_port,
)
mavproxy.expect(r'Telemetry log: (\S+)\r\n')
self.logfile = mavproxy.match.group(1)
self.progress("LOGFILE %s" % self.logfile)
Expand Down Expand Up @@ -11455,9 +11475,10 @@ def NMEAOutput(self):
'''Test AHRS NMEA Output can be read by out NMEA GPS'''
self.set_parameter("SERIAL5_PROTOCOL", 20) # serial5 is NMEA output
self.set_parameter("GPS_TYPE2", 5) # GPS2 is NMEA
port = self.spare_network_port()
self.customise_SITL_commandline([
"--uartE=tcp:6735", # GPS2 is NMEA....
"--uartF=tcpclient:127.0.0.1:6735", # serial5 spews to localhost:6735
"--uartE=tcp:%u" % port, # GPS2 is NMEA....
"--uartF=tcpclient:127.0.0.1:%u" % port, # serial5 spews to localhost port
])
self.do_timesync_roundtrip()
self.wait_gps_fix_type_gte(3)
Expand Down Expand Up @@ -12066,10 +12087,11 @@ def FRSkyPassThroughStatustext(self):
"RPM1_TYPE": 10, # enable RPM output
"TERRAIN_ENABLE": 0,
})
port = self.spare_network_port()
self.customise_SITL_commandline([
"--uartF=tcp:6735" # serial5 spews to localhost:6735
"--uartF=tcp:%u" % port # serial5 spews to localhost port
])
frsky = FRSkyPassThrough(("127.0.0.1", 6735),
frsky = FRSkyPassThrough(("127.0.0.1", port),
get_time=self.get_sim_time_cached)

# waiting until we are ready to arm should ensure our wanted
Expand Down Expand Up @@ -12160,10 +12182,11 @@ def FRSkyPassThroughSensorIDs(self):
"SERIAL5_PROTOCOL": 10, # serial5 is FRSky passthrough
"RPM1_TYPE": 10, # enable RPM output
})
port = self.spare_network_port()
self.customise_SITL_commandline([
"--uartF=tcp:6735" # serial5 spews to localhost:6735
"--uartF=tcp:%u" % port # serial5 spews to localhost port
])
frsky = FRSkyPassThrough(("127.0.0.1", 6735),
frsky = FRSkyPassThrough(("127.0.0.1", port),
get_time=self.get_sim_time_cached)

self.wait_ready_to_arm()
Expand Down Expand Up @@ -12314,10 +12337,11 @@ def run_cmd_via_mavlite_get_ack(self, frsky, sport_to_mavlite, command, want_res
def FRSkyMAVlite(self):
'''Test FrSky MAVlite serial output'''
self.set_parameter("SERIAL5_PROTOCOL", 10) # serial5 is FRSky passthrough
port = self.spare_network_port()
self.customise_SITL_commandline([
"--uartF=tcp:6735" # serial5 spews to localhost:6735
"--uartF=tcp:%u" % port # serial5 spews to localhost port
])
frsky = FRSkyPassThrough(("127.0.0.1", 6735))
frsky = FRSkyPassThrough(("127.0.0.1", port))
frsky.connect()

sport_to_mavlite = SPortToMAVlite()
Expand Down Expand Up @@ -12588,10 +12612,11 @@ def FRSkySPort(self):
'''Test FrSky SPort mode'''
self.set_parameter("SERIAL5_PROTOCOL", 4) # serial5 is FRSky sport
self.set_parameter("RPM1_TYPE", 10) # enable SITL RPM sensor
port = self.spare_network_port()
self.customise_SITL_commandline([
"--uartF=tcp:6735" # serial5 spews to localhost:6735
"--uartF=tcp:%u" % port # serial5 spews to localhost port
])
frsky = FRSkySPort(("127.0.0.1", 6735), verbose=True)
frsky = FRSkySPort(("127.0.0.1", port), verbose=True)
self.wait_ready_to_arm()

# we need to start the engine to get some RPM readings, we do it for plane only
Expand Down Expand Up @@ -12660,10 +12685,11 @@ def FRSkySPort(self):
def FRSkyD(self):
'''Test FrSkyD serial output'''
self.set_parameter("SERIAL5_PROTOCOL", 3) # serial5 is FRSky output
port = self.spare_network_port()
self.customise_SITL_commandline([
"--uartF=tcp:6735" # serial5 spews to localhost:6735
"--uartF=tcp:%u" % port # serial5 spews to localhost port
])
frsky = FRSkyD(("127.0.0.1", 6735))
frsky = FRSkyD(("127.0.0.1", port))
self.wait_ready_to_arm()
m = self.assert_receive_message('GLOBAL_POSITION_INT', timeout=1)
gpi_abs_alt = int((m.alt+500) / 1000) # mm -> m
Expand Down Expand Up @@ -12782,10 +12808,11 @@ def test_ltm_s(self, ltm):
def LTM(self):
'''Test LTM serial output'''
self.set_parameter("SERIAL5_PROTOCOL", 25) # serial5 is LTM output
port = self.spare_network_port()
self.customise_SITL_commandline([
"--uartF=tcp:6735" # serial5 spews to localhost:6735
"--uartF=tcp:%u" % port # serial5 spews to localhost port
])
ltm = LTM(("127.0.0.1", 6735))
ltm = LTM(("127.0.0.1", port))
self.wait_ready_to_arm()

wants = {
Expand Down Expand Up @@ -12824,10 +12851,11 @@ def DEVO(self):
'''Test DEVO serial output'''
self.context_push()
self.set_parameter("SERIAL5_PROTOCOL", 17) # serial5 is DEVO output
port = self.spare_network_port()
self.customise_SITL_commandline([
"--uartF=tcp:6735" # serial5 spews to localhost:6735
"--uartF=tcp:%u" % port # serial5 spews to localhost port
])
devo = DEVO(("127.0.0.1", 6735))
devo = DEVO(("127.0.0.1", port))
self.wait_ready_to_arm()
m = self.assert_receive_message('GLOBAL_POSITION_INT', timeout=1)

Expand Down Expand Up @@ -12896,10 +12924,11 @@ def MSP_DJI(self):
'''Test MSP DJI serial output'''
self.set_parameter("SERIAL5_PROTOCOL", 33) # serial5 is MSP DJI output
self.set_parameter("MSP_OPTIONS", 1) # telemetry (unpolled) mode
port = self.spare_network_port()
self.customise_SITL_commandline([
"--uartF=tcp:6735" # serial5 spews to localhost:6735
"--uartF=tcp:%u" % port # serial5 spews to localhost port
])
msp = MSP_DJI(("127.0.0.1", 6735))
msp = MSP_DJI(("127.0.0.1", port))
self.wait_ready_to_arm()

tstart = self.get_sim_time()
Expand All @@ -12923,10 +12952,11 @@ def CRSF(self):
ex = None
try:
self.set_parameter("SERIAL5_PROTOCOL", 23) # serial5 is RCIN input
port = self.spare_network_port()
self.customise_SITL_commandline([
"--uartF=tcp:6735" # serial5 reads from to localhost:6735
"--uartF=tcp:%u" % port # serial5 reads from to localhost port
])
crsf = CRSF(("127.0.0.1", 6735))
crsf = CRSF(("127.0.0.1", port))
crsf.connect()

self.progress("Writing vtx_frame")
Expand Down
7 changes: 6 additions & 1 deletion Tools/autotest/pysim/util.py
Original file line number Diff line number Diff line change
Expand Up @@ -600,11 +600,15 @@ def MAVProxy_version():
def start_MAVProxy_SITL(atype,
aircraft=None,
setup=False,
master='tcp:127.0.0.1:5762',
master=None,
options=[],
sitl_rcin_port=5501,
pexpect_timeout=60,
logfile=sys.stdout):
"""Launch mavproxy connected to a SITL instance."""
if master is None:
raise ValueError("Expected a master")

local_mp_modules_dir = os.path.abspath(
os.path.join(__file__, '..', '..', '..', 'mavproxy_modules'))
env = dict(os.environ)
Expand All @@ -617,6 +621,7 @@ def start_MAVProxy_SITL(atype,
cmd = []
cmd.append(mavproxy_cmd())
cmd.extend(['--master', master])
cmd.extend(['--sitl', "localhost:%u" % sitl_rcin_port])
if setup:
cmd.append('--setup')
if aircraft is None:
Expand Down
8 changes: 5 additions & 3 deletions Tools/autotest/rover.py
Original file line number Diff line number Diff line change
Expand Up @@ -624,8 +624,9 @@ def ServoRelayEvents(self):

def MAVProxy_SetModeUsingSwitch(self):
"""Set modes via mavproxy switch"""
port = self.sitl_rcin_port(offset=1)
self.customise_SITL_commandline([
"--rc-in-port", "5502",
"--rc-in-port", str(port),
])
ex = None
try:
Expand All @@ -637,7 +638,7 @@ def MAVProxy_SetModeUsingSwitch(self):
(4, 'AUTO'),
(5, 'AUTO'), # non-existant mode, should stay in RTL
(6, 'MANUAL')]
mavproxy = self.start_mavproxy()
mavproxy = self.start_mavproxy(sitl_rcin_port=port)
for (num, expected) in fnoo:
mavproxy.send('switch %u\n' % num)
self.wait_mode(expected)
Expand Down Expand Up @@ -6181,7 +6182,8 @@ def AutoDock(self):
def PrivateChannel(self):
'''test the serial option bit specifying a mavlink channel as private'''
global mav2
mav2 = mavutil.mavlink_connection("tcp:localhost:5763",
port = self.adjust_ardupilot_port(5763)
mav2 = mavutil.mavlink_connection("tcp:localhost:%u" % port,
robust_parsing=True,
source_system=7,
source_component=7)
Expand Down

0 comments on commit b90166a

Please sign in to comment.