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 Mar 21, 2024
1 parent aa8b48b commit aea2f8d
Show file tree
Hide file tree
Showing 2 changed files with 52 additions and 36 deletions.
14 changes: 7 additions & 7 deletions Tools/autotest/unittest/extract_param_defaults_unittest.py
Original file line number Diff line number Diff line change
Expand Up @@ -10,7 +10,7 @@

import unittest
from unittest.mock import patch, MagicMock
from extract_param_defaults import extract_parameter_default_values, missionplanner_sort, \
from extract_param_defaults import extract_parameter_values, missionplanner_sort, \
mavproxy_sort, sort_params, output_params, parse_arguments, \
NO_DEFAULT_VALUES_MESSAGE, MAVLINK_SYSID_MAX, MAVLINK_COMPID_MAX

Expand Down Expand Up @@ -71,7 +71,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 +88,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 +102,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 +114,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 +126,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,7 +137,7 @@ 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):
Expand Down
74 changes: 45 additions & 29 deletions Tools/scripts/extract_param_defaults.py
Original file line number Diff line number Diff line change
Expand Up @@ -43,7 +43,7 @@ def parse_arguments(args=None):
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',
parser.add_argument('-v', '--version', action='version', version='%(prog)s 1.1',
help='Display version information and exit.',
)
parser.add_argument('-i', '--sysid', type=int, default=-1,
Expand All @@ -52,6 +52,10 @@ def parse_arguments(args=None):
parser.add_argument('-c', '--compid', type=int, default=-1,
help='Component ID for qgcs output format. Defaults to 1.',
)
parser.add_argument('-t', '--type',
choices=['defaults', 'values', 'non_default_values'],
default='defaults', help='Type of parameter values to extract. Defaults to %(default)s.',
)
parser.add_argument('bin_file', help='The ArduPilot .bin log file to read')
args, _ = parser.parse_known_args(args)

Expand All @@ -67,35 +71,47 @@ def parse_arguments(args=None):
return args


def extract_parameter_default_values(logfile: str) -> Dict[str, float]:
def extract_parameter_values(logfile: str, type: str = 'defaults') -> Dict[str, float]:
"""
Extracts the parameter default values from an ArduPilot .bin log file.
Extracts the parameter values from an ArduPilot .bin log file.
Args:
logfile: The path to the ArduPilot .bin log file.
type: The type of parameter values to extract. Can be 'defaults', 'values' or 'non_default_values'.
Returns:
A dictionary with parameter names as keys and their default values as float.
A dictionary with parameter names as keys and their 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 = {}
values = {}
while True:
m = mlog.recv_match(type=['PARM'])
if m is None:
if not defaults:
if not values:
raise SystemExit(NO_DEFAULT_VALUES_MESSAGE)
return defaults
return values
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
if pname in values:
continue
if type == 'defaults':
if hasattr(m, 'Default'):
values[pname] = m.Default
elif type == 'values':
if hasattr(m, 'Value'):
values[pname] = m.Value
elif type == 'non_default_values':
if hasattr(m, 'Value') and hasattr(m, 'Default') and m.Value != m.Default:
values[pname] = m.Value
else:
raise SystemExit("Invalid type %s" % type)


def missionplanner_sort(item: str) -> Tuple[str, ...]:
Expand Down Expand Up @@ -126,42 +142,42 @@ def mavproxy_sort(item: str) -> str:
return item


def sort_params(defaults: Dict[str, float], sort_type: str = 'none') -> Dict[str, float]:
def sort_params(params: 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.
params: A dictionary with parameter names as keys and their 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.
A dictionary with parameter names as keys and their values as float.
"""
if sort_type == "missionplanner":
defaults = dict(sorted(defaults.items(), key=lambda x: missionplanner_sort(x[0])))
params = dict(sorted(params.items(), key=lambda x: missionplanner_sort(x[0])))
elif sort_type == "mavproxy":
defaults = dict(sorted(defaults.items(), key=lambda x: mavproxy_sort(x[0])))
params = dict(sorted(params.items(), key=lambda x: mavproxy_sort(x[0])))
elif sort_type == "qgcs":
defaults = {k: defaults[k] for k in sorted(defaults)}
return defaults
params = {k: params[k] for k in sorted(params)}
return params


def output_params(defaults: Dict[str, float], format_type: str = 'missionplanner',
def output_params(params: Dict[str, float], format_type: str = 'missionplanner',
sysid: int = -1, compid: int = -1) -> None:
"""
Outputs parameters names and their default values to the console
Outputs parameters names and their values to the console
Args:
defaults: A dictionary with parameter names as keys and their default values as float.
params: A dictionary with parameter names as keys and their 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']
if 'SYSID_THISMAV' in params:
sysid = params['SYSID_THISMAV']
else:
sysid = 1 # if unspecified, default to 1
if compid == -1:
Expand All @@ -179,26 +195,26 @@ def output_params(defaults: Dict[str, float], format_type: str = 'missionplanner
# # Vehicle-Id Component-Id Name Value Type
""")

for param_name, default_value in defaults.items():
for param_name, param_value in params.items():
if format_type == "missionplanner":
try:
default_value = format(default_value, '.6f').rstrip('0').rstrip('.')
param_value = format(param_value, '.6f').rstrip('0').rstrip('.')
except ValueError:
pass # preserve non-floating point strings, if present
print(f"{param_name},{default_value}")
print(f"{param_name},{param_value}")
elif format_type == "mavproxy":
print("%-15s %.6f" % (param_name, default_value))
print("%-15s %.6f" % (param_name, param_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))
(sysid, compid, param_name, param_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)
parameter_values = extract_parameter_values(args.bin_file, args.type)
parameter_values = sort_params(parameter_values, args.sort)
output_params(parameter_values, args.format, args.sysid, args.compid)


if __name__ == "__main__":
Expand Down

0 comments on commit aea2f8d

Please sign in to comment.