Skip to content

Commit 104dc15

Browse files
ardupilot_manager: tweak tests so they run faster
This took the mavlink routers tests down from 108s to 65s on my machine
1 parent bd3d4f4 commit 104dc15

File tree

1 file changed

+52
-4
lines changed

1 file changed

+52
-4
lines changed

core/services/ardupilot_manager/mavlink_proxy/test_all.py

Lines changed: 52 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -1,4 +1,5 @@
11
# pylint: disable=redefined-outer-name
2+
import asyncio
23
import os
34
import pathlib
45
import pty
@@ -182,6 +183,34 @@ async def serial_test_mavproxy(valid_output_endpoints: Set[Endpoint], valid_mast
182183
)
183184

184185

186+
def create_endpoints_with_offset(endpoints: Set[Endpoint], port_offset: int) -> Set[Endpoint]:
187+
"""Create a new set of endpoints with ports offset by the given amount"""
188+
new_endpoints = set()
189+
for endpoint in endpoints:
190+
# Only modify network endpoints with non-None arguments
191+
if (
192+
endpoint.connection_type
193+
in [
194+
EndpointType.UDPServer,
195+
EndpointType.UDPClient,
196+
EndpointType.TCPServer,
197+
EndpointType.TCPClient,
198+
]
199+
and endpoint.argument is not None
200+
):
201+
new_endpoint = Endpoint(
202+
name=endpoint.name,
203+
owner=endpoint.owner,
204+
connection_type=endpoint.connection_type,
205+
place=endpoint.place,
206+
argument=endpoint.argument + port_offset,
207+
)
208+
new_endpoints.add(new_endpoint)
209+
else:
210+
new_endpoints.add(endpoint)
211+
return new_endpoints
212+
213+
185214
async def serial_test_mavlink_router(
186215
valid_output_endpoints: Set[Endpoint], valid_master_endpoints: Set[Endpoint]
187216
) -> None:
@@ -191,6 +220,10 @@ async def serial_test_mavlink_router(
191220

192221
assert AbstractRouter.get_interface("MAVLinkRouter"), "Failed to find interface MAVLinkRouter"
193222

223+
# Use base ports for MAVLinkRouter (offset by 0)
224+
output_endpoints = create_endpoints_with_offset(valid_output_endpoints, 0)
225+
master_endpoints = create_endpoints_with_offset(valid_master_endpoints, 0)
226+
194227
mavlink_router = MAVLinkRouter()
195228
assert mavlink_router.name() == "MAVLinkRouter", "Name does not match."
196229
assert re.search(r"\d+", str(mavlink_router.version())) is not None, "Version does not follow pattern."
@@ -207,8 +240,12 @@ async def serial_test_mavlink_router(
207240
EndpointType.TCPClient,
208241
EndpointType.Serial,
209242
]
243+
244+
filtered_output_endpoints = set(e for e in output_endpoints if e.connection_type in allowed_output_types)
245+
filtered_master_endpoints = set(e for e in master_endpoints if e.connection_type in allowed_master_types)
246+
210247
await run_common_routing_tests(
211-
mavlink_router, allowed_output_types, allowed_master_types, valid_output_endpoints, valid_master_endpoints
248+
mavlink_router, allowed_output_types, allowed_master_types, filtered_output_endpoints, filtered_master_endpoints
212249
)
213250

214251

@@ -220,6 +257,10 @@ async def serial_test_mavp2p(valid_output_endpoints: Set[Endpoint], valid_master
220257

221258
assert AbstractRouter.get_interface("MAVP2P"), "Failed to find interface MAVP2P"
222259

260+
# Offset ports by 100 for MAVP2P to avoid conflicts as we run tests in parallel
261+
output_endpoints = create_endpoints_with_offset(valid_output_endpoints, 100)
262+
master_endpoints = create_endpoints_with_offset(valid_master_endpoints, 100)
263+
223264
mavp2p = MAVP2P()
224265
assert mavp2p.name() == "MAVP2P", "Name does not match."
225266
assert re.search(r"\d+.\d+.\d+", str(mavp2p.version())) is not None, "Version does not follow pattern."
@@ -232,16 +273,23 @@ async def serial_test_mavp2p(valid_output_endpoints: Set[Endpoint], valid_master
232273
EndpointType.Serial,
233274
]
234275
allowed_master_types = allowed_output_types
276+
277+
filtered_output_endpoints = set(e for e in output_endpoints if e.connection_type in allowed_output_types)
278+
filtered_master_endpoints = set(e for e in master_endpoints if e.connection_type in allowed_master_types)
279+
235280
await run_common_routing_tests(
236-
mavp2p, allowed_output_types, allowed_master_types, valid_output_endpoints, valid_master_endpoints
281+
mavp2p, allowed_output_types, allowed_master_types, filtered_output_endpoints, filtered_master_endpoints
237282
)
238283

239284

240285
@pytest.mark.timeout(120)
241286
@pytest.mark.asyncio
242287
async def test_router(valid_output_endpoints: Set[Endpoint], valid_master_endpoints: Set[Endpoint]) -> None:
243-
for router in [serial_test_mavlink_router, serial_test_mavp2p]:
244-
await router(valid_output_endpoints, valid_master_endpoints)
288+
# Run both router tests in parallel
289+
await asyncio.gather(
290+
serial_test_mavlink_router(valid_output_endpoints, valid_master_endpoints),
291+
serial_test_mavp2p(valid_output_endpoints, valid_master_endpoints),
292+
)
245293

246294

247295
@pytest.mark.timeout(10)

0 commit comments

Comments
 (0)