Skip to content

Commit

Permalink
core: ardupilot-manager: Add support for UDP Server endpoints on Mavl…
Browse files Browse the repository at this point in the history
…inkRouter
  • Loading branch information
rafaellehmkuhl committed May 21, 2021
1 parent 593b409 commit 7bff468
Show file tree
Hide file tree
Showing 2 changed files with 57 additions and 17 deletions.
18 changes: 17 additions & 1 deletion core/services/ardupilot_manager/mavlink_proxy/MAVLinkRouter.py
Original file line number Diff line number Diff line change
Expand Up @@ -29,11 +29,26 @@ def convert_endpoint(endpoint: Endpoint) -> str:
return f"--tcp-port {endpoint.argument}"
if endpoint.connection_type == EndpointType.TCPClient:
return f"--tcp-endpoint {endpoint.place}:{endpoint.argument}"
if endpoint.connection_type == EndpointType.UDPServer:
return f"{endpoint.place}:{endpoint.argument}"
if endpoint.connection_type == EndpointType.UDPClient:
return f"--endpoint {endpoint.place}:{endpoint.argument}"
raise ValueError(f"Endpoint of type {endpoint.connection_type} not supported on MavlinkRouter.")

endpoints = " ".join([convert_endpoint(endpoint) for endpoint in self.endpoints()])
# Since MAVLinkRouter does not have an argument specifier for UDP Server connections
# (e.g. "--endpoint" for UDP Clients), we rely on the UDP Server endpoints being
# on the beginning of the endpoints list, and so as the first endpoints on the
# process call, for them to work
types_order = {
EndpointType.UDPServer: 0,
EndpointType.UDPClient: 1,
EndpointType.TCPServer: 2,
EndpointType.TCPClient: 3,
}
sorted_endpoints = sorted(
self.endpoints(), key=lambda endpoint: types_order[endpoint.connection_type] # type: ignore
)
endpoints = " ".join([convert_endpoint(endpoint) for endpoint in sorted_endpoints])

if master.connection_type not in [
EndpointType.UDPServer,
Expand Down Expand Up @@ -61,6 +76,7 @@ def binary_name() -> str:
def _validate_endpoint(endpoint: Endpoint) -> None:
valid_connection_types = [
EndpointType.UDPClient,
EndpointType.UDPServer,
EndpointType.TCPServer,
EndpointType.TCPClient,
]
Expand Down
56 changes: 40 additions & 16 deletions core/services/ardupilot_manager/mavlink_proxy/test_all.py
Original file line number Diff line number Diff line change
Expand Up @@ -113,7 +113,12 @@ def test_mavlink_router(valid_output_endpoints: Set[Endpoint], valid_master_endp
assert mavlink_router.name() == "MAVLinkRouter", "Name does not match."
assert re.search(r"\d+", str(mavlink_router.version())) is not None, "Version does not follow pattern."

allowed_output_types = [EndpointType.UDPClient, EndpointType.TCPServer, EndpointType.TCPClient]
allowed_output_types = [
EndpointType.UDPServer,
EndpointType.UDPClient,
EndpointType.TCPServer,
EndpointType.TCPClient,
]
allowed_master_types = [EndpointType.UDPServer, EndpointType.Serial, EndpointType.TCPServer]
run_common_routing_tests(
mavlink_router, allowed_output_types, allowed_master_types, valid_output_endpoints, valid_master_endpoints
Expand All @@ -134,27 +139,46 @@ def run_common_routing_tests(
allowed_output_endpoints = set(
filter(lambda endpoint: endpoint.connection_type in allowed_output_types, output_endpoints)
)
for endpoint in allowed_output_endpoints:
router.add_endpoint(endpoint)
assert router.endpoints() == allowed_output_endpoints, "Endpoint list does not match."

unallowed_output_endpoints = output_endpoints.difference(allowed_output_endpoints)
for endpoint in unallowed_output_endpoints:
with pytest.raises(ValueError):
router.add_endpoint(endpoint)

allowed_master_endpoints = set(
filter(lambda endpoint: endpoint.connection_type in allowed_master_types, master_endpoints)
)
for endpoint in allowed_master_endpoints:
router.start(endpoint)
assert router.is_running(), f"{router.name()} is not running after start."
router.exit()
while router.is_running():
pass
assert not router.is_running(), f"{router.name()} is not stopping after exit."

unallowed_output_endpoints = output_endpoints.difference(allowed_output_endpoints)
unallowed_master_endpoints = master_endpoints.difference(allowed_master_endpoints)

for endpoint in unallowed_output_endpoints:
with pytest.raises(ValueError):
router.add_endpoint(endpoint)

for endpoint in unallowed_master_endpoints:
with pytest.raises(ValueError):
router.start(endpoint)

def test_endpoint_combinations(master_endpoints: List[Endpoint], output_endpoints: List[Endpoint]):
for master_endpoint in master_endpoints:
router.clear_endpoints()

for output_endpoint in output_endpoints:
router.add_endpoint(output_endpoint)
assert set(router.endpoints()) == set(output_endpoints), "Endpoint list does not match."

router.start(master_endpoint)
assert router.is_running(), f"{router.name()} is not running after start."
router.exit()
while router.is_running():
pass
assert not router.is_running(), f"{router.name()} is not stopping after exit."

types_order = {
EndpointType.UDPServer: 0,
EndpointType.UDPClient: 1,
EndpointType.TCPServer: 2,
EndpointType.TCPClient: 3,
EndpointType.Serial: 4,
}
sorted_endpoints = sorted(allowed_output_endpoints, key=lambda e: types_order[e.connection_type]) # type: ignore

# Test endpoint combinationsin two orders: regular and reversed
test_endpoint_combinations(allowed_master_endpoints, sorted_endpoints)
test_endpoint_combinations(allowed_master_endpoints, sorted_endpoints[::-1])

0 comments on commit 7bff468

Please sign in to comment.