diff --git a/.github/workflows/test_unit_tests.yml b/.github/workflows/test_unit_tests.yml index 609e30386c..d78cd5408b 100644 --- a/.github/workflows/test_unit_tests.yml +++ b/.github/workflows/test_unit_tests.yml @@ -147,6 +147,16 @@ jobs: fi PATH="/github/home/.local/bin:$PATH" Tools/scripts/build_ci.sh + - name: Unittest extract_param_defaults + env: + PYTHONPATH: "${{ github.workspace }}/Tools/scripts:${{ github.workspace }}/modules/mavlink/pymavlink" + shell: 'script -q -e -c "bash {0}"' + run: | + if [[ ${{ matrix.config }} == "unit-tests" ]]; then + Tools/autotest/unittest/extract_param_defaults_unittest.py + else + echo ${{matrix.config}} does not have pymavlink + fi - name: Archive buildlog artifacts uses: actions/upload-artifact@v3 diff --git a/Tools/autotest/unittest/extract_param_defaults_unittest.py b/Tools/autotest/unittest/extract_param_defaults_unittest.py new file mode 100755 index 0000000000..fe53965547 --- /dev/null +++ b/Tools/autotest/unittest/extract_param_defaults_unittest.py @@ -0,0 +1,310 @@ +#!/usr/bin/python3 + +''' +Extracts parameter default values from an ArduPilot .bin log file. Unittests. + +AP_FLAKE8_CLEAN + +Amilcar do Carmo Lucas, IAV GmbH +''' + +import unittest +from unittest.mock import patch, MagicMock +from extract_param_defaults import extract_parameter_default_values, missionplanner_sort, \ + mavproxy_sort, sort_params, output_params, parse_arguments, \ + NO_DEFAULT_VALUES_MESSAGE, MAVLINK_SYSID_MAX, MAVLINK_COMPID_MAX + + +class TestArgParseParameters(unittest.TestCase): + def test_command_line_arguments_combinations(self): + # Check the 'format' and 'sort' default parameters + args = parse_arguments(['dummy.bin']) + self.assertEqual(args.format, 'missionplanner') + self.assertEqual(args.sort, 'missionplanner') + + # Check the 'format' and 'sort' parameters to see if 'sort' can be explicitly overwritten + args = parse_arguments(['-s', 'none', 'dummy.bin']) + self.assertEqual(args.format, 'missionplanner') + self.assertEqual(args.sort, 'none') + + # Check the 'format' and 'sort' parameters to see if 'sort' can be implicitly overwritten (mavproxy) + args = parse_arguments(['-f', 'mavproxy', 'dummy.bin']) + self.assertEqual(args.format, 'mavproxy') + self.assertEqual(args.sort, 'mavproxy') + + # Check the 'format' and 'sort' parameters to see if 'sort' can be implicitly overwritten (qgcs) + args = parse_arguments(['-f', 'qgcs', 'dummy.bin']) + self.assertEqual(args.format, 'qgcs') + self.assertEqual(args.sort, 'qgcs') + + # Check the 'format' and 'sort' parameters + args = parse_arguments(['-f', 'mavproxy', '-s', 'none', 'dummy.bin']) + self.assertEqual(args.format, 'mavproxy') + self.assertEqual(args.sort, 'none') + + # Assert that a SystemExit is raised when --sysid is used without --format set to qgcs + with self.assertRaises(SystemExit): + with patch('builtins.print') as mock_print: + parse_arguments(['-f', 'mavproxy', '-i', '7', 'dummy.bin']) + mock_print.assert_called_once_with("--sysid parameter is only relevant if --format is qgcs") + + # Assert that a SystemExit is raised when --compid is used without --format set to qgcs + with self.assertRaises(SystemExit): + with patch('builtins.print') as mock_print: + parse_arguments(['-f', 'missionplanner', '-c', '3', 'dummy.bin']) + mock_print.assert_called_once_with("--compid parameter is only relevant if --format is qgcs") + + # Assert that a valid sysid and compid are parsed correctly + args = parse_arguments(['-f', 'qgcs', '-i', '7', '-c', '3', 'dummy.bin']) + self.assertEqual(args.format, 'qgcs') + self.assertEqual(args.sort, 'qgcs') + self.assertEqual(args.sysid, 7) + self.assertEqual(args.compid, 3) + + +class TestExtractParameterDefaultValues(unittest.TestCase): + + @patch('extract_param_defaults.mavutil.mavlink_connection') + def test_logfile_does_not_exist(self, mock_mavlink_connection): + # Mock the mavlink connection to raise an exception + mock_mavlink_connection.side_effect = Exception("Test exception") + + # Call the function with a dummy logfile path + with self.assertRaises(SystemExit) as cm: + extract_parameter_default_values('dummy.bin') + + # Check the error message + self.assertEqual(str(cm.exception), "Error opening the dummy.bin logfile: Test exception") + + @patch('extract_param_defaults.mavutil.mavlink_connection') + def test_extract_parameter_default_values(self, mock_mavlink_connection): + # Mock the mavlink connection and the messages it returns + mock_mlog = MagicMock() + mock_mavlink_connection.return_value = mock_mlog + mock_mlog.recv_match.side_effect = [ + MagicMock(Name='PARAM1', Default=1.1), + MagicMock(Name='PARAM2', Default=2.0), + None # End of messages + ] + + # Call the function with a dummy logfile path + defaults = extract_parameter_default_values('dummy.bin') + + # Check if the defaults dictionary contains the correct parameters and values + self.assertEqual(defaults, {'PARAM1': 1.1, 'PARAM2': 2.0}) + + @patch('extract_param_defaults.mavutil.mavlink_connection') + def test_no_parameters(self, mock_mavlink_connection): + # Mock the mavlink connection to return no parameter messages + mock_mlog = MagicMock() + mock_mavlink_connection.return_value = mock_mlog + mock_mlog.recv_match.return_value = None # No PARM messages + + # Call the function with a dummy logfile path and assert SystemExit is raised with the correct message + with self.assertRaises(SystemExit) as cm: + extract_parameter_default_values('dummy.bin') + self.assertEqual(str(cm.exception), NO_DEFAULT_VALUES_MESSAGE) + + @patch('extract_param_defaults.mavutil.mavlink_connection') + def test_no_parameter_defaults(self, mock_mavlink_connection): + # Mock the mavlink connection to simulate no parameter default values in the .bin file + mock_mlog = MagicMock() + mock_mavlink_connection.return_value = mock_mlog + mock_mlog.recv_match.return_value = None # No PARM messages + + # Call the function with a dummy logfile path and assert SystemExit is raised with the correct message + with self.assertRaises(SystemExit) as cm: + extract_parameter_default_values('dummy.bin') + self.assertEqual(str(cm.exception), NO_DEFAULT_VALUES_MESSAGE) + + @patch('extract_param_defaults.mavutil.mavlink_connection') + def test_invalid_parameter_name(self, mock_mavlink_connection): + # Mock the mavlink connection to simulate an invalid parameter name + mock_mlog = MagicMock() + mock_mavlink_connection.return_value = mock_mlog + mock_mlog.recv_match.return_value = MagicMock(Name='INVALID_NAME%', Default=1.0) + + # Call the function with a dummy logfile path + with self.assertRaises(SystemExit): + extract_parameter_default_values('dummy.bin') + + @patch('extract_param_defaults.mavutil.mavlink_connection') + def test_long_parameter_name(self, mock_mavlink_connection): + # Mock the mavlink connection to simulate a too long parameter name + mock_mlog = MagicMock() + mock_mavlink_connection.return_value = mock_mlog + mock_mlog.recv_match.return_value = MagicMock(Name='TOO_LONG_PARAMETER_NAME', Default=1.0) + + # Call the function with a dummy logfile path + with self.assertRaises(SystemExit): + extract_parameter_default_values('dummy.bin') + + +class TestSortFunctions(unittest.TestCase): + def test_missionplanner_sort(self): + # Define a list of parameter names + params = ['PARAM_GROUP1_PARAM1', 'PARAM_GROUP2_PARAM2', 'PARAM_GROUP1_PARAM2'] + + # Sort the parameters using the missionplanner_sort function + sorted_params = sorted(params, key=missionplanner_sort) + + # Check if the parameters were sorted correctly + self.assertEqual(sorted_params, ['PARAM_GROUP1_PARAM1', 'PARAM_GROUP1_PARAM2', 'PARAM_GROUP2_PARAM2']) + + # Test with a parameter name that doesn't contain an underscore + params = ['PARAM1', 'PARAM3', 'PARAM2'] + sorted_params = sorted(params, key=missionplanner_sort) + self.assertEqual(sorted_params, ['PARAM1', 'PARAM2', 'PARAM3']) + + def test_mavproxy_sort(self): + # Define a list of parameter names + params = ['PARAM_GROUP1_PARAM1', 'PARAM_GROUP2_PARAM2', 'PARAM_GROUP1_PARAM2'] + + # Sort the parameters using the mavproxy_sort function + sorted_params = sorted(params, key=mavproxy_sort) + + # Check if the parameters were sorted correctly + self.assertEqual(sorted_params, ['PARAM_GROUP1_PARAM1', 'PARAM_GROUP1_PARAM2', 'PARAM_GROUP2_PARAM2']) + + # Test with a parameter name that doesn't contain an underscore + params = ['PARAM1', 'PARAM3', 'PARAM2'] + sorted_params = sorted(params, key=mavproxy_sort) + self.assertEqual(sorted_params, ['PARAM1', 'PARAM2', 'PARAM3']) + + +class TestOutputParams(unittest.TestCase): + + @patch('extract_param_defaults.print') + def test_output_params(self, mock_print): + # Prepare a dummy defaults dictionary + defaults = {'PARAM2': 1.0, 'PARAM1': 2.0} + + # Call the function with the dummy dictionary, 'missionplanner' format type + output_params(defaults, 'missionplanner') + + # Check if the print function was called with the correct parameters + expected_calls = [unittest.mock.call('PARAM2,1'), unittest.mock.call('PARAM1,2')] + mock_print.assert_has_calls(expected_calls, any_order=False) + + @patch('extract_param_defaults.print') + def test_output_params_missionplanner_non_numeric(self, mock_print): + # Prepare a dummy defaults dictionary + defaults = {'PARAM1': 'non-numeric'} + + # Call the function with the dummy dictionary, 'missionplanner' format type + output_params(defaults, 'missionplanner') + + # Check if the print function was called with the correct parameters + expected_calls = [unittest.mock.call('PARAM1,non-numeric')] + mock_print.assert_has_calls(expected_calls, any_order=False) + + @patch('extract_param_defaults.print') + def test_output_params_mavproxy(self, mock_print): + # Prepare a dummy defaults dictionary + defaults = {'PARAM2': 2.0, 'PARAM1': 1.0} + + # Call the function with the dummy dictionary, 'mavproxy' format type and 'mavproxy' sort type + defaults = sort_params(defaults, 'mavproxy') + output_params(defaults, 'mavproxy') + + # Check if the print function was called with the correct parameters + expected_calls = [unittest.mock.call("%-15s %.6f" % ('PARAM1', 1.0)), + unittest.mock.call("%-15s %.6f" % ('PARAM2', 2.0))] + mock_print.assert_has_calls(expected_calls, any_order=False) + + @patch('extract_param_defaults.print') + def test_output_params_qgcs(self, mock_print): + # Prepare a dummy defaults dictionary + defaults = {'PARAM2': 2.0, 'PARAM1': 1.0} + + # Call the function with the dummy dictionary, 'qgcs' format type and 'qgcs' sort type + defaults = sort_params(defaults, 'qgcs') + output_params(defaults, 'qgcs') + + # Check if the print function was called with the correct parameters + expected_calls = [unittest.mock.call("\n# # Vehicle-Id Component-Id Name Value Type\n"), + unittest.mock.call("%u %u %-15s %.6f %u" % (1, 1, 'PARAM1', 1.0, 9)), + unittest.mock.call("%u %u %-15s %.6f %u" % (1, 1, 'PARAM2', 2.0, 9))] + mock_print.assert_has_calls(expected_calls, any_order=False) + + @patch('extract_param_defaults.print') + def test_output_params_qgcs_2_4(self, mock_print): + # Prepare a dummy defaults dictionary + defaults = {'PARAM2': 2.0, 'PARAM1': 1.0} + + # Call the function with the dummy dictionary, 'qgcs' format type and 'qgcs' sort type + defaults = sort_params(defaults, 'qgcs') + output_params(defaults, 'qgcs', 2, 4) + + # Check if the print function was called with the correct parameters + expected_calls = [unittest.mock.call("\n# # Vehicle-Id Component-Id Name Value Type\n"), + unittest.mock.call("%u %u %-15s %.6f %u" % (2, 4, 'PARAM1', 1.0, 9)), + unittest.mock.call("%u %u %-15s %.6f %u" % (2, 4, 'PARAM2', 2.0, 9))] + mock_print.assert_has_calls(expected_calls, any_order=False) + + @patch('extract_param_defaults.print') + def test_output_params_qgcs_SYSID_THISMAV(self, mock_print): + # Prepare a dummy defaults dictionary + defaults = {'PARAM2': 2.0, 'PARAM1': 1.0, 'SYSID_THISMAV': 3.0} + + # Call the function with the dummy dictionary, 'qgcs' format type and 'qgcs' sort type + defaults = sort_params(defaults, 'qgcs') + output_params(defaults, 'qgcs', -1, 7) + + # Check if the print function was called with the correct parameters + expected_calls = [unittest.mock.call("\n# # Vehicle-Id Component-Id Name Value Type\n"), + unittest.mock.call("%u %u %-15s %.6f %u" % (3, 7, 'PARAM1', 1.0, 9)), + unittest.mock.call("%u %u %-15s %.6f %u" % (3, 7, 'PARAM2', 2.0, 9)), + unittest.mock.call("%u %u %-15s %.6f %u" % (3, 7, 'SYSID_THISMAV', 3.0, 9))] + mock_print.assert_has_calls(expected_calls, any_order=False) + + @patch('extract_param_defaults.print') + def test_output_params_qgcs_SYSID_INVALID(self, mock_print): + # Prepare a dummy defaults dictionary + defaults = {'PARAM2': 2.0, 'PARAM1': 1.0, 'SYSID_THISMAV': -1.0} + + # Assert that a SystemExit is raised with the correct message when an invalid sysid is used + with self.assertRaises(SystemExit) as cm: + defaults = sort_params(defaults, 'qgcs') + output_params(defaults, 'qgcs', -1, 7) + self.assertEqual(str(cm.exception), "Invalid system ID parameter -1 must not be negative") + + # Assert that a SystemExit is raised with the correct message when an invalid sysid is used + with self.assertRaises(SystemExit) as cm: + defaults = sort_params(defaults, 'qgcs') + output_params(defaults, 'qgcs', MAVLINK_SYSID_MAX+2, 7) + self.assertEqual(str(cm.exception), f"Invalid system ID parameter 16777218 must be smaller than {MAVLINK_SYSID_MAX}") + + @patch('extract_param_defaults.print') + def test_output_params_qgcs_COMPID_INVALID(self, mock_print): + # Prepare a dummy defaults dictionary + defaults = {'PARAM2': 2.0, 'PARAM1': 1.0} + + # Assert that a SystemExit is raised with the correct message when an invalid compid is used + with self.assertRaises(SystemExit) as cm: + defaults = sort_params(defaults, 'qgcs') + output_params(defaults, 'qgcs', -1, -3) + self.assertEqual(str(cm.exception), "Invalid component ID parameter -3 must not be negative") + + # Assert that a SystemExit is raised with the correct message when an invalid compid is used + with self.assertRaises(SystemExit) as cm: + defaults = sort_params(defaults, 'qgcs') + output_params(defaults, 'qgcs', 1, MAVLINK_COMPID_MAX+3) + self.assertEqual(str(cm.exception), f"Invalid component ID parameter 259 must be smaller than {MAVLINK_COMPID_MAX}") + + @patch('extract_param_defaults.print') + def test_output_params_integer(self, mock_print): + # Prepare a dummy defaults dictionary with an integer value + defaults = {'PARAM1': 1.01, 'PARAM2': 2.00} + + # Call the function with the dummy dictionary, 'missionplanner' format type and 'missionplanner' sort type + defaults = sort_params(defaults, 'missionplanner') + output_params(defaults, 'missionplanner') + + # Check if the print function was called with the correct parameters + expected_calls = [unittest.mock.call('PARAM1,1.01'), unittest.mock.call('PARAM2,2')] + mock_print.assert_has_calls(expected_calls, any_order=False) + + +if __name__ == '__main__': + unittest.main() diff --git a/Tools/scripts/__init__.py b/Tools/scripts/__init__.py new file mode 100644 index 0000000000..f213939719 --- /dev/null +++ b/Tools/scripts/__init__.py @@ -0,0 +1 @@ +"""Automation Scripts""" \ No newline at end of file diff --git a/Tools/scripts/extract_param_defaults.py b/Tools/scripts/extract_param_defaults.py new file mode 100755 index 0000000000..cf50e16ab2 --- /dev/null +++ b/Tools/scripts/extract_param_defaults.py @@ -0,0 +1,205 @@ +#!/usr/bin/python3 + +''' +Extracts parameter default values from an ArduPilot .bin log file. + +Supports Mission Planner, MAVProxy and QGCS file format output + +Currently has 95% unit test coverage + +AP_FLAKE8_CLEAN + +Amilcar do Carmo Lucas, IAV GmbH +''' + +import argparse +import re +from typing import Dict, Tuple +from pymavlink import mavutil + +NO_DEFAULT_VALUES_MESSAGE = "The .bin file contained no parameter default values. Update to a newer ArduPilot firmware version" +PARAM_NAME_REGEX = r'^[A-Z][A-Z_0-9]*$' +PARAM_NAME_MAX_LEN = 16 +MAVLINK_SYSID_MAX = 2**24 +MAVLINK_COMPID_MAX = 2**8 + + +def parse_arguments(args=None): + """ + Parses command line arguments for the script. + + Args: + args: List of command line arguments. Defaults to None, which means it uses sys.argv. + + Returns: + Namespace object containing the parsed arguments. + """ + parser = argparse.ArgumentParser(description='Extracts parameter default values from an ArduPilot .bin log file.') + parser.add_argument('-f', '--format', + choices=['missionplanner', 'mavproxy', 'qgcs'], + default='missionplanner', help='Output file format. Defaults to %(default)s.', + ) + parser.add_argument('-s', '--sort', + choices=['none', 'missionplanner', 'mavproxy', 'qgcs'], + default='', help='Sort the parameters in the file. Defaults to the same as the format.', + ) + parser.add_argument('-v', '--version', action='version', version='%(prog)s 1.0', + help='Display version information and exit.', + ) + parser.add_argument('-i', '--sysid', type=int, default=-1, + help='System ID for qgcs output format. Defaults to SYSID_THISMAV if defined else 1.', + ) + parser.add_argument('-c', '--compid', type=int, default=-1, + help='Component ID for qgcs output format. Defaults to 1.', + ) + parser.add_argument('bin_file', help='The ArduPilot .bin log file to read') + args, _ = parser.parse_known_args(args) + + if args.sort == '': + args.sort = args.format + + if args.format != 'qgcs': + if args.sysid != -1: + raise SystemExit("--sysid parameter is only relevant if --format is qgcs") + if args.compid != -1: + raise SystemExit("--compid parameter is only relevant if --format is qgcs") + + return args + + +def extract_parameter_default_values(logfile: str) -> Dict[str, float]: + """ + Extracts the parameter default values from an ArduPilot .bin log file. + + Args: + logfile: The path to the ArduPilot .bin log file. + + Returns: + A dictionary with parameter names as keys and their default values as float. + """ + try: + mlog = mavutil.mavlink_connection(logfile) + except Exception as e: + raise SystemExit("Error opening the %s logfile: %s" % (logfile, str(e))) from e + defaults = {} + while True: + m = mlog.recv_match(type=['PARM']) + if m is None: + if not defaults: + raise SystemExit(NO_DEFAULT_VALUES_MESSAGE) + return defaults + pname = m.Name + if len(pname) > PARAM_NAME_MAX_LEN: + raise SystemExit("Too long parameter name: %s" % pname) + if not re.match(PARAM_NAME_REGEX, pname): + raise SystemExit("Invalid parameter name %s" % pname) + # parameter names are supposed to be unique + if pname not in defaults and hasattr(m, 'Default'): + defaults[pname] = m.Default # the first time default is declared is enough + + +def missionplanner_sort(item: str) -> Tuple[str, ...]: + """ + Sorts a parameter name according to the rules defined in the Mission Planner software. + + Args: + item: The parameter name to sort. + + Returns: + A tuple representing the sorted parameter name. + """ + parts = item.split("_") # Split the parameter name by underscore + # Compare the parts separately + return tuple(parts) + + +def mavproxy_sort(item: str) -> str: + """ + Sorts a parameter name according to the rules defined in the MAVProxy software. + + Args: + item: The parameter name to sort. + + Returns: + The sorted parameter name. + """ + return item + + +def sort_params(defaults: Dict[str, float], sort_type: str = 'none') -> Dict[str, float]: + """ + Sorts parameter names according to sort_type + + Args: + defaults: A dictionary with parameter names as keys and their default values as float. + sort_type: The type of sorting to apply. Can be 'none', 'missionplanner', 'mavproxy' or 'qgcs'. + + Returns: + A dictionary with parameter names as keys and their default values as float. + """ + if sort_type == "missionplanner": + defaults = dict(sorted(defaults.items(), key=lambda x: missionplanner_sort(x[0]))) + elif sort_type == "mavproxy": + defaults = dict(sorted(defaults.items(), key=lambda x: mavproxy_sort(x[0]))) + elif sort_type == "qgcs": + defaults = {k: defaults[k] for k in sorted(defaults)} + return defaults + + +def output_params(defaults: Dict[str, float], format_type: str = 'missionplanner', + sysid: int = -1, compid: int = -1) -> None: + """ + Outputs parameters names and their default values to the console + + Args: + defaults: A dictionary with parameter names as keys and their default values as float. + format_type: The output file format. Can be 'missionplanner', 'mavproxy' or 'qgcs'. + + Returns: + None + """ + if format_type == "qgcs": + if sysid == -1: + if 'SYSID_THISMAV' in defaults: + sysid = defaults['SYSID_THISMAV'] + else: + sysid = 1 # if unspecified, default to 1 + if compid == -1: + compid = 1 # if unspecified, default to 1 + if sysid < 0: + raise SystemExit("Invalid system ID parameter %i must not be negative" % sysid) + if sysid > MAVLINK_SYSID_MAX-1: + raise SystemExit("Invalid system ID parameter %i must be smaller than %i" % (sysid, MAVLINK_SYSID_MAX)) + if compid < 0: + raise SystemExit("Invalid component ID parameter %i must not be negative" % compid) + if compid > MAVLINK_COMPID_MAX-1: + raise SystemExit("Invalid component ID parameter %i must be smaller than %i" % (compid, MAVLINK_COMPID_MAX)) + # see https://dev.qgroundcontrol.com/master/en/file_formats/parameters.html + print(""" +# # Vehicle-Id Component-Id Name Value Type +""") + + for param_name, default_value in defaults.items(): + if format_type == "missionplanner": + try: + default_value = format(default_value, '.6f').rstrip('0').rstrip('.') + except ValueError: + pass # preserve non-floating point strings, if present + print(f"{param_name},{default_value}") + elif format_type == "mavproxy": + print("%-15s %.6f" % (param_name, default_value)) + elif format_type == "qgcs": + MAV_PARAM_TYPE_REAL32 = 9 + print("%u %u %-15s %.6f %u" % + (sysid, compid, param_name, default_value, MAV_PARAM_TYPE_REAL32)) + + +def main(): + args = parse_arguments() + parameter_default_values = extract_parameter_default_values(args.bin_file) + parameter_default_values = sort_params(parameter_default_values, args.sort) + output_params(parameter_default_values, args.format, args.sysid, args.compid) + + +if __name__ == "__main__": + main()