Skip to content

Commit

Permalink
BUGFIX: Adapt to the 14_pid_adjustment.param rename to 15_pid_adjustm…
Browse files Browse the repository at this point in the history
…ent.param
  • Loading branch information
amilcarlucas committed May 20, 2024
1 parent 2fcf42d commit fadfce6
Show file tree
Hide file tree
Showing 2 changed files with 6 additions and 6 deletions.
8 changes: 4 additions & 4 deletions MethodicConfigurator/param_pid_adjustment_update.py
Original file line number Diff line number Diff line change
Expand Up @@ -32,9 +32,9 @@ def parse_arguments():
It loads three sets of parameters from files in the DIRECTORY directory:
00_default.param - the (complete) default parameters,
optimized_param_file - the (complete) optimized parameters, and
14_pid_adjustment.param - the (intermediate) PID adjustment parameters.
15_pid_adjustment.param - the (intermediate) PID adjustment parameters.
It calculates the PID adjustment parameter values based on the ADJUSTMENT_FACTOR argument.
It updates the intermediate parameter file 14_pid_adjustment.param with parameter comments
It updates the intermediate parameter file 15_pid_adjustment.param with parameter comments
explaining how their new value relates to the default parameter value.
""")
parser.add_argument("-d", "--directory",
Expand Down Expand Up @@ -155,7 +155,7 @@ def update_pid_adjustment_params(directory: str, optimized_param_file: str, adju
"""
default_param_file_path = os.path.join(directory, "00_default.param")
optimized_param_file_path = os.path.join(directory, optimized_param_file)
pid_adjustment_file_path = os.path.join(directory, "14_pid_adjustment.param")
pid_adjustment_file_path = os.path.join(directory, "15_pid_adjustment.param")

# Load the default parameter file into a dictionary (comment source)
default_params_dict, _ = Par.load_param_file_into_dict(default_param_file_path)
Expand Down Expand Up @@ -203,7 +203,7 @@ def main():
# export the updated PID adjust parameters to a file, preserving the first eight header lines
Par.export_to_param(pid_adjustment_params_dict, pid_adjustment_file_path, content_header)
# annotate each parameter with up-to date documentation
subprocess.run(['./annotate_params.py', os.path.join(args.directory, "14_pid_adjustment.param")], check=True)
subprocess.run(['./annotate_params.py', os.path.join(args.directory, "15_pid_adjustment.param")], check=True)


if __name__ == "__main__":
Expand Down
4 changes: 2 additions & 2 deletions unittests/param_pid_adjustment_update_test.py
Original file line number Diff line number Diff line change
Expand Up @@ -224,7 +224,7 @@ def setUp(self):
os.mkdir(self.test_dir)
# Create a default, adjustment and optimized parameter file for testing
self.default_param_file = os.path.join(self.test_dir, '00_default.param')
self.adjustment_param_file = os.path.join(self.test_dir, '14_pid_adjustment.param')
self.adjustment_param_file = os.path.join(self.test_dir, '15_pid_adjustment.param')
self.optimized_param_file = os.path.join(self.test_dir, 'optimized_parameter_file.param')
with open(self.default_param_file, 'w', encoding='utf-8') as f:
f.write('PARAM1,1.0\nPARAM2,2.0\nPARAM3,3.0\n')
Expand Down Expand Up @@ -296,7 +296,7 @@ def test_empty_adjustment_file(self):
with self.assertRaises(SystemExit) as cm:
update_pid_adjustment_params(self.test_dir, os.path.basename(self.optimized_param_file), 0.5)
self.assertEqual(cm.exception.args[0],
"Failed to load PID adjustment parameters from test_directory/14_pid_adjustment.param")
"Failed to load PID adjustment parameters from test_directory/15_pid_adjustment.param")

def test_zero_default_value(self):
# Set a parameter in the default parameter file to zero
Expand Down

0 comments on commit fadfce6

Please sign in to comment.