From 228c4e10f7d5ecf4f4ae54b628af760bb7682fcc Mon Sep 17 00:00:00 2001 From: Zhe Shen Date: Tue, 26 Mar 2024 16:43:57 +0900 Subject: [PATCH 01/20] add the consistency checker for the parameters in the controllers and the dynamics Signed-off-by: Zhe Shen --- control/consistency_checker.py | 60 ++++++++++++++++++++++++++++++++++ 1 file changed, 60 insertions(+) create mode 100644 control/consistency_checker.py diff --git a/control/consistency_checker.py b/control/consistency_checker.py new file mode 100644 index 00000000..a6ab50d9 --- /dev/null +++ b/control/consistency_checker.py @@ -0,0 +1,60 @@ +import yaml +import math + +def read_yaml(file_path): + """Read YAML file and return the data.""" + with open(file_path, 'r') as file: + return yaml.safe_load(file) + +# paths to the YAML files +mpc_param_file_path = "/home/zheshen/pilot-auto.x2/src/autoware/launcher/autoware_launch/config/control/trajectory_follower/lateral/mpc.param.yaml" +pid_param_file_path = "/home/zheshen/pilot-auto.x2/src/autoware/launcher/autoware_launch/config/control/trajectory_follower/longitudinal/pid.param.yaml" +simulator_model_param_file_path = "/home/zheshen/pilot-auto.x2/src/description/vehicle/j6_gen1_description/j6_gen1_description/config/simulator_model.param.yaml" + +# read the YAML files +mpc_params = read_yaml(mpc_param_file_path)["/**"]["ros__parameters"] +pid_params = read_yaml(pid_param_file_path)["/**"]["ros__parameters"] +simulator_model_params = read_yaml(simulator_model_param_file_path)["/**"]["ros__parameters"] + +# compare the parameters +results = [ +# "mpc_vehicle_model_type_consistency": mpc_params["vehicle_model_type"] == simulator_model_params["vehicle_model_type"], # Should not compare directly. Modify later!! + ("[MPC] steer_delay_difference: {}, (controller: {}, simulator: {})".format( + simulator_model_params["steer_time_delay"] - mpc_params["input_delay"], + mpc_params["input_delay"], + simulator_model_params["steer_time_delay"])), + + ("[MPC] steer_time_constant_difference: {}, (controller: {}, simulator: {})".format( + simulator_model_params["steer_time_constant"] - mpc_params["vehicle_model_steer_tau"], + mpc_params["vehicle_model_steer_tau"], + simulator_model_params["steer_time_constant"])), + + ("[MPC] acceleration_limit_difference: {}, (controller: {}, simulator: {})".format( + simulator_model_params["vel_rate_lim"] - mpc_params["acceleration_limit"], + mpc_params["acceleration_limit"], + simulator_model_params["vel_rate_lim"])), + + ("[MPC] max_steer_rate_lim_difference_by_curvature: {}, (controller: {}, simulator: {})".format( + simulator_model_params["steer_rate_lim"] - max(mpc_params["steer_rate_lim_dps_list_by_curvature"]) * (math.pi / 180), + max(mpc_params["steer_rate_lim_dps_list_by_curvature"]) * (math.pi / 180), + simulator_model_params["steer_rate_lim"])), + + ("[MPC] max_steer_rate_lim_difference_by_velocity: {}, (controller: {}, simulator: {})".format( + simulator_model_params["steer_rate_lim"] - max(mpc_params["steer_rate_lim_dps_list_by_velocity"]) * (math.pi / 180), + max(mpc_params["steer_rate_lim_dps_list_by_velocity"]) * (math.pi / 180), + simulator_model_params["steer_rate_lim"])), + + ("[PID] max_acc_difference: {}, (controller: {}, simulator: {})".format( + simulator_model_params["vel_rate_lim"] - pid_params["max_acc"], + pid_params["max_acc"], + simulator_model_params["vel_rate_lim"])), + + ("[PID] min_acc_difference: {}, (controller: {}, simulator: {})".format( + - simulator_model_params["vel_rate_lim"] - pid_params["min_acc"], + pid_params["min_acc"], + - simulator_model_params["vel_rate_lim"])) +] + +# print the results +for item in results: + print(item) From 96af1e8145e95f0f6e3168cd061ec369b9345097 Mon Sep 17 00:00:00 2001 From: "pre-commit-ci[bot]" <66853113+pre-commit-ci[bot]@users.noreply.github.com> Date: Tue, 26 Mar 2024 07:55:54 +0000 Subject: [PATCH 02/20] style(pre-commit): autofix --- control/consistency_checker.py | 94 +++++++++++++++++++++------------- 1 file changed, 57 insertions(+), 37 deletions(-) diff --git a/control/consistency_checker.py b/control/consistency_checker.py index a6ab50d9..4537047d 100644 --- a/control/consistency_checker.py +++ b/control/consistency_checker.py @@ -1,11 +1,14 @@ -import yaml import math +import yaml + + def read_yaml(file_path): """Read YAML file and return the data.""" - with open(file_path, 'r') as file: + with open(file_path, "r") as file: return yaml.safe_load(file) + # paths to the YAML files mpc_param_file_path = "/home/zheshen/pilot-auto.x2/src/autoware/launcher/autoware_launch/config/control/trajectory_follower/lateral/mpc.param.yaml" pid_param_file_path = "/home/zheshen/pilot-auto.x2/src/autoware/launcher/autoware_launch/config/control/trajectory_follower/longitudinal/pid.param.yaml" @@ -18,41 +21,58 @@ def read_yaml(file_path): # compare the parameters results = [ -# "mpc_vehicle_model_type_consistency": mpc_params["vehicle_model_type"] == simulator_model_params["vehicle_model_type"], # Should not compare directly. Modify later!! - ("[MPC] steer_delay_difference: {}, (controller: {}, simulator: {})".format( - simulator_model_params["steer_time_delay"] - mpc_params["input_delay"], - mpc_params["input_delay"], - simulator_model_params["steer_time_delay"])), - - ("[MPC] steer_time_constant_difference: {}, (controller: {}, simulator: {})".format( - simulator_model_params["steer_time_constant"] - mpc_params["vehicle_model_steer_tau"], - mpc_params["vehicle_model_steer_tau"], - simulator_model_params["steer_time_constant"])), - - ("[MPC] acceleration_limit_difference: {}, (controller: {}, simulator: {})".format( - simulator_model_params["vel_rate_lim"] - mpc_params["acceleration_limit"], - mpc_params["acceleration_limit"], - simulator_model_params["vel_rate_lim"])), - - ("[MPC] max_steer_rate_lim_difference_by_curvature: {}, (controller: {}, simulator: {})".format( - simulator_model_params["steer_rate_lim"] - max(mpc_params["steer_rate_lim_dps_list_by_curvature"]) * (math.pi / 180), - max(mpc_params["steer_rate_lim_dps_list_by_curvature"]) * (math.pi / 180), - simulator_model_params["steer_rate_lim"])), - - ("[MPC] max_steer_rate_lim_difference_by_velocity: {}, (controller: {}, simulator: {})".format( - simulator_model_params["steer_rate_lim"] - max(mpc_params["steer_rate_lim_dps_list_by_velocity"]) * (math.pi / 180), - max(mpc_params["steer_rate_lim_dps_list_by_velocity"]) * (math.pi / 180), - simulator_model_params["steer_rate_lim"])), - - ("[PID] max_acc_difference: {}, (controller: {}, simulator: {})".format( - simulator_model_params["vel_rate_lim"] - pid_params["max_acc"], - pid_params["max_acc"], - simulator_model_params["vel_rate_lim"])), - - ("[PID] min_acc_difference: {}, (controller: {}, simulator: {})".format( - - simulator_model_params["vel_rate_lim"] - pid_params["min_acc"], - pid_params["min_acc"], - - simulator_model_params["vel_rate_lim"])) + # "mpc_vehicle_model_type_consistency": mpc_params["vehicle_model_type"] == simulator_model_params["vehicle_model_type"], # Should not compare directly. Modify later!! + ( + "[MPC] steer_delay_difference: {}, (controller: {}, simulator: {})".format( + simulator_model_params["steer_time_delay"] - mpc_params["input_delay"], + mpc_params["input_delay"], + simulator_model_params["steer_time_delay"], + ) + ), + ( + "[MPC] steer_time_constant_difference: {}, (controller: {}, simulator: {})".format( + simulator_model_params["steer_time_constant"] - mpc_params["vehicle_model_steer_tau"], + mpc_params["vehicle_model_steer_tau"], + simulator_model_params["steer_time_constant"], + ) + ), + ( + "[MPC] acceleration_limit_difference: {}, (controller: {}, simulator: {})".format( + simulator_model_params["vel_rate_lim"] - mpc_params["acceleration_limit"], + mpc_params["acceleration_limit"], + simulator_model_params["vel_rate_lim"], + ) + ), + ( + "[MPC] max_steer_rate_lim_difference_by_curvature: {}, (controller: {}, simulator: {})".format( + simulator_model_params["steer_rate_lim"] + - max(mpc_params["steer_rate_lim_dps_list_by_curvature"]) * (math.pi / 180), + max(mpc_params["steer_rate_lim_dps_list_by_curvature"]) * (math.pi / 180), + simulator_model_params["steer_rate_lim"], + ) + ), + ( + "[MPC] max_steer_rate_lim_difference_by_velocity: {}, (controller: {}, simulator: {})".format( + simulator_model_params["steer_rate_lim"] + - max(mpc_params["steer_rate_lim_dps_list_by_velocity"]) * (math.pi / 180), + max(mpc_params["steer_rate_lim_dps_list_by_velocity"]) * (math.pi / 180), + simulator_model_params["steer_rate_lim"], + ) + ), + ( + "[PID] max_acc_difference: {}, (controller: {}, simulator: {})".format( + simulator_model_params["vel_rate_lim"] - pid_params["max_acc"], + pid_params["max_acc"], + simulator_model_params["vel_rate_lim"], + ) + ), + ( + "[PID] min_acc_difference: {}, (controller: {}, simulator: {})".format( + -simulator_model_params["vel_rate_lim"] - pid_params["min_acc"], + pid_params["min_acc"], + -simulator_model_params["vel_rate_lim"], + ) + ), ] # print the results From 1625dfea01a8b089b4ac37470376d0e8b19ddb17 Mon Sep 17 00:00:00 2001 From: Zhe Shen Date: Wed, 27 Mar 2024 10:38:57 +0900 Subject: [PATCH 03/20] delete the comments Signed-off-by: Zhe Shen --- control/consistency_checker.py | 14 +++----------- 1 file changed, 3 insertions(+), 11 deletions(-) diff --git a/control/consistency_checker.py b/control/consistency_checker.py index 4537047d..fb741f31 100644 --- a/control/consistency_checker.py +++ b/control/consistency_checker.py @@ -1,27 +1,20 @@ import math - import yaml - def read_yaml(file_path): """Read YAML file and return the data.""" with open(file_path, "r") as file: return yaml.safe_load(file) +mpc_param_file_path = "/home/shen/pilot-auto.x2/src/autoware/launcher/autoware_launch/config/control/trajectory_follower/lateral/mpc.param.yaml" +pid_param_file_path = "/home/shen/pilot-auto.x2/src/autoware/launcher/autoware_launch/config/control/trajectory_follower/longitudinal/pid.param.yaml" +simulator_model_param_file_path = "/home/shen/pilot-auto.x2/src/description/vehicle/j6_gen1_description/j6_gen1_description/config/simulator_model.param.yaml" -# paths to the YAML files -mpc_param_file_path = "/home/zheshen/pilot-auto.x2/src/autoware/launcher/autoware_launch/config/control/trajectory_follower/lateral/mpc.param.yaml" -pid_param_file_path = "/home/zheshen/pilot-auto.x2/src/autoware/launcher/autoware_launch/config/control/trajectory_follower/longitudinal/pid.param.yaml" -simulator_model_param_file_path = "/home/zheshen/pilot-auto.x2/src/description/vehicle/j6_gen1_description/j6_gen1_description/config/simulator_model.param.yaml" - -# read the YAML files mpc_params = read_yaml(mpc_param_file_path)["/**"]["ros__parameters"] pid_params = read_yaml(pid_param_file_path)["/**"]["ros__parameters"] simulator_model_params = read_yaml(simulator_model_param_file_path)["/**"]["ros__parameters"] -# compare the parameters results = [ - # "mpc_vehicle_model_type_consistency": mpc_params["vehicle_model_type"] == simulator_model_params["vehicle_model_type"], # Should not compare directly. Modify later!! ( "[MPC] steer_delay_difference: {}, (controller: {}, simulator: {})".format( simulator_model_params["steer_time_delay"] - mpc_params["input_delay"], @@ -75,6 +68,5 @@ def read_yaml(file_path): ), ] -# print the results for item in results: print(item) From a4162bdeb8f3adb56fbde68505c5bdc023716c91 Mon Sep 17 00:00:00 2001 From: "pre-commit-ci[bot]" <66853113+pre-commit-ci[bot]@users.noreply.github.com> Date: Wed, 27 Mar 2024 01:39:24 +0000 Subject: [PATCH 04/20] style(pre-commit): autofix --- control/consistency_checker.py | 3 +++ 1 file changed, 3 insertions(+) diff --git a/control/consistency_checker.py b/control/consistency_checker.py index fb741f31..c1b42621 100644 --- a/control/consistency_checker.py +++ b/control/consistency_checker.py @@ -1,11 +1,14 @@ import math + import yaml + def read_yaml(file_path): """Read YAML file and return the data.""" with open(file_path, "r") as file: return yaml.safe_load(file) + mpc_param_file_path = "/home/shen/pilot-auto.x2/src/autoware/launcher/autoware_launch/config/control/trajectory_follower/lateral/mpc.param.yaml" pid_param_file_path = "/home/shen/pilot-auto.x2/src/autoware/launcher/autoware_launch/config/control/trajectory_follower/longitudinal/pid.param.yaml" simulator_model_param_file_path = "/home/shen/pilot-auto.x2/src/description/vehicle/j6_gen1_description/j6_gen1_description/config/simulator_model.param.yaml" From bfa607cc9a66d843d4f2a1c3a1649610106e2e8c Mon Sep 17 00:00:00 2001 From: Zhe Shen Date: Wed, 27 Mar 2024 13:34:24 +0900 Subject: [PATCH 05/20] path added automatically Signed-off-by: Zhe Shen --- control/consistency_checker.py | 9 ++++++--- 1 file changed, 6 insertions(+), 3 deletions(-) diff --git a/control/consistency_checker.py b/control/consistency_checker.py index c1b42621..ec9a17ec 100644 --- a/control/consistency_checker.py +++ b/control/consistency_checker.py @@ -1,6 +1,7 @@ import math import yaml +from ament_index_python.packages import get_package_share_directory def read_yaml(file_path): @@ -8,10 +9,12 @@ def read_yaml(file_path): with open(file_path, "r") as file: return yaml.safe_load(file) +autoware_launch_path = get_package_share_directory('autoware_launch') +vehicle_description_path = get_package_share_directory('j6_gen1_description') -mpc_param_file_path = "/home/shen/pilot-auto.x2/src/autoware/launcher/autoware_launch/config/control/trajectory_follower/lateral/mpc.param.yaml" -pid_param_file_path = "/home/shen/pilot-auto.x2/src/autoware/launcher/autoware_launch/config/control/trajectory_follower/longitudinal/pid.param.yaml" -simulator_model_param_file_path = "/home/shen/pilot-auto.x2/src/description/vehicle/j6_gen1_description/j6_gen1_description/config/simulator_model.param.yaml" +mpc_param_file_path = f"{autoware_launch_path}/config/control/trajectory_follower/lateral/mpc.param.yaml" +pid_param_file_path = f"{autoware_launch_path}/config/control/trajectory_follower/longitudinal/pid.param.yaml" +simulator_model_param_file_path = f"{vehicle_description_path}/config/simulator_model.param.yaml" mpc_params = read_yaml(mpc_param_file_path)["/**"]["ros__parameters"] pid_params = read_yaml(pid_param_file_path)["/**"]["ros__parameters"] From 615775dbf7d57eef47a7c72617aad0cecdc769d4 Mon Sep 17 00:00:00 2001 From: "pre-commit-ci[bot]" <66853113+pre-commit-ci[bot]@users.noreply.github.com> Date: Wed, 27 Mar 2024 04:34:41 +0000 Subject: [PATCH 06/20] style(pre-commit): autofix --- control/consistency_checker.py | 15 ++++++++++----- 1 file changed, 10 insertions(+), 5 deletions(-) diff --git a/control/consistency_checker.py b/control/consistency_checker.py index ec9a17ec..03ab7746 100644 --- a/control/consistency_checker.py +++ b/control/consistency_checker.py @@ -1,7 +1,7 @@ import math -import yaml from ament_index_python.packages import get_package_share_directory +import yaml def read_yaml(file_path): @@ -9,11 +9,16 @@ def read_yaml(file_path): with open(file_path, "r") as file: return yaml.safe_load(file) -autoware_launch_path = get_package_share_directory('autoware_launch') -vehicle_description_path = get_package_share_directory('j6_gen1_description') -mpc_param_file_path = f"{autoware_launch_path}/config/control/trajectory_follower/lateral/mpc.param.yaml" -pid_param_file_path = f"{autoware_launch_path}/config/control/trajectory_follower/longitudinal/pid.param.yaml" +autoware_launch_path = get_package_share_directory("autoware_launch") +vehicle_description_path = get_package_share_directory("j6_gen1_description") + +mpc_param_file_path = ( + f"{autoware_launch_path}/config/control/trajectory_follower/lateral/mpc.param.yaml" +) +pid_param_file_path = ( + f"{autoware_launch_path}/config/control/trajectory_follower/longitudinal/pid.param.yaml" +) simulator_model_param_file_path = f"{vehicle_description_path}/config/simulator_model.param.yaml" mpc_params = read_yaml(mpc_param_file_path)["/**"]["ros__parameters"] From 40f63540ef837fdeb66d3c6a0463de037bd0b3f9 Mon Sep 17 00:00:00 2001 From: Zhe Shen Date: Wed, 27 Mar 2024 14:03:21 +0900 Subject: [PATCH 07/20] the automatically found path can be overridden by passing in the arguments. e.g., --mpc_param_file path/to/the/file Signed-off-by: Zhe Shen --- control/consistency_checker.py | 19 +++++++++++++++---- 1 file changed, 15 insertions(+), 4 deletions(-) diff --git a/control/consistency_checker.py b/control/consistency_checker.py index 03ab7746..8d9febc7 100644 --- a/control/consistency_checker.py +++ b/control/consistency_checker.py @@ -1,5 +1,5 @@ import math - +import argparse from ament_index_python.packages import get_package_share_directory import yaml @@ -13,13 +13,24 @@ def read_yaml(file_path): autoware_launch_path = get_package_share_directory("autoware_launch") vehicle_description_path = get_package_share_directory("j6_gen1_description") -mpc_param_file_path = ( +default_mpc_param_file_path = ( f"{autoware_launch_path}/config/control/trajectory_follower/lateral/mpc.param.yaml" ) -pid_param_file_path = ( +default_pid_param_file_path = ( f"{autoware_launch_path}/config/control/trajectory_follower/longitudinal/pid.param.yaml" ) -simulator_model_param_file_path = f"{vehicle_description_path}/config/simulator_model.param.yaml" +default_simulator_model_param_file_path = f"{vehicle_description_path}/config/simulator_model.param.yaml" + +parser = argparse.ArgumentParser(description='Process the parameters of the controllers and simulator.') + +parser.add_argument('--mpc_param_file', help='Override the default MPC parameter file path', default=default_mpc_param_file_path) +parser.add_argument('--pid_param_file', help='Override the default PID parameter file path', default=default_pid_param_file_path) +parser.add_argument('--simulator_model_param_file', help='Override the default simulator model parameter file path', default=default_simulator_model_param_file_path) + +args = parser.parse_args() +mpc_param_file_path = args.mpc_param_file +pid_param_file_path = args.pid_param_file +simulator_model_param_file_path = args.simulator_model_param_file mpc_params = read_yaml(mpc_param_file_path)["/**"]["ros__parameters"] pid_params = read_yaml(pid_param_file_path)["/**"]["ros__parameters"] From 566d68a8f80a28760a13203b22c7d9b814b69430 Mon Sep 17 00:00:00 2001 From: "pre-commit-ci[bot]" <66853113+pre-commit-ci[bot]@users.noreply.github.com> Date: Wed, 27 Mar 2024 05:03:40 +0000 Subject: [PATCH 08/20] style(pre-commit): autofix --- control/consistency_checker.py | 29 +++++++++++++++++++++++------ 1 file changed, 23 insertions(+), 6 deletions(-) diff --git a/control/consistency_checker.py b/control/consistency_checker.py index 8d9febc7..697a2f67 100644 --- a/control/consistency_checker.py +++ b/control/consistency_checker.py @@ -1,5 +1,6 @@ -import math import argparse +import math + from ament_index_python.packages import get_package_share_directory import yaml @@ -19,13 +20,29 @@ def read_yaml(file_path): default_pid_param_file_path = ( f"{autoware_launch_path}/config/control/trajectory_follower/longitudinal/pid.param.yaml" ) -default_simulator_model_param_file_path = f"{vehicle_description_path}/config/simulator_model.param.yaml" +default_simulator_model_param_file_path = ( + f"{vehicle_description_path}/config/simulator_model.param.yaml" +) -parser = argparse.ArgumentParser(description='Process the parameters of the controllers and simulator.') +parser = argparse.ArgumentParser( + description="Process the parameters of the controllers and simulator." +) -parser.add_argument('--mpc_param_file', help='Override the default MPC parameter file path', default=default_mpc_param_file_path) -parser.add_argument('--pid_param_file', help='Override the default PID parameter file path', default=default_pid_param_file_path) -parser.add_argument('--simulator_model_param_file', help='Override the default simulator model parameter file path', default=default_simulator_model_param_file_path) +parser.add_argument( + "--mpc_param_file", + help="Override the default MPC parameter file path", + default=default_mpc_param_file_path, +) +parser.add_argument( + "--pid_param_file", + help="Override the default PID parameter file path", + default=default_pid_param_file_path, +) +parser.add_argument( + "--simulator_model_param_file", + help="Override the default simulator model parameter file path", + default=default_simulator_model_param_file_path, +) args = parser.parse_args() mpc_param_file_path = args.mpc_param_file From 1cf2db8e2265ad537a8fcbe4e869e42d6b90af05 Mon Sep 17 00:00:00 2001 From: Zhe Shen Date: Wed, 27 Mar 2024 16:40:14 +0900 Subject: [PATCH 09/20] set the default vehicle description and parser it Signed-off-by: Zhe Shen --- control/consistency_checker.py | 38 ++++++++++++++-------------------- 1 file changed, 15 insertions(+), 23 deletions(-) diff --git a/control/consistency_checker.py b/control/consistency_checker.py index 697a2f67..3c6cfef5 100644 --- a/control/consistency_checker.py +++ b/control/consistency_checker.py @@ -10,44 +10,36 @@ def read_yaml(file_path): with open(file_path, "r") as file: return yaml.safe_load(file) - -autoware_launch_path = get_package_share_directory("autoware_launch") -vehicle_description_path = get_package_share_directory("j6_gen1_description") - -default_mpc_param_file_path = ( - f"{autoware_launch_path}/config/control/trajectory_follower/lateral/mpc.param.yaml" -) -default_pid_param_file_path = ( - f"{autoware_launch_path}/config/control/trajectory_follower/longitudinal/pid.param.yaml" -) -default_simulator_model_param_file_path = ( - f"{vehicle_description_path}/config/simulator_model.param.yaml" -) - parser = argparse.ArgumentParser( description="Process the parameters of the controllers and simulator." ) +parser.add_argument( + "--vehicle_description", + help="Specify the vehicle description package name", + default="sample_vehicle_description" +) parser.add_argument( "--mpc_param_file", - help="Override the default MPC parameter file path", - default=default_mpc_param_file_path, + help="Override the default MPC parameter file path" ) parser.add_argument( "--pid_param_file", - help="Override the default PID parameter file path", - default=default_pid_param_file_path, + help="Override the default PID parameter file path" ) parser.add_argument( "--simulator_model_param_file", - help="Override the default simulator model parameter file path", - default=default_simulator_model_param_file_path, + help="Override the default simulator model parameter file path" ) args = parser.parse_args() -mpc_param_file_path = args.mpc_param_file -pid_param_file_path = args.pid_param_file -simulator_model_param_file_path = args.simulator_model_param_file + +autoware_launch_path = get_package_share_directory("autoware_launch") +vehicle_description_path = get_package_share_directory(args.vehicle_description) + +mpc_param_file_path = args.mpc_param_file if args.mpc_param_file else f"{autoware_launch_path}/config/control/trajectory_follower/lateral/mpc.param.yaml" +pid_param_file_path = args.pid_param_file if args.pid_param_file else f"{autoware_launch_path}/config/control/trajectory_follower/longitudinal/pid.param.yaml" +simulator_model_param_file_path = args.simulator_model_param_file if args.simulator_model_param_file else f"{vehicle_description_path}/config/simulator_model.param.yaml" mpc_params = read_yaml(mpc_param_file_path)["/**"]["ros__parameters"] pid_params = read_yaml(pid_param_file_path)["/**"]["ros__parameters"] From 19c1b00e0bf04454135005927c8148a3c5140b8f Mon Sep 17 00:00:00 2001 From: "pre-commit-ci[bot]" <66853113+pre-commit-ci[bot]@users.noreply.github.com> Date: Wed, 27 Mar 2024 07:40:32 +0000 Subject: [PATCH 10/20] style(pre-commit): autofix --- control/consistency_checker.py | 34 ++++++++++++++++++++-------------- 1 file changed, 20 insertions(+), 14 deletions(-) diff --git a/control/consistency_checker.py b/control/consistency_checker.py index 3c6cfef5..900b186a 100644 --- a/control/consistency_checker.py +++ b/control/consistency_checker.py @@ -10,6 +10,7 @@ def read_yaml(file_path): with open(file_path, "r") as file: return yaml.safe_load(file) + parser = argparse.ArgumentParser( description="Process the parameters of the controllers and simulator." ) @@ -17,19 +18,12 @@ def read_yaml(file_path): parser.add_argument( "--vehicle_description", help="Specify the vehicle description package name", - default="sample_vehicle_description" -) -parser.add_argument( - "--mpc_param_file", - help="Override the default MPC parameter file path" -) -parser.add_argument( - "--pid_param_file", - help="Override the default PID parameter file path" + default="sample_vehicle_description", ) +parser.add_argument("--mpc_param_file", help="Override the default MPC parameter file path") +parser.add_argument("--pid_param_file", help="Override the default PID parameter file path") parser.add_argument( - "--simulator_model_param_file", - help="Override the default simulator model parameter file path" + "--simulator_model_param_file", help="Override the default simulator model parameter file path" ) args = parser.parse_args() @@ -37,9 +31,21 @@ def read_yaml(file_path): autoware_launch_path = get_package_share_directory("autoware_launch") vehicle_description_path = get_package_share_directory(args.vehicle_description) -mpc_param_file_path = args.mpc_param_file if args.mpc_param_file else f"{autoware_launch_path}/config/control/trajectory_follower/lateral/mpc.param.yaml" -pid_param_file_path = args.pid_param_file if args.pid_param_file else f"{autoware_launch_path}/config/control/trajectory_follower/longitudinal/pid.param.yaml" -simulator_model_param_file_path = args.simulator_model_param_file if args.simulator_model_param_file else f"{vehicle_description_path}/config/simulator_model.param.yaml" +mpc_param_file_path = ( + args.mpc_param_file + if args.mpc_param_file + else f"{autoware_launch_path}/config/control/trajectory_follower/lateral/mpc.param.yaml" +) +pid_param_file_path = ( + args.pid_param_file + if args.pid_param_file + else f"{autoware_launch_path}/config/control/trajectory_follower/longitudinal/pid.param.yaml" +) +simulator_model_param_file_path = ( + args.simulator_model_param_file + if args.simulator_model_param_file + else f"{vehicle_description_path}/config/simulator_model.param.yaml" +) mpc_params = read_yaml(mpc_param_file_path)["/**"]["ros__parameters"] pid_params = read_yaml(pid_param_file_path)["/**"]["ros__parameters"] From 951636932f8bd63097a1558265167afa35bf3ee5 Mon Sep 17 00:00:00 2001 From: Zhe Shen Date: Thu, 28 Mar 2024 13:14:41 +0900 Subject: [PATCH 11/20] add the error output with color Signed-off-by: Zhe Shen --- control/consistency_checker.py | 18 +++++++++++++++++- 1 file changed, 17 insertions(+), 1 deletion(-) diff --git a/control/consistency_checker.py b/control/consistency_checker.py index 900b186a..0c0991f4 100644 --- a/control/consistency_checker.py +++ b/control/consistency_checker.py @@ -106,4 +106,20 @@ def read_yaml(file_path): ] for item in results: - print(item) + description = item.split(",")[0] # 提取描述部分,例如 "[MPC] steer_delay_difference: 1.0" + value = float(description.split(":")[1].strip()) # 提取差异值 + error_message = "" + if "steer_delay_difference" in item or "steer_time_constant_difference" in item: + if value != 0.0: + error_message = "\033[91m [ERROR] The parameters of the controller and simulator should be identical.\033[0m" + if "acceleration_limit_difference" in item: + if value < 0: + error_message = "\033[91m [ERROR] The parameter of the controller should be smaller than the parameter of the simulator.\033[0m" + if "max_steer_rate_lim_difference_by_curvature" in item or "max_steer_rate_lim_difference_by_velocity" in item: + if value < 0: + error_message = "\033[91m [ERROR] The parameter of the controller should be smaller than the parameter of the simulator.\033[0m" + if "max_acc_difference" in item and value < 0: + error_message = "\033[91m [ERROR] The parameter of the controller should be smaller than the parameter of the simulator.\033[0m" + if "min_acc_difference" in item and value > 0: + error_message = "\033[91m [ERROR] The parameter of the controller should be bigger than the parameter of the simulator.\033[0m" + print(f"{item}{error_message}") From 309442eb2c804e5e1a9800be2a4b42a78b33a720 Mon Sep 17 00:00:00 2001 From: "pre-commit-ci[bot]" <66853113+pre-commit-ci[bot]@users.noreply.github.com> Date: Thu, 28 Mar 2024 04:14:58 +0000 Subject: [PATCH 12/20] style(pre-commit): autofix --- control/consistency_checker.py | 5 ++++- 1 file changed, 4 insertions(+), 1 deletion(-) diff --git a/control/consistency_checker.py b/control/consistency_checker.py index 0c0991f4..c1ea0fa7 100644 --- a/control/consistency_checker.py +++ b/control/consistency_checker.py @@ -115,7 +115,10 @@ def read_yaml(file_path): if "acceleration_limit_difference" in item: if value < 0: error_message = "\033[91m [ERROR] The parameter of the controller should be smaller than the parameter of the simulator.\033[0m" - if "max_steer_rate_lim_difference_by_curvature" in item or "max_steer_rate_lim_difference_by_velocity" in item: + if ( + "max_steer_rate_lim_difference_by_curvature" in item + or "max_steer_rate_lim_difference_by_velocity" in item + ): if value < 0: error_message = "\033[91m [ERROR] The parameter of the controller should be smaller than the parameter of the simulator.\033[0m" if "max_acc_difference" in item and value < 0: From f6939a282d5a5c463735817be3b9707a452435bb Mon Sep 17 00:00:00 2001 From: Zhe Shen Date: Thu, 28 Mar 2024 13:45:44 +0900 Subject: [PATCH 13/20] delete the comments Signed-off-by: Zhe Shen --- control/consistency_checker.py | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/control/consistency_checker.py b/control/consistency_checker.py index c1ea0fa7..8be4ce74 100644 --- a/control/consistency_checker.py +++ b/control/consistency_checker.py @@ -106,8 +106,8 @@ def read_yaml(file_path): ] for item in results: - description = item.split(",")[0] # 提取描述部分,例如 "[MPC] steer_delay_difference: 1.0" - value = float(description.split(":")[1].strip()) # 提取差异值 + description = item.split(",")[0] + value = float(description.split(":")[1].strip()) error_message = "" if "steer_delay_difference" in item or "steer_time_constant_difference" in item: if value != 0.0: From ed97d0b1fc1cd4f56b8f722ae90df15415ee6136 Mon Sep 17 00:00:00 2001 From: Zhe Shen Date: Thu, 28 Mar 2024 16:16:45 +0900 Subject: [PATCH 14/20] reorganize the output style in error message Signed-off-by: Zhe Shen --- control/consistency_checker.py | 19 +++++++++---------- 1 file changed, 9 insertions(+), 10 deletions(-) diff --git a/control/consistency_checker.py b/control/consistency_checker.py index 8be4ce74..634f1618 100644 --- a/control/consistency_checker.py +++ b/control/consistency_checker.py @@ -111,18 +111,17 @@ def read_yaml(file_path): error_message = "" if "steer_delay_difference" in item or "steer_time_constant_difference" in item: if value != 0.0: - error_message = "\033[91m [ERROR] The parameters of the controller and simulator should be identical.\033[0m" - if "acceleration_limit_difference" in item: - if value < 0: - error_message = "\033[91m [ERROR] The parameter of the controller should be smaller than the parameter of the simulator.\033[0m" + error_message = "[ERROR] The parameters of the controller and simulator should be identical.\033[0m" if ( - "max_steer_rate_lim_difference_by_curvature" in item + "acceleration_limit_difference" in item + or "max_steer_rate_lim_difference_by_curvature" in item or "max_steer_rate_lim_difference_by_velocity" in item + or "max_acc_difference" in item ): if value < 0: - error_message = "\033[91m [ERROR] The parameter of the controller should be smaller than the parameter of the simulator.\033[0m" - if "max_acc_difference" in item and value < 0: - error_message = "\033[91m [ERROR] The parameter of the controller should be smaller than the parameter of the simulator.\033[0m" + error_message = "[ERROR] The parameter of the controller should be smaller than the parameter of the simulator.\033[0m" if "min_acc_difference" in item and value > 0: - error_message = "\033[91m [ERROR] The parameter of the controller should be bigger than the parameter of the simulator.\033[0m" - print(f"{item}{error_message}") + error_message = "[ERROR] The parameter of the controller should be bigger than the parameter of the simulator.\033[0m" + print(f"{item}") + if error_message: + print(f"\033[91m{error_message}\033[0m\n") From ec501da9c4242cd08ff6ad6ca3cb15aae0eca0f4 Mon Sep 17 00:00:00 2001 From: "pre-commit-ci[bot]" <66853113+pre-commit-ci[bot]@users.noreply.github.com> Date: Thu, 28 Mar 2024 07:17:03 +0000 Subject: [PATCH 15/20] style(pre-commit): autofix --- control/consistency_checker.py | 4 +++- 1 file changed, 3 insertions(+), 1 deletion(-) diff --git a/control/consistency_checker.py b/control/consistency_checker.py index 634f1618..12bce958 100644 --- a/control/consistency_checker.py +++ b/control/consistency_checker.py @@ -111,7 +111,9 @@ def read_yaml(file_path): error_message = "" if "steer_delay_difference" in item or "steer_time_constant_difference" in item: if value != 0.0: - error_message = "[ERROR] The parameters of the controller and simulator should be identical.\033[0m" + error_message = ( + "[ERROR] The parameters of the controller and simulator should be identical.\033[0m" + ) if ( "acceleration_limit_difference" in item or "max_steer_rate_lim_difference_by_curvature" in item From 76d6e4cfe6f13bd746448b156f106ce0cbd41019 Mon Sep 17 00:00:00 2001 From: Zhe Shen Date: Thu, 28 Mar 2024 16:39:45 +0900 Subject: [PATCH 16/20] rename the control src folder Signed-off-by: Zhe Shen --- {control => control_src}/consistency_checker.py | 0 1 file changed, 0 insertions(+), 0 deletions(-) rename {control => control_src}/consistency_checker.py (100%) diff --git a/control/consistency_checker.py b/control_src/consistency_checker.py similarity index 100% rename from control/consistency_checker.py rename to control_src/consistency_checker.py From ebc38ddcc50a80cef1d90ed266ed3ec6dd94f3c3 Mon Sep 17 00:00:00 2001 From: Zhe Shen Date: Thu, 28 Mar 2024 17:28:20 +0900 Subject: [PATCH 17/20] add the accelerate delay comparison Signed-off-by: Zhe Shen --- control_src/consistency_checker.py | 9 ++++++++- 1 file changed, 8 insertions(+), 1 deletion(-) diff --git a/control_src/consistency_checker.py b/control_src/consistency_checker.py index 12bce958..86ae318e 100644 --- a/control_src/consistency_checker.py +++ b/control_src/consistency_checker.py @@ -103,13 +103,20 @@ def read_yaml(file_path): -simulator_model_params["vel_rate_lim"], ) ), + ( + "[PID] accelerate_delay_difference: {}, (controller: {}, simulator: {})".format( + simulator_model_params["acc_time_delay"] - pid_params["delay_compensation_time"], + pid_params["delay_compensation_time"], + simulator_model_params["acc_time_delay"], + ) + ), ] for item in results: description = item.split(",")[0] value = float(description.split(":")[1].strip()) error_message = "" - if "steer_delay_difference" in item or "steer_time_constant_difference" in item: + if "steer_delay_difference" in item or "steer_time_constant_difference" in item or "accelerate_delay_difference" in item: if value != 0.0: error_message = ( "[ERROR] The parameters of the controller and simulator should be identical.\033[0m" From b4c9134132dc43a028fa87091b9b524c78448045 Mon Sep 17 00:00:00 2001 From: "pre-commit-ci[bot]" <66853113+pre-commit-ci[bot]@users.noreply.github.com> Date: Thu, 28 Mar 2024 08:28:44 +0000 Subject: [PATCH 18/20] style(pre-commit): autofix --- control_src/consistency_checker.py | 6 +++++- 1 file changed, 5 insertions(+), 1 deletion(-) diff --git a/control_src/consistency_checker.py b/control_src/consistency_checker.py index 86ae318e..2a671db7 100644 --- a/control_src/consistency_checker.py +++ b/control_src/consistency_checker.py @@ -116,7 +116,11 @@ def read_yaml(file_path): description = item.split(",")[0] value = float(description.split(":")[1].strip()) error_message = "" - if "steer_delay_difference" in item or "steer_time_constant_difference" in item or "accelerate_delay_difference" in item: + if ( + "steer_delay_difference" in item + or "steer_time_constant_difference" in item + or "accelerate_delay_difference" in item + ): if value != 0.0: error_message = ( "[ERROR] The parameters of the controller and simulator should be identical.\033[0m" From f58d6926607748f907adc41748b42c13237b13f0 Mon Sep 17 00:00:00 2001 From: Zhe Shen Date: Fri, 29 Mar 2024 13:47:01 +0900 Subject: [PATCH 19/20] add the main function Signed-off-by: Zhe Shen --- control_src/consistency_checker.py | 217 +++++++++++++++-------------- 1 file changed, 111 insertions(+), 106 deletions(-) diff --git a/control_src/consistency_checker.py b/control_src/consistency_checker.py index 2a671db7..041b8a19 100644 --- a/control_src/consistency_checker.py +++ b/control_src/consistency_checker.py @@ -26,115 +26,120 @@ def read_yaml(file_path): "--simulator_model_param_file", help="Override the default simulator model parameter file path" ) -args = parser.parse_args() +def main(): -autoware_launch_path = get_package_share_directory("autoware_launch") -vehicle_description_path = get_package_share_directory(args.vehicle_description) + args = parser.parse_args() -mpc_param_file_path = ( - args.mpc_param_file - if args.mpc_param_file - else f"{autoware_launch_path}/config/control/trajectory_follower/lateral/mpc.param.yaml" -) -pid_param_file_path = ( - args.pid_param_file - if args.pid_param_file - else f"{autoware_launch_path}/config/control/trajectory_follower/longitudinal/pid.param.yaml" -) -simulator_model_param_file_path = ( - args.simulator_model_param_file - if args.simulator_model_param_file - else f"{vehicle_description_path}/config/simulator_model.param.yaml" -) + autoware_launch_path = get_package_share_directory("autoware_launch") + vehicle_description_path = get_package_share_directory(args.vehicle_description) -mpc_params = read_yaml(mpc_param_file_path)["/**"]["ros__parameters"] -pid_params = read_yaml(pid_param_file_path)["/**"]["ros__parameters"] -simulator_model_params = read_yaml(simulator_model_param_file_path)["/**"]["ros__parameters"] + mpc_param_file_path = ( + args.mpc_param_file + if args.mpc_param_file + else f"{autoware_launch_path}/config/control/trajectory_follower/lateral/mpc.param.yaml" + ) + pid_param_file_path = ( + args.pid_param_file + if args.pid_param_file + else f"{autoware_launch_path}/config/control/trajectory_follower/longitudinal/pid.param.yaml" + ) + simulator_model_param_file_path = ( + args.simulator_model_param_file + if args.simulator_model_param_file + else f"{vehicle_description_path}/config/simulator_model.param.yaml" + ) -results = [ - ( - "[MPC] steer_delay_difference: {}, (controller: {}, simulator: {})".format( - simulator_model_params["steer_time_delay"] - mpc_params["input_delay"], - mpc_params["input_delay"], - simulator_model_params["steer_time_delay"], - ) - ), - ( - "[MPC] steer_time_constant_difference: {}, (controller: {}, simulator: {})".format( - simulator_model_params["steer_time_constant"] - mpc_params["vehicle_model_steer_tau"], - mpc_params["vehicle_model_steer_tau"], - simulator_model_params["steer_time_constant"], - ) - ), - ( - "[MPC] acceleration_limit_difference: {}, (controller: {}, simulator: {})".format( - simulator_model_params["vel_rate_lim"] - mpc_params["acceleration_limit"], - mpc_params["acceleration_limit"], - simulator_model_params["vel_rate_lim"], - ) - ), - ( - "[MPC] max_steer_rate_lim_difference_by_curvature: {}, (controller: {}, simulator: {})".format( - simulator_model_params["steer_rate_lim"] - - max(mpc_params["steer_rate_lim_dps_list_by_curvature"]) * (math.pi / 180), - max(mpc_params["steer_rate_lim_dps_list_by_curvature"]) * (math.pi / 180), - simulator_model_params["steer_rate_lim"], - ) - ), - ( - "[MPC] max_steer_rate_lim_difference_by_velocity: {}, (controller: {}, simulator: {})".format( - simulator_model_params["steer_rate_lim"] - - max(mpc_params["steer_rate_lim_dps_list_by_velocity"]) * (math.pi / 180), - max(mpc_params["steer_rate_lim_dps_list_by_velocity"]) * (math.pi / 180), - simulator_model_params["steer_rate_lim"], - ) - ), - ( - "[PID] max_acc_difference: {}, (controller: {}, simulator: {})".format( - simulator_model_params["vel_rate_lim"] - pid_params["max_acc"], - pid_params["max_acc"], - simulator_model_params["vel_rate_lim"], - ) - ), - ( - "[PID] min_acc_difference: {}, (controller: {}, simulator: {})".format( - -simulator_model_params["vel_rate_lim"] - pid_params["min_acc"], - pid_params["min_acc"], - -simulator_model_params["vel_rate_lim"], - ) - ), - ( - "[PID] accelerate_delay_difference: {}, (controller: {}, simulator: {})".format( - simulator_model_params["acc_time_delay"] - pid_params["delay_compensation_time"], - pid_params["delay_compensation_time"], - simulator_model_params["acc_time_delay"], - ) - ), -] + mpc_params = read_yaml(mpc_param_file_path)["/**"]["ros__parameters"] + pid_params = read_yaml(pid_param_file_path)["/**"]["ros__parameters"] + simulator_model_params = read_yaml(simulator_model_param_file_path)["/**"]["ros__parameters"] -for item in results: - description = item.split(",")[0] - value = float(description.split(":")[1].strip()) - error_message = "" - if ( - "steer_delay_difference" in item - or "steer_time_constant_difference" in item - or "accelerate_delay_difference" in item - ): - if value != 0.0: - error_message = ( - "[ERROR] The parameters of the controller and simulator should be identical.\033[0m" + results = [ + ( + "[MPC] steer_delay_difference: {}, (controller: {}, simulator: {})".format( + simulator_model_params["steer_time_delay"] - mpc_params["input_delay"], + mpc_params["input_delay"], + simulator_model_params["steer_time_delay"], + ) + ), + ( + "[MPC] steer_time_constant_difference: {}, (controller: {}, simulator: {})".format( + simulator_model_params["steer_time_constant"] - mpc_params["vehicle_model_steer_tau"], + mpc_params["vehicle_model_steer_tau"], + simulator_model_params["steer_time_constant"], + ) + ), + ( + "[MPC] acceleration_limit_difference: {}, (controller: {}, simulator: {})".format( + simulator_model_params["vel_rate_lim"] - mpc_params["acceleration_limit"], + mpc_params["acceleration_limit"], + simulator_model_params["vel_rate_lim"], + ) + ), + ( + "[MPC] max_steer_rate_lim_difference_by_curvature: {}, (controller: {}, simulator: {})".format( + simulator_model_params["steer_rate_lim"] + - max(mpc_params["steer_rate_lim_dps_list_by_curvature"]) * (math.pi / 180), + max(mpc_params["steer_rate_lim_dps_list_by_curvature"]) * (math.pi / 180), + simulator_model_params["steer_rate_lim"], ) - if ( - "acceleration_limit_difference" in item - or "max_steer_rate_lim_difference_by_curvature" in item - or "max_steer_rate_lim_difference_by_velocity" in item - or "max_acc_difference" in item - ): - if value < 0: - error_message = "[ERROR] The parameter of the controller should be smaller than the parameter of the simulator.\033[0m" - if "min_acc_difference" in item and value > 0: - error_message = "[ERROR] The parameter of the controller should be bigger than the parameter of the simulator.\033[0m" - print(f"{item}") - if error_message: - print(f"\033[91m{error_message}\033[0m\n") + ), + ( + "[MPC] max_steer_rate_lim_difference_by_velocity: {}, (controller: {}, simulator: {})".format( + simulator_model_params["steer_rate_lim"] + - max(mpc_params["steer_rate_lim_dps_list_by_velocity"]) * (math.pi / 180), + max(mpc_params["steer_rate_lim_dps_list_by_velocity"]) * (math.pi / 180), + simulator_model_params["steer_rate_lim"], + ) + ), + ( + "[PID] max_acc_difference: {}, (controller: {}, simulator: {})".format( + simulator_model_params["vel_rate_lim"] - pid_params["max_acc"], + pid_params["max_acc"], + simulator_model_params["vel_rate_lim"], + ) + ), + ( + "[PID] min_acc_difference: {}, (controller: {}, simulator: {})".format( + -simulator_model_params["vel_rate_lim"] - pid_params["min_acc"], + pid_params["min_acc"], + -simulator_model_params["vel_rate_lim"], + ) + ), + ( + "[PID] accelerate_delay_difference: {}, (controller: {}, simulator: {})".format( + simulator_model_params["acc_time_delay"] - pid_params["delay_compensation_time"], + pid_params["delay_compensation_time"], + simulator_model_params["acc_time_delay"], + ) + ), + ] + + for item in results: + description = item.split(",")[0] + value = float(description.split(":")[1].strip()) + error_message = "" + if ( + "steer_delay_difference" in item + or "steer_time_constant_difference" in item + or "accelerate_delay_difference" in item + ): + if value != 0.0: + error_message = ( + "[ERROR] The parameters of the controller and simulator should be identical.\033[0m" + ) + if ( + "acceleration_limit_difference" in item + or "max_steer_rate_lim_difference_by_curvature" in item + or "max_steer_rate_lim_difference_by_velocity" in item + or "max_acc_difference" in item + ): + if value < 0: + error_message = "[ERROR] The parameter of the controller should be smaller than the parameter of the simulator.\033[0m" + if "min_acc_difference" in item and value > 0: + error_message = "[ERROR] The parameter of the controller should be bigger than the parameter of the simulator.\033[0m" + print(f"{item}") + if error_message: + print(f"\033[91m{error_message}\033[0m\n") + +if __name__ == '__main__': + main() \ No newline at end of file From 851a26eb7a5e388b35446cbcb3ccfefe5f7ccc79 Mon Sep 17 00:00:00 2001 From: "pre-commit-ci[bot]" <66853113+pre-commit-ci[bot]@users.noreply.github.com> Date: Fri, 29 Mar 2024 04:47:38 +0000 Subject: [PATCH 20/20] style(pre-commit): autofix --- control_src/consistency_checker.py | 14 +++++++------- 1 file changed, 7 insertions(+), 7 deletions(-) diff --git a/control_src/consistency_checker.py b/control_src/consistency_checker.py index 041b8a19..fc572539 100644 --- a/control_src/consistency_checker.py +++ b/control_src/consistency_checker.py @@ -26,8 +26,8 @@ def read_yaml(file_path): "--simulator_model_param_file", help="Override the default simulator model parameter file path" ) -def main(): +def main(): args = parser.parse_args() autoware_launch_path = get_package_share_directory("autoware_launch") @@ -63,7 +63,8 @@ def main(): ), ( "[MPC] steer_time_constant_difference: {}, (controller: {}, simulator: {})".format( - simulator_model_params["steer_time_constant"] - mpc_params["vehicle_model_steer_tau"], + simulator_model_params["steer_time_constant"] + - mpc_params["vehicle_model_steer_tau"], mpc_params["vehicle_model_steer_tau"], simulator_model_params["steer_time_constant"], ) @@ -124,9 +125,7 @@ def main(): or "accelerate_delay_difference" in item ): if value != 0.0: - error_message = ( - "[ERROR] The parameters of the controller and simulator should be identical.\033[0m" - ) + error_message = "[ERROR] The parameters of the controller and simulator should be identical.\033[0m" if ( "acceleration_limit_difference" in item or "max_steer_rate_lim_difference_by_curvature" in item @@ -141,5 +140,6 @@ def main(): if error_message: print(f"\033[91m{error_message}\033[0m\n") -if __name__ == '__main__': - main() \ No newline at end of file + +if __name__ == "__main__": + main()