Skip to content

Commit 4eea884

Browse files
committed
FEATURE: add initial test_backend_flightcontroller file
1 parent bb38dfc commit 4eea884

File tree

1 file changed

+170
-0
lines changed

1 file changed

+170
-0
lines changed
Lines changed: 170 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,170 @@
1+
#!/usr/bin/env python3
2+
3+
"""
4+
Tests for the backend_filesystem.py file.
5+
6+
This file is part of Ardupilot methodic configurator. https://github.com/ArduPilot/MethodicConfigurator
7+
8+
SPDX-FileCopyrightText: 2024-2025 Amilcar do Carmo Lucas <[email protected]>
9+
10+
SPDX-License-Identifier: GPL-3.0-or-later
11+
"""
12+
13+
from unittest.mock import mock_open, patch
14+
15+
from ardupilot_methodic_configurator.annotate_params import Par
16+
from ardupilot_methodic_configurator.backend_flightcontroller import FlightController
17+
18+
19+
def test_add_connection() -> None:
20+
fc = FlightController(reboot_time=7)
21+
assert fc.add_connection("test_connection") is True
22+
assert fc.add_connection("test_connection") is False
23+
assert fc.add_connection("") is False
24+
25+
26+
def test_discover_connections() -> None:
27+
fc = FlightController(reboot_time=7)
28+
fc.discover_connections()
29+
assert len(fc.get_connection_tuples()) > 0
30+
31+
32+
def test_connect() -> None:
33+
fc = FlightController(reboot_time=7)
34+
result = fc.connect(device="test")
35+
assert result == ""
36+
37+
38+
def test_disconnect() -> None:
39+
fc = FlightController(reboot_time=7)
40+
fc.connect(device="test")
41+
fc.disconnect()
42+
assert fc.master is None
43+
44+
45+
@patch("builtins.open", new_callable=mock_open, read_data="param1=1\nparam2=2")
46+
@patch(
47+
"ardupilot_methodic_configurator.annotate_params.Par.load_param_file_into_dict",
48+
side_effect=lambda x: {"param1": Par(1, x), "param2": Par(2, x)},
49+
)
50+
def test_download_params(mock_load_param_file_into_dict, mock_file) -> None:
51+
fc = FlightController(reboot_time=7)
52+
fc.connect(device="test")
53+
with patch("ardupilot_methodic_configurator.backend_flightcontroller.open", mock_file):
54+
params, _ = fc.download_params()
55+
assert isinstance(params, dict)
56+
assert params == {"param1": 1, "param2": 2}
57+
mock_load_param_file_into_dict.assert_called_once_with("params.param")
58+
59+
60+
@patch("builtins.open", new_callable=mock_open, read_data="param1,1\nparam2,2")
61+
@patch(
62+
"ardupilot_methodic_configurator.annotate_params.Par.load_param_file_into_dict",
63+
side_effect=lambda x: {"param1": Par(1, x), "param2": Par(2, x)},
64+
)
65+
def test_set_param(mock_load_param_file_into_dict, mock_file) -> None:
66+
fc = FlightController(reboot_time=7)
67+
fc.connect(device="test")
68+
fc.set_param("TEST_PARAM", 1.0)
69+
with patch("ardupilot_methodic_configurator.backend_flightcontroller.open", mock_file):
70+
params, _ = fc.download_params()
71+
assert params.get("TEST_PARAM") is None # Assuming the mock environment does not actually set the parameter
72+
mock_load_param_file_into_dict.assert_called_once_with("params.param")
73+
74+
75+
def test_reset_and_reconnect() -> None:
76+
fc = FlightController(reboot_time=7)
77+
fc.connect(device="test")
78+
result = fc.reset_and_reconnect()
79+
assert result == ""
80+
81+
82+
def test_upload_file() -> None:
83+
fc = FlightController(reboot_time=7)
84+
fc.connect(device="test")
85+
result = fc.upload_file("local.txt", "remote.txt")
86+
# Assuming the mock environment always returns False for upload_file
87+
assert result is False
88+
89+
90+
def test_get_connection_tuples() -> None:
91+
fc = FlightController(reboot_time=7)
92+
fc.add_connection("test_connection")
93+
connections = fc.get_connection_tuples()
94+
assert ("test_connection", "test_connection") in connections
95+
96+
97+
@patch("builtins.open", new_callable=mock_open, read_data="param1,1\nparam2,2")
98+
@patch(
99+
"ardupilot_methodic_configurator.annotate_params.Par.load_param_file_into_dict",
100+
side_effect=lambda x: {"param1": Par(1, x), "param2": Par(2, x)},
101+
)
102+
def test_set_param_and_verify(mock_load_param_file_into_dict, mock_file) -> None:
103+
fc = FlightController(reboot_time=7)
104+
fc.connect(device="test")
105+
fc.set_param("TEST_PARAM", 1.0)
106+
with patch("ardupilot_methodic_configurator.backend_flightcontroller.open", mock_file):
107+
params, _ = fc.download_params()
108+
# Assuming the mock environment does not actually set the parameter
109+
assert params.get("TEST_PARAM") is None
110+
mock_load_param_file_into_dict.assert_called_once_with("params.param")
111+
112+
113+
def test_download_params_via_mavftp() -> None:
114+
fc = FlightController(reboot_time=7)
115+
fc.connect(device="test")
116+
params, default_params = fc.download_params_via_mavftp()
117+
assert isinstance(params, dict)
118+
assert isinstance(default_params, dict)
119+
120+
121+
def test_auto_detect_serial() -> None:
122+
fc = FlightController(reboot_time=7)
123+
serial_ports = fc._FlightController__auto_detect_serial() # noqa: SLF001 pylint: disable=protected-access
124+
assert isinstance(serial_ports, list)
125+
126+
127+
def test_list_serial_ports() -> None:
128+
serial_ports = FlightController._FlightController__list_serial_ports() # noqa: SLF001 pylint: disable=protected-access
129+
assert isinstance(serial_ports, list)
130+
131+
132+
def test_list_network_ports() -> None:
133+
network_ports = FlightController._FlightController__list_network_ports() # noqa: SLF001 pylint: disable=protected-access
134+
assert isinstance(network_ports, list)
135+
assert "tcp:127.0.0.1:5760" in network_ports
136+
137+
138+
def test_request_banner() -> None:
139+
fc = FlightController(reboot_time=7)
140+
fc.connect(device="test")
141+
fc._FlightController__request_banner() # noqa: SLF001 pylint: disable=protected-access
142+
# Since we cannot verify in the mock environment, we will just ensure no exceptions are raised
143+
144+
145+
def test_receive_banner_text() -> None:
146+
fc = FlightController(reboot_time=7)
147+
fc.connect(device="test")
148+
banner_text = fc._FlightController__receive_banner_text() # noqa: SLF001 pylint: disable=protected-access
149+
assert isinstance(banner_text, list)
150+
151+
152+
def test_request_message() -> None:
153+
fc = FlightController(reboot_time=7)
154+
fc.connect(device="test")
155+
fc._FlightController__request_message(1) # noqa: SLF001 pylint: disable=protected-access
156+
# Since we cannot verify in the mock environment, we will just ensure no exceptions are raised
157+
158+
159+
def test_create_connection_with_retry() -> None:
160+
fc = FlightController(reboot_time=7)
161+
result = fc._FlightController__create_connection_with_retry(progress_callback=None, retries=1, timeout=1) # noqa: SLF001 pylint: disable=protected-access
162+
assert result == ""
163+
164+
165+
def test_process_autopilot_version() -> None:
166+
fc = FlightController(reboot_time=7)
167+
fc.connect(device="test")
168+
banner_msgs = ["ChibiOS: 123", "ArduPilot"]
169+
result = fc._FlightController__process_autopilot_version(None, banner_msgs) # noqa: SLF001 pylint: disable=protected-access
170+
assert isinstance(result, str)

0 commit comments

Comments
 (0)