Skip to content

Commit

Permalink
style(pre-commit): autofix
Browse files Browse the repository at this point in the history
  • Loading branch information
pre-commit-ci[bot] committed Mar 27, 2024
1 parent 1cf2db8 commit 19c1b00
Showing 1 changed file with 20 additions and 14 deletions.
34 changes: 20 additions & 14 deletions control/consistency_checker.py
Original file line number Diff line number Diff line change
Expand Up @@ -10,36 +10,42 @@ 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."
)

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()

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"]
Expand Down

0 comments on commit 19c1b00

Please sign in to comment.