Skip to content

Commit 2a5efaf

Browse files
committed
refactor(Par): Reduce code duplication
1 parent 19ac585 commit 2a5efaf

4 files changed

Lines changed: 101 additions & 107 deletions

File tree

ardupilot_methodic_configurator/annotate_params.py

Lines changed: 10 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -414,20 +414,24 @@ def extract_parameter_name_and_validate(line: str, filename: str, line_nr: int)
414414
SystemExit: If the line is invalid or the parameter name is too long or invalid.
415415
416416
"""
417-
# Extract the parameter name
418-
match = re.match(PARAM_NAME_REGEX, line)
417+
# Extract the parameter name from the line (until we hit a separator)
418+
# Create a regex to extract parameter name followed by separator
419+
param_line_pattern = r"^([A-Z][A-Z_0-9]*)[,\s\t]"
420+
match = re.match(param_line_pattern, line)
419421
if match:
420-
param_name = match.group(0)
422+
param_name = match.group(1)
421423
else:
422424
logging.critical("Invalid line %d in file %s: %s", line_nr, filename, line)
423425
msg = "Invalid line in input file"
424426
raise SystemExit(msg)
425-
param_len = len(param_name)
426-
param_sep = line[param_len] # the character following the parameter name must be a separator
427-
if param_sep not in {",", " ", "\t"}:
427+
428+
# Validate the extracted parameter name against the strict parameter name regex
429+
if not re.match(PARAM_NAME_REGEX, param_name):
428430
logging.critical("Invalid parameter name %s on line %d in file %s", param_name, line_nr, filename)
429431
msg = "Invalid parameter name"
430432
raise SystemExit(msg)
433+
434+
param_len = len(param_name)
431435
if param_len > PARAM_NAME_MAX_LEN:
432436
logging.critical("Too long parameter name on line %d in file %s", line_nr, filename)
433437
msg = "Too long parameter name"

ardupilot_methodic_configurator/data_model_par_dict.py

Lines changed: 7 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -20,7 +20,7 @@
2020
from ardupilot_methodic_configurator import _
2121

2222
# ArduPilot parameter names start with a capital letter and can have capital letters, numbers and _
23-
PARAM_NAME_REGEX = r"^[A-Z][A-Z_0-9]*"
23+
PARAM_NAME_REGEX = r"^[A-Z][A-Z_0-9]*$"
2424
PARAM_NAME_MAX_LEN = 16
2525

2626

@@ -208,17 +208,22 @@ def _format_params(self, file_format: str = "missionplanner") -> list[str]: # p
208208
formatted_params.append(f"{key:<16} {parameter:<8.6f}")
209209
return formatted_params
210210

211-
def export_to_param(self, filename_out: str, file_format: str = "missionplanner") -> None:
211+
def export_to_param(
212+
self, filename_out: str, file_format: str = "missionplanner", content_header: Optional[list[str]] = None
213+
) -> None:
212214
"""
213215
Export parameters to a parameter file.
214216
215217
Args:
216218
filename_out: Output filename.
217219
file_format: File format ("missionplanner" or "mavproxy").
220+
content_header: Optional list of header lines to include at the top of the file.
218221
219222
"""
220223
formatted_params = self._format_params(file_format)
221224
with open(filename_out, "w", encoding="utf-8") as output_file:
225+
if content_header:
226+
output_file.write("\n".join(content_header) + "\n")
222227
output_file.writelines(line + "\n" for line in formatted_params)
223228

224229
@staticmethod

ardupilot_methodic_configurator/param_pid_adjustment_update.py

Lines changed: 57 additions & 76 deletions
Original file line numberDiff line numberDiff line change
@@ -17,17 +17,14 @@
1717
import argparse
1818
import os
1919
import re
20-
import subprocess
21-
from typing import Callable, Optional, Union
20+
from typing import Callable, Union
2221

2322
import argcomplete
2423
from argcomplete.completers import DirectoriesCompleter, FilesCompleter
2524

26-
from ardupilot_methodic_configurator.data_model_par_dict import ParDict
25+
from ardupilot_methodic_configurator.data_model_par_dict import PARAM_NAME_MAX_LEN, PARAM_NAME_REGEX, Par, ParDict
2726

28-
PARAM_NAME_REGEX = r"^[A-Z][A-Z_0-9]*$"
29-
PARAM_NAME_MAX_LEN = 16
30-
VERSION = "1.0"
27+
VERSION = "1.1"
3128

3229

3330
def create_argument_parser() -> argparse.ArgumentParser:
@@ -54,9 +51,9 @@ def create_argument_parser() -> argparse.ArgumentParser:
5451
parser.add_argument(
5552
"-a",
5653
"--adjustment_factor",
57-
type=ranged_type(float, 0.1, 0.8),
54+
type=ranged_type(float, 0.1, 1.2),
5855
default=0.5,
59-
help="The adjustment factor to apply to the optimized parameters. Must be in the interval 0.1 to 0.8. Default is 0.5.",
56+
help="The adjustment factor to apply to the optimized parameters. Must be in the interval 0.1 to 1.2. Default is 0.5.",
6057
)
6158
parser.add_argument(
6259
"-v",
@@ -100,72 +97,58 @@ def range_checker(arg: str) -> Union[int, float]:
10097
return range_checker
10198

10299

103-
class Par:
100+
def load_param_file_with_content(param_file: str) -> tuple[ParDict, list[str]]:
104101
"""
105-
A class representing a parameter with a value and an optional comment.
102+
Load parameter file into ParDict and return the file content as well.
106103
107-
Attributes:
108-
value (float): The value of the parameter.
109-
comment (str): An optional comment describing the parameter.
104+
This is a helper function that extends ParDict.load_param_file_into_dict()
105+
to also return the original file content lines for header preservation.
110106
111-
"""
107+
Args:
108+
param_file: Path to the parameter file.
112109
113-
def __init__(self, value: float, comment: Optional[str] = None) -> None:
114-
self.value = value
115-
self.comment = comment
116-
117-
@staticmethod
118-
def load_param_file_into_dict(param_file: str) -> tuple[ParDict, list[str]]:
119-
parameter_dict = {}
120-
content = []
121-
with open(param_file, encoding="utf-8") as f_handle:
122-
for n, f_line in enumerate(f_handle, start=1):
123-
line = f_line.strip()
124-
content.append(line)
125-
comment = None
126-
if not line or line.startswith("#"):
127-
continue
128-
if "#" in line:
129-
line, comment = line.split("#", 1)
130-
comment = comment.strip()
131-
if "," in line:
132-
parameter, value = line.split(",", 1)
133-
elif " " in line:
134-
parameter, value = line.split(" ", 1)
135-
elif "\t" in line:
136-
parameter, value = line.split("\t", 1)
137-
else:
138-
msg = f"Missing parameter-value separator: {line} in {param_file} line {n}"
139-
raise SystemExit(msg)
140-
if len(parameter) > PARAM_NAME_MAX_LEN:
141-
msg = f"Too long parameter name: {parameter} in {param_file} line {n}"
142-
raise SystemExit(msg)
143-
if not re.match(PARAM_NAME_REGEX, parameter):
144-
msg = f"Invalid characters in parameter name {parameter} in {param_file} line {n}"
145-
raise SystemExit(msg)
146-
try:
147-
fvalue = float(value)
148-
except ValueError as exc:
149-
msg = f"Invalid parameter value {value} in {param_file} line {n}"
150-
raise SystemExit(msg) from exc
151-
if parameter in parameter_dict:
152-
msg = f"Duplicated parameter {parameter} in {param_file} line {n}"
153-
raise SystemExit(msg)
154-
parameter_dict[parameter] = Par(fvalue, comment)
155-
return parameter_dict, content
156-
157-
@staticmethod
158-
def export_to_param(param_dict: ParDict, filename_out: str, content_header: Optional[list[str]] = None) -> None:
159-
if content_header is None:
160-
content_header = []
161-
with open(filename_out, "w", encoding="utf-8") as output_file:
162-
if content_header:
163-
output_file.write("\n".join(content_header) + "\n")
164-
for key, par in param_dict.items():
165-
line = f"{key},{format(par.value, '.6f').rstrip('0').rstrip('.')}"
166-
if par.comment:
167-
line += f" # {par.comment}"
168-
output_file.write(line + "\n")
110+
Returns:
111+
A tuple of (ParDict, list of file content lines).
112+
113+
"""
114+
parameter_dict = ParDict()
115+
content = []
116+
with open(param_file, encoding="utf-8") as f_handle:
117+
for n, f_line in enumerate(f_handle, start=1):
118+
line = f_line.strip()
119+
content.append(line)
120+
comment = None
121+
if not line or line.startswith("#"):
122+
continue
123+
if "#" in line:
124+
line, comment = line.split("#", 1)
125+
comment = comment.strip()
126+
if "," in line:
127+
parameter, value = line.split(",", 1)
128+
elif " " in line:
129+
parameter, value = line.split(" ", 1)
130+
elif "\t" in line:
131+
parameter, value = line.split("\t", 1)
132+
else:
133+
msg = f"Missing parameter-value separator: {line} in {param_file} line {n}"
134+
raise SystemExit(msg)
135+
parameter = parameter.strip()
136+
if len(parameter) > PARAM_NAME_MAX_LEN:
137+
msg = f"Too long parameter name: {parameter} in {param_file} line {n}"
138+
raise SystemExit(msg)
139+
if not re.match(PARAM_NAME_REGEX, parameter):
140+
msg = f"Invalid characters in parameter name {parameter} in {param_file} line {n}"
141+
raise SystemExit(msg)
142+
try:
143+
fvalue = float(value.strip())
144+
except ValueError as exc:
145+
msg = f"Invalid parameter value {value} in {param_file} line {n}"
146+
raise SystemExit(msg) from exc
147+
if parameter in parameter_dict:
148+
msg = f"Duplicated parameter {parameter} in {param_file} line {n}"
149+
raise SystemExit(msg)
150+
parameter_dict[parameter] = Par(fvalue, comment)
151+
return parameter_dict, content
169152

170153

171154
def update_pid_adjustment_params(
@@ -191,13 +174,13 @@ def update_pid_adjustment_params(
191174
pid_adjustment_file_path = os.path.join(directory, "16_pid_adjustment.param")
192175

193176
# Load the default parameter file into a dictionary (comment source)
194-
default_params_dict, _ = ParDict.load_param_file_into_dict(default_param_file_path)
177+
default_params_dict = ParDict.load_param_file_into_dict(default_param_file_path)
195178

196179
# Load the optimized parameter file into a dictionary (source)
197-
optimized_params_dict, _ = ParDict.load_param_file_into_dict(optimized_param_file_path)
180+
optimized_params_dict = ParDict.load_param_file_into_dict(optimized_param_file_path)
198181

199182
# Load the PID adjustment parameter file into a dictionary (destination)
200-
pid_adjustment_params_dict, content = ParDict.load_param_file_into_dict(pid_adjustment_file_path)
183+
pid_adjustment_params_dict, content = load_param_file_with_content(pid_adjustment_file_path)
201184

202185
if not default_params_dict:
203186
msg = f"Failed to load default parameters from {default_param_file_path}"
@@ -242,9 +225,7 @@ def main() -> None:
242225
args.directory, args.optimized_param_file, args.adjustment_factor
243226
)
244227
# export the updated PID adjust parameters to a file, preserving the first eight header lines
245-
ParDict.export_to_param(pid_adjustment_params_dict, pid_adjustment_file_path, content_header)
246-
# annotate each parameter with up-to date documentation
247-
subprocess.run(["./annotate_params.py", os.path.join(args.directory, "16_pid_adjustment.param")], check=True) # noqa: S603
228+
pid_adjustment_params_dict.export_to_param(pid_adjustment_file_path, content_header=content_header)
248229

249230

250231
if __name__ == "__main__":

0 commit comments

Comments
 (0)