Skip to content

Commit 87d4945

Browse files
committed
fix(security): replace unsafe expression evaluator with simpleeval
Python's built-in eval() with empty globals auto-injects __builtins__, making __import__ accessible from user-controlled JSON config files. Replace with simpleeval which only allows arithmetic, comparisons, dict lookups, and whitelisted functions (max, min, round, abs, len, log). Closes #1405 Signed-off-by: Yash Goel <yashhzd@gmail.com> Signed-off-by: Yash Goel <yashhzd@users.noreply.github.com>
1 parent 339afde commit 87d4945

9 files changed

+119
-7
lines changed

ardupilot_methodic_configurator/backend_filesystem_configuration_steps.py

Lines changed: 4 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -20,9 +20,11 @@
2020
# from logging import debug as logging_debug
2121
from jsonschema import validate as json_validate
2222
from jsonschema.exceptions import ValidationError
23+
from simpleeval import InvalidExpression
2324

2425
from ardupilot_methodic_configurator import _
2526
from ardupilot_methodic_configurator.data_model_par_dict import Par, ParDict
27+
from ardupilot_methodic_configurator.safe_expression_evaluator import safe_evaluate
2628

2729

2830
class PhaseData(TypedDict, total=False):
@@ -193,7 +195,7 @@ def compute_parameters( # pylint: disable=too-many-branches, too-many-arguments
193195
continue
194196

195197
try:
196-
result = eval(str(parameter_info["New Value"]), {}, variables) # noqa: S307 pylint: disable=eval-used
198+
result = safe_evaluate(str(parameter_info["New Value"]), variables)
197199
except (ZeroDivisionError, ValueError):
198200
# Handle math errors like:
199201
# - ZeroDivisionError: division by zero or 0.0 raised to negative power
@@ -236,7 +238,7 @@ def compute_parameters( # pylint: disable=too-many-branches, too-many-arguments
236238
destination[filename] = ParDict()
237239
change_reason = _(parameter_info["Change Reason"]) if parameter_info["Change Reason"] else ""
238240
destination[filename][parameter] = Par(float(result), change_reason)
239-
except (SyntaxError, NameError, KeyError, StopIteration) as _e:
241+
except (SyntaxError, NameError, KeyError, StopIteration, InvalidExpression) as _e:
240242
error_msg = _(
241243
"In file '{self.configuration_steps_filename}': '{filename}' {parameter_type} "
242244
"parameter '{parameter}' could not be computed: {_e}"

ardupilot_methodic_configurator/configuration_steps_ArduCopter.json

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -207,7 +207,7 @@
207207
"ATC_RAT_RLL_FLTT": { "New Value": "max(20, (round(289.22*vehicle_components['Propellers']['Specifications']['Diameter_inches']**-0.838, 0))) / 2", "Change Reason": "INS_GYRO_FILTER / 2" },
208208
"ATC_RAT_YAW_FLTT": { "New Value": "max(20, (round(289.22*vehicle_components['Propellers']['Specifications']['Diameter_inches']**-0.838, 0))) / 2", "Change Reason": "INS_GYRO_FILTER / 2" },
209209
"INS_GYRO_FILTER": { "New Value": "max(20, (round(289.22*vehicle_components['Propellers']['Specifications']['Diameter_inches']**-0.838, 0)))", "Change Reason": "Derived from vehicle component editor propeller size" },
210-
"MOT_THST_EXPO": { "New Value": "min(0.8, round(0.15686*__import__('math').log(vehicle_components['Propellers']['Specifications']['Diameter_inches'])+0.23693, 2))", "Change Reason": "Derived from vehicle component editor propeller size" }
210+
"MOT_THST_EXPO": { "New Value": "min(0.8, round(0.15686*log(vehicle_components['Propellers']['Specifications']['Diameter_inches'])+0.23693, 2))", "Change Reason": "Derived from vehicle component editor propeller size" }
211211
},
212212
"old_filenames": []
213213
},

ardupilot_methodic_configurator/configuration_steps_ArduPlane.json

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -206,7 +206,7 @@
206206
"ATC_RAT_RLL_FLTT": { "New Value": "max(20, (round(289.22*vehicle_components['Propellers']['Specifications']['Diameter_inches']**-0.838, 0))) / 2", "Change Reason": "INS_GYRO_FILTER / 2" },
207207
"ATC_RAT_YAW_FLTT": { "New Value": "max(20, (round(289.22*vehicle_components['Propellers']['Specifications']['Diameter_inches']**-0.838, 0))) / 2", "Change Reason": "INS_GYRO_FILTER / 2" },
208208
"INS_GYRO_FILTER": { "New Value": "max(20, (round(289.22*vehicle_components['Propellers']['Specifications']['Diameter_inches']**-0.838, 0)))", "Change Reason": "Derived from vehicle component editor propeller size" },
209-
"MOT_THST_EXPO": { "New Value": "min(0.8, round(0.15686*__import__('math').log(vehicle_components['Propellers']['Specifications']['Diameter_inches'])+0.23693, 2))", "Change Reason": "Derived from vehicle component editor propeller size" }
209+
"MOT_THST_EXPO": { "New Value": "min(0.8, round(0.15686*log(vehicle_components['Propellers']['Specifications']['Diameter_inches'])+0.23693, 2))", "Change Reason": "Derived from vehicle component editor propeller size" }
210210
},
211211
"old_filenames": []
212212
},

ardupilot_methodic_configurator/configuration_steps_Rover.json

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -206,7 +206,7 @@
206206
"ATC_RAT_RLL_FLTT": { "New Value": "max(20, (round(289.22*vehicle_components['Propellers']['Specifications']['Diameter_inches']**-0.838, 0))) / 2", "Change Reason": "INS_GYRO_FILTER / 2" },
207207
"ATC_RAT_YAW_FLTT": { "New Value": "max(20, (round(289.22*vehicle_components['Propellers']['Specifications']['Diameter_inches']**-0.838, 0))) / 2", "Change Reason": "INS_GYRO_FILTER / 2" },
208208
"INS_GYRO_FILTER": { "New Value": "max(20, (round(289.22*vehicle_components['Propellers']['Specifications']['Diameter_inches']**-0.838, 0)))", "Change Reason": "Derived from vehicle component editor propeller size" },
209-
"MOT_THST_EXPO": { "New Value": "min(0.8, round(0.15686*__import__('math').log(vehicle_components['Propellers']['Specifications']['Diameter_inches'])+0.23693, 2))", "Change Reason": "Derived from vehicle component editor propeller size" }
209+
"MOT_THST_EXPO": { "New Value": "min(0.8, round(0.15686*log(vehicle_components['Propellers']['Specifications']['Diameter_inches'])+0.23693, 2))", "Change Reason": "Derived from vehicle component editor propeller size" }
210210
},
211211
"old_filenames": []
212212
},

ardupilot_methodic_configurator/data_model_configuration_step.py

Lines changed: 2 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -18,6 +18,7 @@
1818
from ardupilot_methodic_configurator.backend_filesystem import LocalFilesystem
1919
from ardupilot_methodic_configurator.data_model_ardupilot_parameter import ArduPilotParameter
2020
from ardupilot_methodic_configurator.data_model_par_dict import Par, ParDict
21+
from ardupilot_methodic_configurator.safe_expression_evaluator import safe_evaluate
2122

2223

2324
class ConfigurationStepProcessor:
@@ -299,7 +300,7 @@ def _calculate_connection_rename_operations(
299300
"""
300301
if variables:
301302
# If variables provided, evaluate the new_connection_prefix
302-
new_connection_prefix = eval(str(new_connection_prefix), {}, variables) # noqa: S307 pylint: disable=eval-used
303+
new_connection_prefix = safe_evaluate(str(new_connection_prefix), variables)
303304

304305
# Generate the rename mapping
305306
renames = ConfigurationStepProcessor._generate_connection_renames(list(parameters.keys()), new_connection_prefix)
Lines changed: 52 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,52 @@
1+
"""
2+
Safe expression evaluator for configuration step parameter processing.
3+
4+
Replaces Python's built-in expression evaluation with simpleeval to prevent
5+
arbitrary code execution from user-controlled JSON configuration files.
6+
7+
This file is part of ArduPilot Methodic Configurator. https://github.com/ArduPilot/MethodicConfigurator
8+
9+
SPDX-FileCopyrightText: 2024-2026 Amilcar do Carmo Lucas <amilcar.lucas@iav.de>
10+
11+
SPDX-License-Identifier: GPL-3.0-or-later
12+
"""
13+
14+
from math import log
15+
from types import MappingProxyType
16+
17+
from simpleeval import simple_eval
18+
19+
SAFE_FUNCTIONS = MappingProxyType(
20+
{
21+
"max": max,
22+
"min": min,
23+
"round": round,
24+
"abs": abs,
25+
"len": len,
26+
"log": log,
27+
}
28+
)
29+
30+
31+
def safe_evaluate(expression: str, variables: dict) -> object:
32+
"""
33+
Evaluate a parameter expression safely using simpleeval.
34+
35+
Only arithmetic, comparisons, ternary conditionals, dict lookups,
36+
and whitelisted functions (max, min, round, abs, len, log) are allowed.
37+
Any attempt to call __import__, access dunder attributes, or use
38+
disallowed constructs will raise an exception.
39+
40+
Args:
41+
expression: The expression string from a configuration step JSON file.
42+
variables: A dictionary of variable names available during evaluation.
43+
44+
Returns:
45+
The result of evaluating the expression.
46+
47+
Raises:
48+
InvalidExpression: If the expression uses a disallowed feature,
49+
calls an unknown function, or references an undefined variable.
50+
51+
"""
52+
return simple_eval(expression, names=variables, functions=SAFE_FUNCTIONS)

ardupilot_methodic_configurator/vehicle_templates/ArduPlane/normal_plane/configuration_steps_ArduPlane.json

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -199,7 +199,7 @@
199199
"ATC_RAT_RLL_FLTT": { "New Value": "max(20, (round(289.22*vehicle_components['Propellers']['Specifications']['Diameter_inches']**-0.838, 0))) / 2", "Change Reason": "INS_GYRO_FILTER / 2" },
200200
"ATC_RAT_YAW_FLTT": { "New Value": "max(20, (round(289.22*vehicle_components['Propellers']['Specifications']['Diameter_inches']**-0.838, 0))) / 2", "Change Reason": "INS_GYRO_FILTER / 2" },
201201
"INS_GYRO_FILTER": { "New Value": "max(20, (round(289.22*vehicle_components['Propellers']['Specifications']['Diameter_inches']**-0.838, 0)))", "Change Reason": "Derived from vehicle component editor propeller size" },
202-
"MOT_THST_EXPO": { "New Value": "min(0.8, round(0.15686*__import__('math').log(vehicle_components['Propellers']['Specifications']['Diameter_inches'])+0.23693, 2))", "Change Reason": "Derived from vehicle component editor propeller size" }
202+
"MOT_THST_EXPO": { "New Value": "min(0.8, round(0.15686*log(vehicle_components['Propellers']['Specifications']['Diameter_inches'])+0.23693, 2))", "Change Reason": "Derived from vehicle component editor propeller size" }
203203
},
204204
"old_filenames": []
205205
},

pyproject.toml

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -59,6 +59,7 @@ dependencies = [
5959
"pymavlink==2.4.49",
6060
"pyserial==3.5",
6161
"requests==2.32.5",
62+
"simpleeval==1.0.7",
6263
"screeninfo==0.8.1",
6364
]
6465

tests/test_backend_filesystem_configuration_steps.py

Lines changed: 56 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -463,5 +463,61 @@ def test_validate_parameters_empty_dict() -> None:
463463
assert True # If we get here, no exception was raised
464464

465465

466+
def test_malicious_expression_import_blocked() -> None:
467+
"""Test that __import__ expressions are blocked by the safe evaluator."""
468+
config_steps = ConfigurationSteps("vehicle_dir", "vehicle_type")
469+
file_info = {
470+
"forced_parameters": {
471+
"PARAM1": {"New Value": "__import__('os').system('echo pwned')", "Change Reason": "Malicious"},
472+
}
473+
}
474+
variables = {"doc_dict": {"PARAM1": {"values": {}}}}
475+
476+
result = config_steps.compute_parameters("test_file", file_info, "forced", variables)
477+
478+
assert result != ""
479+
assert "PARAM1" in result
480+
assert "test_file" not in config_steps.forced_parameters
481+
482+
483+
def test_malicious_expression_builtins_blocked() -> None:
484+
"""Test that accessing __builtins__ is blocked by the safe evaluator."""
485+
config_steps = ConfigurationSteps("vehicle_dir", "vehicle_type")
486+
file_info = {
487+
"forced_parameters": {
488+
"PARAM1": {"New Value": "__builtins__.__import__('os').system('id')", "Change Reason": "Malicious"},
489+
}
490+
}
491+
variables = {"doc_dict": {"PARAM1": {"values": {}}}}
492+
493+
result = config_steps.compute_parameters("test_file", file_info, "forced", variables)
494+
495+
assert result != ""
496+
assert "PARAM1" in result
497+
assert "test_file" not in config_steps.forced_parameters
498+
499+
500+
def test_safe_log_function_in_expression() -> None:
501+
"""Test that log() works as a whitelisted safe function (replacing __import__('math').log())."""
502+
config_steps = ConfigurationSteps("vehicle_dir", "vehicle_type")
503+
file_info = {
504+
"forced_parameters": {
505+
"MOT_THST_EXPO": {
506+
"New Value": "min(0.8, round(0.15686*log(vehicle_components['Propellers']['Specifications']['Diameter_inches'])+0.23693, 2))",
507+
"Change Reason": "Derived from propeller size",
508+
},
509+
}
510+
}
511+
variables = {
512+
"doc_dict": {"MOT_THST_EXPO": {"values": {}}},
513+
"vehicle_components": {"Propellers": {"Specifications": {"Diameter_inches": 10}}},
514+
}
515+
516+
result = config_steps.compute_parameters("test_file", file_info, "forced", variables)
517+
518+
assert result == ""
519+
assert abs(config_steps.forced_parameters["test_file"]["MOT_THST_EXPO"].value - 0.6) < 0.01
520+
521+
466522
if __name__ == "__main__":
467523
unittest.main()

0 commit comments

Comments
 (0)