Skip to content

Commit

Permalink
Tools: extract_param_defaults.py improved linting
Browse files Browse the repository at this point in the history
  • Loading branch information
amilcarlucas committed Jun 19, 2024
1 parent 13b1fd5 commit ef1ddb6
Showing 1 changed file with 22 additions and 21 deletions.
43 changes: 22 additions & 21 deletions Tools/scripts/extract_param_defaults.py
Original file line number Diff line number Diff line change
@@ -1,15 +1,17 @@
#!/usr/bin/python3

'''
Extracts parameter default values from an ArduPilot .bin log file.
Extracts parameter values or 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
SPDX-FileCopyrightText: 2024 Amilcar do Carmo Lucas <[email protected]>
SPDX-License-Identifier: GPL-3.0-or-later
'''

import argparse
Expand All @@ -22,6 +24,7 @@
PARAM_NAME_MAX_LEN = 16
MAVLINK_SYSID_MAX = 2**24
MAVLINK_COMPID_MAX = 2**8
MAV_PARAM_TYPE_REAL32 = 9


def parse_arguments(args=None):
Expand Down Expand Up @@ -71,21 +74,21 @@ def parse_arguments(args=None):
return args


def extract_parameter_values(logfile: str, type: str = 'defaults') -> Dict[str, float]:
def extract_parameter_values(logfile: str, param_type: str = 'defaults') -> Dict[str, float]: # pylint: disable=too-many-branches
"""
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'.
param_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 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
raise SystemExit(f"Error opening the {logfile} logfile: {str(e)}") from e
values = {}
while True:
m = mlog.recv_match(type=['PARM'])
Expand All @@ -95,23 +98,23 @@ def extract_parameter_values(logfile: str, type: str = 'defaults') -> Dict[str,
return values
pname = m.Name
if len(pname) > PARAM_NAME_MAX_LEN:
raise SystemExit("Too long parameter name: %s" % pname)
raise SystemExit(f"Too long parameter name: {pname}")
if not re.match(PARAM_NAME_REGEX, pname):
raise SystemExit("Invalid parameter name %s" % pname)
raise SystemExit(f"Invalid parameter name {pname}")
# parameter names are supposed to be unique
if pname in values:
continue
if type == 'defaults':
if param_type == 'defaults':
if hasattr(m, 'Default'):
values[pname] = m.Default
elif type == 'values':
elif param_type == 'values':
if hasattr(m, 'Value'):
values[pname] = m.Value
elif type == 'non_default_values':
elif param_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)
raise SystemExit(f"Invalid type {param_type}")


def missionplanner_sort(item: str) -> Tuple[str, ...]:
Expand Down Expand Up @@ -162,7 +165,7 @@ def sort_params(params: Dict[str, float], sort_type: str = 'none') -> Dict[str,
return params


def output_params(params: Dict[str, float], format_type: str = 'missionplanner',
def output_params(params: Dict[str, float], format_type: str = 'missionplanner', # pylint: disable=too-many-branches
sysid: int = -1, compid: int = -1) -> None:
"""
Outputs parameters names and their values to the console
Expand All @@ -177,19 +180,19 @@ def output_params(params: Dict[str, float], format_type: str = 'missionplanner',
if format_type == "qgcs":
if sysid == -1:
if 'SYSID_THISMAV' in params:
sysid = params['SYSID_THISMAV']
sysid = int(params['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)
raise SystemExit(f"Invalid system ID parameter {sysid} must not be negative")
if sysid > MAVLINK_SYSID_MAX-1:
raise SystemExit("Invalid system ID parameter %i must be smaller than %i" % (sysid, MAVLINK_SYSID_MAX))
raise SystemExit(f"Invalid system ID parameter {sysid} must be smaller than {MAVLINK_SYSID_MAX}")
if compid < 0:
raise SystemExit("Invalid component ID parameter %i must not be negative" % compid)
raise SystemExit(f"Invalid component ID parameter {compid} must not be negative")
if compid > MAVLINK_COMPID_MAX-1:
raise SystemExit("Invalid component ID parameter %i must be smaller than %i" % (compid, MAVLINK_COMPID_MAX))
raise SystemExit(f"Invalid component ID parameter {compid} must be smaller than {MAVLINK_COMPID_MAX}")
# see https://dev.qgroundcontrol.com/master/en/file_formats/parameters.html
print("""
# # Vehicle-Id Component-Id Name Value Type
Expand All @@ -203,11 +206,9 @@ def output_params(params: Dict[str, float], format_type: str = 'missionplanner',
pass # preserve non-floating point strings, if present
print(f"{param_name},{param_value}")
elif format_type == "mavproxy":
print("%-15s %.6f" % (param_name, param_value))
print(f"{param_name:<15} {param_value:.6f}")
elif format_type == "qgcs":
MAV_PARAM_TYPE_REAL32 = 9
print("%u %u %-15s %.6f %u" %
(sysid, compid, param_name, param_value, MAV_PARAM_TYPE_REAL32))
print(f"{sysid} {compid} {param_name:<15} {param_value:.6f} {MAV_PARAM_TYPE_REAL32}")


def main():
Expand Down

0 comments on commit ef1ddb6

Please sign in to comment.