Skip to content

Commit

Permalink
Tools: extract_param_defaults can now also extract 'values' and 'non_…
Browse files Browse the repository at this point in the history
…default_values'

Also rename a bit to make it more generic
  • Loading branch information
amilcarlucas committed Jun 19, 2024
1 parent e34c91d commit c7f6357
Show file tree
Hide file tree
Showing 2 changed files with 107 additions and 76 deletions.
86 changes: 50 additions & 36 deletions Tools/autotest/unittest/extract_param_defaults_unittest.py
Original file line number Diff line number Diff line change
Expand Up @@ -5,17 +5,28 @@
AP_FLAKE8_CLEAN
Amilcar do Carmo Lucas, IAV GmbH
SPDX-FileCopyrightText: 2024 Amilcar do Carmo Lucas <[email protected]>
SPDX-License-Identifier: GPL-3.0-or-later
'''


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
from unittest.mock import patch
from unittest.mock import MagicMock

from extract_param_defaults import extract_parameter_values
from extract_param_defaults import missionplanner_sort
from extract_param_defaults import mavproxy_sort
from extract_param_defaults import sort_params
from extract_param_defaults import output_params
from extract_param_defaults import parse_arguments
from extract_param_defaults import NO_DEFAULT_VALUES_MESSAGE
from extract_param_defaults import MAVLINK_SYSID_MAX
from extract_param_defaults import MAVLINK_COMPID_MAX

class TestArgParseParameters(unittest.TestCase):

class TestArgParseParameters(unittest.TestCase): # pylint: disable=missing-class-docstring
def test_command_line_arguments_combinations(self):
# Check the 'format' and 'sort' default parameters
args = parse_arguments(['dummy.bin'])
Expand Down Expand Up @@ -62,7 +73,7 @@ def test_command_line_arguments_combinations(self):
self.assertEqual(args.compid, 3)


class TestExtractParameterDefaultValues(unittest.TestCase):
class TestExtractParameterDefaultValues(unittest.TestCase): # pylint: disable=missing-class-docstring

@patch('extract_param_defaults.mavutil.mavlink_connection')
def test_logfile_does_not_exist(self, mock_mavlink_connection):
Expand All @@ -71,7 +82,7 @@ def test_logfile_does_not_exist(self, mock_mavlink_connection):

# Call the function with a dummy logfile path
with self.assertRaises(SystemExit) as cm:
extract_parameter_default_values('dummy.bin')
extract_parameter_values('dummy.bin')

# Check the error message
self.assertEqual(str(cm.exception), "Error opening the dummy.bin logfile: Test exception")
Expand All @@ -88,7 +99,7 @@ def test_extract_parameter_default_values(self, mock_mavlink_connection):
]

# Call the function with a dummy logfile path
defaults = extract_parameter_default_values('dummy.bin')
defaults = extract_parameter_values('dummy.bin')

# Check if the defaults dictionary contains the correct parameters and values
self.assertEqual(defaults, {'PARAM1': 1.1, 'PARAM2': 2.0})
Expand All @@ -102,7 +113,7 @@ def test_no_parameters(self, mock_mavlink_connection):

# 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')
extract_parameter_values('dummy.bin')
self.assertEqual(str(cm.exception), NO_DEFAULT_VALUES_MESSAGE)

@patch('extract_param_defaults.mavutil.mavlink_connection')
Expand All @@ -114,7 +125,7 @@ def test_no_parameter_defaults(self, mock_mavlink_connection):

# 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')
extract_parameter_values('dummy.bin')
self.assertEqual(str(cm.exception), NO_DEFAULT_VALUES_MESSAGE)

@patch('extract_param_defaults.mavutil.mavlink_connection')
Expand All @@ -126,7 +137,7 @@ def test_invalid_parameter_name(self, mock_mavlink_connection):

# Call the function with a dummy logfile path
with self.assertRaises(SystemExit):
extract_parameter_default_values('dummy.bin')
extract_parameter_values('dummy.bin')

@patch('extract_param_defaults.mavutil.mavlink_connection')
def test_long_parameter_name(self, mock_mavlink_connection):
Expand All @@ -137,10 +148,10 @@ def test_long_parameter_name(self, mock_mavlink_connection):

# Call the function with a dummy logfile path
with self.assertRaises(SystemExit):
extract_parameter_default_values('dummy.bin')
extract_parameter_values('dummy.bin')


class TestSortFunctions(unittest.TestCase):
class TestSortFunctions(unittest.TestCase): # pylint: disable=missing-class-docstring
def test_missionplanner_sort(self):
# Define a list of parameter names
params = ['PARAM_GROUP1_PARAM1', 'PARAM_GROUP2_PARAM2', 'PARAM_GROUP1_PARAM2']
Expand Down Expand Up @@ -172,9 +183,9 @@ def test_mavproxy_sort(self):
self.assertEqual(sorted_params, ['PARAM1', 'PARAM2', 'PARAM3'])


class TestOutputParams(unittest.TestCase):
class TestOutputParams(unittest.TestCase): # pylint: disable=missing-class-docstring

@patch('extract_param_defaults.print')
@patch('builtins.print')
def test_output_params(self, mock_print):
# Prepare a dummy defaults dictionary
defaults = {'PARAM2': 1.0, 'PARAM1': 2.0}
Expand All @@ -184,9 +195,11 @@ def test_output_params(self, mock_print):

# Check if the print function was called with the correct parameters
expected_calls = [unittest.mock.call('PARAM2,1'), unittest.mock.call('PARAM1,2')]
print(mock_print.mock_calls)
print(expected_calls)
mock_print.assert_has_calls(expected_calls, any_order=False)

@patch('extract_param_defaults.print')
@patch('builtins.print')
def test_output_params_missionplanner_non_numeric(self, mock_print):
# Prepare a dummy defaults dictionary
defaults = {'PARAM1': 'non-numeric'}
Expand All @@ -198,7 +211,7 @@ def test_output_params_missionplanner_non_numeric(self, mock_print):
expected_calls = [unittest.mock.call('PARAM1,non-numeric')]
mock_print.assert_has_calls(expected_calls, any_order=False)

@patch('extract_param_defaults.print')
@patch('builtins.print')
def test_output_params_mavproxy(self, mock_print):
# Prepare a dummy defaults dictionary
defaults = {'PARAM2': 2.0, 'PARAM1': 1.0}
Expand All @@ -208,11 +221,11 @@ def test_output_params_mavproxy(self, mock_print):
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))]
expected_calls = [unittest.mock.call("%-15s %.6f" % ('PARAM1', 1.0)), # pylint: disable=consider-using-f-string
unittest.mock.call("%-15s %.6f" % ('PARAM2', 2.0))] # pylint: disable=consider-using-f-string
mock_print.assert_has_calls(expected_calls, any_order=False)

@patch('extract_param_defaults.print')
@patch('builtins.print')
def test_output_params_qgcs(self, mock_print):
# Prepare a dummy defaults dictionary
defaults = {'PARAM2': 2.0, 'PARAM1': 1.0}
Expand All @@ -223,11 +236,11 @@ def test_output_params_qgcs(self, mock_print):

# 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))]
unittest.mock.call("%u %u %-15s %.6f %u" % (1, 1, 'PARAM1', 1.0, 9)), # pylint: disable=consider-using-f-string
unittest.mock.call("%u %u %-15s %.6f %u" % (1, 1, 'PARAM2', 2.0, 9))] # pylint: disable=consider-using-f-string
mock_print.assert_has_calls(expected_calls, any_order=False)

@patch('extract_param_defaults.print')
@patch('builtins.print')
def test_output_params_qgcs_2_4(self, mock_print):
# Prepare a dummy defaults dictionary
defaults = {'PARAM2': 2.0, 'PARAM1': 1.0}
Expand All @@ -238,12 +251,12 @@ def test_output_params_qgcs_2_4(self, mock_print):

# 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))]
unittest.mock.call("%u %u %-15s %.6f %u" % (2, 4, 'PARAM1', 1.0, 9)), # pylint: disable=consider-using-f-string
unittest.mock.call("%u %u %-15s %.6f %u" % (2, 4, 'PARAM2', 2.0, 9))] # pylint: disable=consider-using-f-string
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):
@patch('builtins.print')
def test_output_params_qgcs_SYSID_THISMAV(self, mock_print): # pylint: disable=invalid-name
# Prepare a dummy defaults dictionary
defaults = {'PARAM2': 2.0, 'PARAM1': 1.0, 'SYSID_THISMAV': 3.0}

Expand All @@ -253,13 +266,13 @@ def test_output_params_qgcs_SYSID_THISMAV(self, mock_print):

# 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))]
unittest.mock.call("%u %u %-15s %.6f %u" % (3, 7, 'PARAM1', 1.0, 9)), # pylint: disable=consider-using-f-string
unittest.mock.call("%u %u %-15s %.6f %u" % (3, 7, 'PARAM2', 2.0, 9)), # pylint: disable=consider-using-f-string
unittest.mock.call("%u %u %-15s %.6f %u" % (3, 7, 'SYSID_THISMAV', 3.0, 9))] # pylint: disable=consider-using-f-string
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):
@patch('builtins.print')
def test_output_params_qgcs_SYSID_INVALID(self, _mock_print): # pylint: disable=invalid-name
# Prepare a dummy defaults dictionary
defaults = {'PARAM2': 2.0, 'PARAM1': 1.0, 'SYSID_THISMAV': -1.0}

Expand All @@ -275,8 +288,8 @@ def test_output_params_qgcs_SYSID_INVALID(self, mock_print):
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):
@patch('builtins.print')
def test_output_params_qgcs_COMPID_INVALID(self, _mock_print): # pylint: disable=invalid-name
# Prepare a dummy defaults dictionary
defaults = {'PARAM2': 2.0, 'PARAM1': 1.0}

Expand All @@ -292,7 +305,7 @@ def test_output_params_qgcs_COMPID_INVALID(self, mock_print):
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')
@patch('builtins.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}
Expand All @@ -306,5 +319,6 @@ def test_output_params_integer(self, mock_print):
mock_print.assert_has_calls(expected_calls, any_order=False)



if __name__ == '__main__':
unittest.main()
Loading

0 comments on commit c7f6357

Please sign in to comment.