Path: blob/master/Tools/autotest/unittest/extract_param_defaults_unittest.py
9842 views
#!/usr/bin/env python312'''3Extracts parameter default values from an ArduPilot .bin log file. Unittests.45AP_FLAKE8_CLEAN67Amilcar do Carmo Lucas, IAV GmbH8'''910import unittest11from unittest.mock import patch, MagicMock12from extract_param_defaults import extract_parameter_default_values, missionplanner_sort, \13mavproxy_sort, sort_params, output_params, parse_arguments, \14NO_DEFAULT_VALUES_MESSAGE, MAVLINK_SYSID_MAX, MAVLINK_COMPID_MAX151617class TestArgParseParameters(unittest.TestCase):18def test_command_line_arguments_combinations(self):19# Check the 'format' and 'sort' default parameters20args = parse_arguments(['dummy.bin'])21self.assertEqual(args.format, 'missionplanner')22self.assertEqual(args.sort, 'missionplanner')2324# Check the 'format' and 'sort' parameters to see if 'sort' can be explicitly overwritten25args = parse_arguments(['-s', 'none', 'dummy.bin'])26self.assertEqual(args.format, 'missionplanner')27self.assertEqual(args.sort, 'none')2829# Check the 'format' and 'sort' parameters to see if 'sort' can be implicitly overwritten (mavproxy)30args = parse_arguments(['-f', 'mavproxy', 'dummy.bin'])31self.assertEqual(args.format, 'mavproxy')32self.assertEqual(args.sort, 'mavproxy')3334# Check the 'format' and 'sort' parameters to see if 'sort' can be implicitly overwritten (qgcs)35args = parse_arguments(['-f', 'qgcs', 'dummy.bin'])36self.assertEqual(args.format, 'qgcs')37self.assertEqual(args.sort, 'qgcs')3839# Check the 'format' and 'sort' parameters40args = parse_arguments(['-f', 'mavproxy', '-s', 'none', 'dummy.bin'])41self.assertEqual(args.format, 'mavproxy')42self.assertEqual(args.sort, 'none')4344# Assert that a SystemExit is raised when --sysid is used without --format set to qgcs45with self.assertRaises(SystemExit):46with patch('builtins.print') as mock_print:47parse_arguments(['-f', 'mavproxy', '-i', '7', 'dummy.bin'])48mock_print.assert_called_once_with("--sysid parameter is only relevant if --format is qgcs")4950# Assert that a SystemExit is raised when --compid is used without --format set to qgcs51with self.assertRaises(SystemExit):52with patch('builtins.print') as mock_print:53parse_arguments(['-f', 'missionplanner', '-c', '3', 'dummy.bin'])54mock_print.assert_called_once_with("--compid parameter is only relevant if --format is qgcs")5556# Assert that a valid sysid and compid are parsed correctly57args = parse_arguments(['-f', 'qgcs', '-i', '7', '-c', '3', 'dummy.bin'])58self.assertEqual(args.format, 'qgcs')59self.assertEqual(args.sort, 'qgcs')60self.assertEqual(args.sysid, 7)61self.assertEqual(args.compid, 3)626364class TestExtractParameterDefaultValues(unittest.TestCase):6566@patch('extract_param_defaults.mavutil.mavlink_connection')67def test_logfile_does_not_exist(self, mock_mavlink_connection):68# Mock the mavlink connection to raise an exception69mock_mavlink_connection.side_effect = Exception("Test exception")7071# Call the function with a dummy logfile path72with self.assertRaises(SystemExit) as cm:73extract_parameter_default_values('dummy.bin')7475# Check the error message76self.assertEqual(str(cm.exception), "Error opening the dummy.bin logfile: Test exception")7778@patch('extract_param_defaults.mavutil.mavlink_connection')79def test_extract_parameter_default_values(self, mock_mavlink_connection):80# Mock the mavlink connection and the messages it returns81mock_mlog = MagicMock()82mock_mavlink_connection.return_value = mock_mlog83mock_mlog.recv_match.side_effect = [84MagicMock(Name='PARAM1', Default=1.1),85MagicMock(Name='PARAM2', Default=2.0),86None # End of messages87]8889# Call the function with a dummy logfile path90defaults = extract_parameter_default_values('dummy.bin')9192# Check if the defaults dictionary contains the correct parameters and values93self.assertEqual(defaults, {'PARAM1': 1.1, 'PARAM2': 2.0})9495@patch('extract_param_defaults.mavutil.mavlink_connection')96def test_no_parameters(self, mock_mavlink_connection):97# Mock the mavlink connection to return no parameter messages98mock_mlog = MagicMock()99mock_mavlink_connection.return_value = mock_mlog100mock_mlog.recv_match.return_value = None # No PARM messages101102# Call the function with a dummy logfile path and assert SystemExit is raised with the correct message103with self.assertRaises(SystemExit) as cm:104extract_parameter_default_values('dummy.bin')105self.assertEqual(str(cm.exception), NO_DEFAULT_VALUES_MESSAGE)106107@patch('extract_param_defaults.mavutil.mavlink_connection')108def test_no_parameter_defaults(self, mock_mavlink_connection):109# Mock the mavlink connection to simulate no parameter default values in the .bin file110mock_mlog = MagicMock()111mock_mavlink_connection.return_value = mock_mlog112mock_mlog.recv_match.return_value = None # No PARM messages113114# Call the function with a dummy logfile path and assert SystemExit is raised with the correct message115with self.assertRaises(SystemExit) as cm:116extract_parameter_default_values('dummy.bin')117self.assertEqual(str(cm.exception), NO_DEFAULT_VALUES_MESSAGE)118119@patch('extract_param_defaults.mavutil.mavlink_connection')120def test_invalid_parameter_name(self, mock_mavlink_connection):121# Mock the mavlink connection to simulate an invalid parameter name122mock_mlog = MagicMock()123mock_mavlink_connection.return_value = mock_mlog124mock_mlog.recv_match.return_value = MagicMock(Name='INVALID_NAME%', Default=1.0)125126# Call the function with a dummy logfile path127with self.assertRaises(SystemExit):128extract_parameter_default_values('dummy.bin')129130@patch('extract_param_defaults.mavutil.mavlink_connection')131def test_long_parameter_name(self, mock_mavlink_connection):132# Mock the mavlink connection to simulate a too long parameter name133mock_mlog = MagicMock()134mock_mavlink_connection.return_value = mock_mlog135mock_mlog.recv_match.return_value = MagicMock(Name='TOO_LONG_PARAMETER_NAME', Default=1.0)136137# Call the function with a dummy logfile path138with self.assertRaises(SystemExit):139extract_parameter_default_values('dummy.bin')140141142class TestSortFunctions(unittest.TestCase):143def test_missionplanner_sort(self):144# Define a list of parameter names145params = ['PARAM_GROUP1_PARAM1', 'PARAM_GROUP2_PARAM2', 'PARAM_GROUP1_PARAM2']146147# Sort the parameters using the missionplanner_sort function148sorted_params = sorted(params, key=missionplanner_sort)149150# Check if the parameters were sorted correctly151self.assertEqual(sorted_params, ['PARAM_GROUP1_PARAM1', 'PARAM_GROUP1_PARAM2', 'PARAM_GROUP2_PARAM2'])152153# Test with a parameter name that doesn't contain an underscore154params = ['PARAM1', 'PARAM3', 'PARAM2']155sorted_params = sorted(params, key=missionplanner_sort)156self.assertEqual(sorted_params, ['PARAM1', 'PARAM2', 'PARAM3'])157158def test_mavproxy_sort(self):159# Define a list of parameter names160params = ['PARAM_GROUP1_PARAM1', 'PARAM_GROUP2_PARAM2', 'PARAM_GROUP1_PARAM2']161162# Sort the parameters using the mavproxy_sort function163sorted_params = sorted(params, key=mavproxy_sort)164165# Check if the parameters were sorted correctly166self.assertEqual(sorted_params, ['PARAM_GROUP1_PARAM1', 'PARAM_GROUP1_PARAM2', 'PARAM_GROUP2_PARAM2'])167168# Test with a parameter name that doesn't contain an underscore169params = ['PARAM1', 'PARAM3', 'PARAM2']170sorted_params = sorted(params, key=mavproxy_sort)171self.assertEqual(sorted_params, ['PARAM1', 'PARAM2', 'PARAM3'])172173174class TestOutputParams(unittest.TestCase):175176@patch('extract_param_defaults.print')177def test_output_params(self, mock_print):178# Prepare a dummy defaults dictionary179defaults = {'PARAM2': 1.0, 'PARAM1': 2.0}180181# Call the function with the dummy dictionary, 'missionplanner' format type182output_params(defaults, 'missionplanner')183184# Check if the print function was called with the correct parameters185expected_calls = [unittest.mock.call('PARAM2,1'), unittest.mock.call('PARAM1,2')]186mock_print.assert_has_calls(expected_calls, any_order=False)187188@patch('extract_param_defaults.print')189def test_output_params_missionplanner_non_numeric(self, mock_print):190# Prepare a dummy defaults dictionary191defaults = {'PARAM1': 'non-numeric'}192193# Call the function with the dummy dictionary, 'missionplanner' format type194output_params(defaults, 'missionplanner')195196# Check if the print function was called with the correct parameters197expected_calls = [unittest.mock.call('PARAM1,non-numeric')]198mock_print.assert_has_calls(expected_calls, any_order=False)199200@patch('extract_param_defaults.print')201def test_output_params_mavproxy(self, mock_print):202# Prepare a dummy defaults dictionary203defaults = {'PARAM2': 2.0, 'PARAM1': 1.0}204205# Call the function with the dummy dictionary, 'mavproxy' format type and 'mavproxy' sort type206defaults = sort_params(defaults, 'mavproxy')207output_params(defaults, 'mavproxy')208209# Check if the print function was called with the correct parameters210expected_calls = [unittest.mock.call("%-15s %.6f" % ('PARAM1', 1.0)),211unittest.mock.call("%-15s %.6f" % ('PARAM2', 2.0))]212mock_print.assert_has_calls(expected_calls, any_order=False)213214@patch('extract_param_defaults.print')215def test_output_params_qgcs(self, mock_print):216# Prepare a dummy defaults dictionary217defaults = {'PARAM2': 2.0, 'PARAM1': 1.0}218219# Call the function with the dummy dictionary, 'qgcs' format type and 'qgcs' sort type220defaults = sort_params(defaults, 'qgcs')221output_params(defaults, 'qgcs')222223# Check if the print function was called with the correct parameters224expected_calls = [unittest.mock.call("\n# # Vehicle-Id Component-Id Name Value Type\n"),225unittest.mock.call("%u %u %-15s %.6f %u" % (1, 1, 'PARAM1', 1.0, 9)),226unittest.mock.call("%u %u %-15s %.6f %u" % (1, 1, 'PARAM2', 2.0, 9))]227mock_print.assert_has_calls(expected_calls, any_order=False)228229@patch('extract_param_defaults.print')230def test_output_params_qgcs_2_4(self, mock_print):231# Prepare a dummy defaults dictionary232defaults = {'PARAM2': 2.0, 'PARAM1': 1.0}233234# Call the function with the dummy dictionary, 'qgcs' format type and 'qgcs' sort type235defaults = sort_params(defaults, 'qgcs')236output_params(defaults, 'qgcs', 2, 4)237238# Check if the print function was called with the correct parameters239expected_calls = [unittest.mock.call("\n# # Vehicle-Id Component-Id Name Value Type\n"),240unittest.mock.call("%u %u %-15s %.6f %u" % (2, 4, 'PARAM1', 1.0, 9)),241unittest.mock.call("%u %u %-15s %.6f %u" % (2, 4, 'PARAM2', 2.0, 9))]242mock_print.assert_has_calls(expected_calls, any_order=False)243244@patch('extract_param_defaults.print')245def test_output_params_qgcs_MAV_SYSID(self, mock_print):246# Prepare a dummy defaults dictionary247defaults = {'PARAM2': 2.0, 'PARAM1': 1.0, 'MAV_SYSID': 3.0}248249# Call the function with the dummy dictionary, 'qgcs' format type and 'qgcs' sort type250defaults = sort_params(defaults, 'qgcs')251output_params(defaults, 'qgcs', -1, 7)252253# Check if the print function was called with the correct parameters254expected_calls = [255unittest.mock.call("\n# # Vehicle-Id Component-Id Name Value Type\n"),256unittest.mock.call("%u %u %-15s %.6f %u" % (3, 7, 'MAV_SYSID', 3.0, 9)),257unittest.mock.call("%u %u %-15s %.6f %u" % (3, 7, 'PARAM1', 1.0, 9)),258unittest.mock.call("%u %u %-15s %.6f %u" % (3, 7, 'PARAM2', 2.0, 9)),259]260mock_print.assert_has_calls(expected_calls, any_order=False)261262@patch('extract_param_defaults.print')263def test_output_params_qgcs_SYSID_INVALID(self, mock_print):264# Prepare a dummy defaults dictionary265defaults = {'PARAM2': 2.0, 'PARAM1': 1.0, 'MAV_SYSID': -1.0}266267# Assert that a SystemExit is raised with the correct message when an invalid sysid is used268with self.assertRaises(SystemExit) as cm:269defaults = sort_params(defaults, 'qgcs')270output_params(defaults, 'qgcs', -1, 7)271self.assertEqual(str(cm.exception), "Invalid system ID parameter -1 must not be negative")272273# Assert that a SystemExit is raised with the correct message when an invalid sysid is used274with self.assertRaises(SystemExit) as cm:275defaults = sort_params(defaults, 'qgcs')276output_params(defaults, 'qgcs', MAVLINK_SYSID_MAX+2, 7)277self.assertEqual(str(cm.exception), f"Invalid system ID parameter 16777218 must be smaller than {MAVLINK_SYSID_MAX}")278279@patch('extract_param_defaults.print')280def test_output_params_qgcs_COMPID_INVALID(self, mock_print):281# Prepare a dummy defaults dictionary282defaults = {'PARAM2': 2.0, 'PARAM1': 1.0}283284# Assert that a SystemExit is raised with the correct message when an invalid compid is used285with self.assertRaises(SystemExit) as cm:286defaults = sort_params(defaults, 'qgcs')287output_params(defaults, 'qgcs', -1, -3)288self.assertEqual(str(cm.exception), "Invalid component ID parameter -3 must not be negative")289290# Assert that a SystemExit is raised with the correct message when an invalid compid is used291with self.assertRaises(SystemExit) as cm:292defaults = sort_params(defaults, 'qgcs')293output_params(defaults, 'qgcs', 1, MAVLINK_COMPID_MAX+3)294self.assertEqual(str(cm.exception), f"Invalid component ID parameter 259 must be smaller than {MAVLINK_COMPID_MAX}")295296@patch('extract_param_defaults.print')297def test_output_params_integer(self, mock_print):298# Prepare a dummy defaults dictionary with an integer value299defaults = {'PARAM1': 1.01, 'PARAM2': 2.00}300301# Call the function with the dummy dictionary, 'missionplanner' format type and 'missionplanner' sort type302defaults = sort_params(defaults, 'missionplanner')303output_params(defaults, 'missionplanner')304305# Check if the print function was called with the correct parameters306expected_calls = [unittest.mock.call('PARAM1,1.01'), unittest.mock.call('PARAM2,2')]307mock_print.assert_has_calls(expected_calls, any_order=False)308309310if __name__ == '__main__':311unittest.main()312313314