Skip to content

Commit 9f05e82

Browse files
committed
fix(reliability): replace SystemExit with catchable ParamFileError
SystemExit on malformed .param files kills the entire GUI with no recovery. Users lose unsaved work with no opportunity to fix the file. - Add ParamFileError(ValueError) exception class - Replace all 9 raise SystemExit in data_model_par_dict.py - Narrow try/except ValueError to only cover float() conversion, moving isfinite check outside to avoid subclass catch conflict - Update all 5 callers to catch ParamFileError instead of SystemExit - Update all tests across 5 test files to expect ParamFileError - Wrap long import line in annotate_params.py Closes #1416 Signed-off-by: Yash Goel <yashhzd@users.noreply.github.com>
1 parent 26801aa commit 9f05e82

10 files changed

+75
-57
lines changed

ardupilot_methodic_configurator/__main__.py

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -40,7 +40,7 @@
4040
from ardupilot_methodic_configurator.backend_flightcontroller import DEVICE_FC_PARAM_FROM_FILE, FlightController
4141
from ardupilot_methodic_configurator.backend_internet import verify_and_open_url, webbrowser_open_url
4242
from ardupilot_methodic_configurator.common_arguments import add_common_arguments
43-
from ardupilot_methodic_configurator.data_model_par_dict import ParDict
43+
from ardupilot_methodic_configurator.data_model_par_dict import ParamFileError, ParDict
4444
from ardupilot_methodic_configurator.data_model_parameter_editor import ParameterEditor
4545
from ardupilot_methodic_configurator.data_model_software_updates import UpdateManager, check_for_software_updates
4646
from ardupilot_methodic_configurator.data_model_vehicle_project import VehicleProjectManager
@@ -365,7 +365,7 @@ def initialize_filesystem(state: ApplicationState) -> None:
365365
state.args.allow_editing_template_files,
366366
state.args.save_component_to_system_templates,
367367
)
368-
except SystemExit as exp:
368+
except ParamFileError as exp:
369369
show_error_message(_("Fatal error reading parameter files"), f"{exp}")
370370
raise
371371

ardupilot_methodic_configurator/annotate_params.py

Lines changed: 7 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -38,7 +38,12 @@
3838
from defusedxml import ElementTree as DET # noqa: N814, just parsing, no data-structure manipulation
3939

4040
from ardupilot_methodic_configurator.backend_internet import download_file_from_url
41-
from ardupilot_methodic_configurator.data_model_par_dict import PARAM_NAME_MAX_LEN, PARAM_NAME_REGEX, ParDict
41+
from ardupilot_methodic_configurator.data_model_par_dict import (
42+
PARAM_NAME_MAX_LEN,
43+
PARAM_NAME_REGEX,
44+
ParamFileError,
45+
ParDict,
46+
)
4247

4348
# URL of the XML file
4449
BASE_URL = "https://autotest.ardupilot.org/Parameters/"
@@ -623,7 +628,7 @@ def main() -> None:
623628
else:
624629
logging.warning("No LUA MAGfit XML documentation found, skipping annotation of %s", target)
625630

626-
except (OSError, SystemExit) as exp:
631+
except (OSError, ParamFileError) as exp:
627632
logging.fatal(exp)
628633
sys_exit(1)
629634

ardupilot_methodic_configurator/data_model_par_dict.py

Lines changed: 19 additions & 14 deletions
Original file line numberDiff line numberDiff line change
@@ -25,6 +25,10 @@
2525
PARAM_NAME_MAX_LEN = 16
2626

2727

28+
class ParamFileError(ValueError):
29+
"""Raised when a .param file contains invalid or malformed data."""
30+
31+
2832
def validate_param_name(param_name: str) -> tuple[bool, str]:
2933
"""
3034
Validate parameter name according to ArduPilot standards.
@@ -159,7 +163,7 @@ def load_param_file_into_dict(param_file: str) -> "ParDict":
159163
msg = _("Missing parameter-value separator: {line} in {param_file} line {i}").format(
160164
line=line, param_file=param_file, i=i
161165
)
162-
raise SystemExit(msg)
166+
raise ParamFileError(msg)
163167
# Strip whitespace from both parameter name and value immediately after splitting
164168
parameter = parameter.strip()
165169
value = value.strip()
@@ -168,7 +172,7 @@ def load_param_file_into_dict(param_file: str) -> "ParDict":
168172
msg = _("Fatal error reading {param_file}, file must be UTF-8 encoded: {exp}").format(
169173
param_file=param_file, exp=exp
170174
)
171-
raise SystemExit(msg) from exp
175+
raise ParamFileError(msg) from exp
172176
return parameter_dict
173177

174178
@staticmethod
@@ -185,30 +189,31 @@ def _validate_parameter( # pylint: disable=too-many-arguments, too-many-positio
185189
msg = _("Too long parameter name: {parameter_name} in {param_file} line {i}").format(
186190
parameter_name=parameter_name, param_file=param_file, i=i
187191
)
188-
raise SystemExit(msg)
192+
raise ParamFileError(msg)
189193
if not re.match(PARAM_NAME_REGEX, parameter_name):
190194
msg = _("Invalid characters in parameter name {parameter_name} in {param_file} line {i}").format(
191195
parameter_name=parameter_name, param_file=param_file, i=i
192196
)
193-
raise SystemExit(msg)
197+
raise ParamFileError(msg)
194198
if parameter_name in parameter_dict:
195199
msg = _("Duplicated parameter {parameter_name} in {param_file} line {i}").format(
196200
parameter_name=parameter_name, param_file=param_file, i=i
197201
)
198-
raise SystemExit(msg)
202+
raise ParamFileError(msg)
199203
try:
200204
fvalue = float(value)
201-
if not math_isfinite(fvalue):
202-
msg = _(
203-
"Non-finite parameter value {value!r} (parsed as {fvalue}) for {parameter_name} in {param_file} line {i}"
204-
).format(value=value, fvalue=fvalue, parameter_name=parameter_name, param_file=param_file, i=i)
205-
raise SystemExit(msg)
206-
parameter_dict[parameter_name] = Par(fvalue, comment)
207205
except ValueError as exc:
208206
msg = _("Invalid parameter value {value!r} in {param_file} line {i}").format(
209207
value=value, param_file=param_file, i=i
210208
)
211-
raise SystemExit(msg) from exc
209+
raise ParamFileError(msg) from exc
210+
if not math_isfinite(fvalue):
211+
msg = _(
212+
"Non-finite parameter value {value!r} (parsed as {fvalue}) for {parameter_name} in {param_file} line {i}"
213+
).format(value=value, fvalue=fvalue, parameter_name=parameter_name, param_file=param_file, i=i)
214+
raise ParamFileError(msg)
215+
try:
216+
parameter_dict[parameter_name] = Par(fvalue, comment)
212217
except OSError as exc:
213218
_exc_type, exc_value, exc_traceback = sys_exc_info()
214219
if isinstance(exc_traceback, TracebackType):
@@ -217,7 +222,7 @@ def _validate_parameter( # pylint: disable=too-many-arguments, too-many-positio
217222
msg = _("Caused by line {i} of file {param_file}: {original_line}").format(
218223
i=i, param_file=param_file, original_line=original_line
219224
)
220-
raise SystemExit(msg) from exc
225+
raise ParamFileError(msg) from exc
221226

222227
@staticmethod
223228
def missionplanner_sort(item: str) -> tuple[str, ...]:
@@ -273,7 +278,7 @@ def _format_params(self, file_format: str = "missionplanner") -> list[str]:
273278
]
274279
else:
275280
msg = _("ERROR: Unsupported file format {file_format}").format(file_format=file_format)
276-
raise SystemExit(msg)
281+
raise ParamFileError(msg)
277282
return formatted_params
278283

279284
def export_to_param(

ardupilot_methodic_configurator/data_model_parameter_editor.py

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -39,7 +39,7 @@
3939
from ardupilot_methodic_configurator.data_model_battery_monitor import BatteryMonitorDataModel
4040
from ardupilot_methodic_configurator.data_model_configuration_step import ConfigurationStepProcessor
4141
from ardupilot_methodic_configurator.data_model_motor_test import MotorTestDataModel
42-
from ardupilot_methodic_configurator.data_model_par_dict import Par, ParDict, is_within_tolerance
42+
from ardupilot_methodic_configurator.data_model_par_dict import Par, ParamFileError, ParDict, is_within_tolerance
4343
from ardupilot_methodic_configurator.plugin_constants import PLUGIN_BATTERY_MONITOR, PLUGIN_MOTOR_TEST
4444
from ardupilot_methodic_configurator.tempcal_imu import IMUfit
4545

@@ -233,7 +233,7 @@ def handle_imu_temperature_calibration_workflow( # pylint: disable=too-many-arg
233233
# Reload parameter files after calibration
234234
self._local_filesystem.file_parameters = self._local_filesystem.read_params_from_files()
235235
return True
236-
except SystemExit as exp:
236+
except ParamFileError as exp:
237237
show_error(_("Fatal error reading parameter files"), f"{exp}")
238238
raise
239239

ardupilot_methodic_configurator/data_model_vehicle_project_opener.py

Lines changed: 3 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -13,6 +13,7 @@
1313

1414
from ardupilot_methodic_configurator import _
1515
from ardupilot_methodic_configurator.backend_filesystem import LocalFilesystem
16+
from ardupilot_methodic_configurator.data_model_par_dict import ParamFileError
1617

1718

1819
class VehicleProjectOpenError(Exception):
@@ -71,7 +72,7 @@ def open_last_vehicle_directory(self, last_vehicle_dir: str) -> str:
7172
# Initialize the filesystem with the directory
7273
try:
7374
self.local_filesystem.re_init(last_vehicle_dir, self.local_filesystem.vehicle_type)
74-
except SystemExit as exp:
75+
except ParamFileError as exp:
7576
raise VehicleProjectOpenError(
7677
_("Fatal error reading parameter files"), _("Fatal error reading parameter files: {exp}").format(exp=exp)
7778
) from exp
@@ -134,7 +135,7 @@ def open_vehicle_directory(self, vehicle_dir: str) -> str:
134135
# Initialize the filesystem with the directory
135136
try:
136137
self.local_filesystem.re_init(vehicle_dir, self.local_filesystem.vehicle_type)
137-
except SystemExit as exp:
138+
except ParamFileError as exp:
138139
raise VehicleProjectOpenError(
139140
_("Fatal error reading parameter files"), _("Fatal error reading parameter files: {exp}").format(exp=exp)
140141
) from exp

tests/test__main__.py

Lines changed: 5 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -44,7 +44,7 @@
4444
write_parameter_defaults,
4545
)
4646
from ardupilot_methodic_configurator.backend_flightcontroller import DEVICE_FC_PARAM_FROM_FILE
47-
from ardupilot_methodic_configurator.data_model_par_dict import ParDict
47+
from ardupilot_methodic_configurator.data_model_par_dict import ParamFileError, ParDict
4848
from ardupilot_methodic_configurator.frontend_tkinter_usage_popup_window import PopupWindow
4949

5050
# pylint: disable=too-many-lines,redefined-outer-name,too-few-public-methods
@@ -423,12 +423,12 @@ def test_user_receives_clear_error_when_configuration_invalid(self, application_
423423
patch("ardupilot_methodic_configurator.__main__.FlightControllerInfoWindow"),
424424
patch(
425425
"ardupilot_methodic_configurator.__main__.LocalFilesystem",
426-
side_effect=SystemExit("Configuration error"),
426+
side_effect=ParamFileError("Configuration error"),
427427
),
428428
patch("ardupilot_methodic_configurator.__main__.show_error_message") as mock_error,
429429
):
430430
# Act & Assert: Configuration error should be handled gracefully
431-
with pytest.raises(SystemExit):
431+
with pytest.raises(ParamFileError):
432432
initialize_flight_controller_and_filesystem(application_state)
433433

434434
# Assert: Clear error message displayed
@@ -1647,12 +1647,12 @@ def test_initialize_filesystem_shows_error_and_re_raises_on_system_exit(self) ->
16471647
with (
16481648
patch(
16491649
"ardupilot_methodic_configurator.__main__.LocalFilesystem",
1650-
side_effect=SystemExit("bad files"),
1650+
side_effect=ParamFileError("bad files"),
16511651
),
16521652
patch("ardupilot_methodic_configurator.__main__.show_error_message") as mock_err,
16531653
):
16541654
# Act + Assert
1655-
with pytest.raises(SystemExit):
1655+
with pytest.raises(ParamFileError):
16561656
initialize_filesystem(state)
16571657
mock_err.assert_called_once()
16581658
assert "fatal" in mock_err.call_args[0][0].lower()

tests/test_annotate_params.py

Lines changed: 4 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -40,7 +40,7 @@
4040
split_into_lines,
4141
update_parameter_documentation,
4242
)
43-
from ardupilot_methodic_configurator.data_model_par_dict import Par, ParDict
43+
from ardupilot_methodic_configurator.data_model_par_dict import Par, ParamFileError, ParDict
4444

4545
# pylint: disable=protected-access
4646

@@ -697,7 +697,7 @@ def test_par_class_methods(self) -> None:
697697
tf.write("PARAM1 invalid_value\n")
698698
tf.flush()
699699

700-
with pytest.raises(SystemExit):
700+
with pytest.raises(ParamFileError):
701701
ParDict.load_param_file_into_dict(tf.name)
702702

703703
def test_format_params_methods(self) -> None:
@@ -716,7 +716,7 @@ def test_format_params_methods(self) -> None:
716716
assert any("# comment1" in line for line in mavproxy_format)
717717

718718
# Test invalid format
719-
with pytest.raises(SystemExit):
719+
with pytest.raises(ParamFileError):
720720
param_dict._format_params("invalid_format")
721721

722722

@@ -854,7 +854,7 @@ def test_par_class_methods_comprehensive(self) -> None:
854854
tf.write("PARAM1,20.5\n") # Duplicate parameter
855855
tf_name = tf.name
856856

857-
with pytest.raises(SystemExit):
857+
with pytest.raises(ParamFileError):
858858
ParDict.load_param_file_into_dict(tf_name)
859859
os.unlink(tf_name)
860860

0 commit comments

Comments
 (0)