From 0ca0c0b9ebeb0b5814901d8e626924a85e63174c Mon Sep 17 00:00:00 2001 From: Hayato Mizushima Date: Tue, 25 Feb 2025 15:36:23 +0900 Subject: [PATCH] refactor: prepare paths (#99) * refactor: prepare paths Signed-off-by: Hayato Mizushima * refactor: variable Signed-off-by: Hayato Mizushima --------- Signed-off-by: Hayato Mizushima --- .../launch/argument.py | 23 +++++++++++-------- 1 file changed, 13 insertions(+), 10 deletions(-) diff --git a/driving_log_replayer_v2/driving_log_replayer_v2/launch/argument.py b/driving_log_replayer_v2/driving_log_replayer_v2/launch/argument.py index e215f295..f919241f 100644 --- a/driving_log_replayer_v2/driving_log_replayer_v2/launch/argument.py +++ b/driving_log_replayer_v2/driving_log_replayer_v2/launch/argument.py @@ -207,11 +207,10 @@ def update_conf_with_dataset_info( dataset_info: dict, output_dir: Path, ) -> None: - v = dataset_info - conf["vehicle_id"] = v["VehicleId"] - conf["initial_pose"] = json.dumps(v.get("InitialPose", {})) - conf["direct_initial_pose"] = json.dumps(v.get("DirectInitialPose", {})) - conf["goal_pose"] = json.dumps(v.get("GoalPose", {})) + conf["vehicle_id"] = dataset_info["VehicleId"] + conf["initial_pose"] = json.dumps(dataset_info.get("InitialPose", {})) + conf["direct_initial_pose"] = json.dumps(dataset_info.get("DirectInitialPose", {})) + conf["goal_pose"] = json.dumps(dataset_info.get("GoalPose", {})) conf["t4_dataset_path"] = t4_dataset_path.as_posix() conf["vehicle_model"] = yaml_obj["VehicleModel"] conf["sensor_model"] = yaml_obj["SensorModel"] @@ -226,17 +225,21 @@ def update_conf_with_dataset_info( conf["record_only"] = "true" +def prepare_paths(conf: dict) -> tuple[Path, Path, Path]: + scenario_path = Path(conf["scenario_path"]) + dataset_dir = scenario_path.parent if conf["dataset_dir"] == "" else Path(conf["dataset_dir"]) + output_dir = create_output_dir(conf["output_dir"], scenario_path) + conf["output_dir"] = output_dir.as_posix() + return scenario_path, dataset_dir, output_dir + + def ensure_arg_compatibility(context: LaunchContext) -> list: conf = context.launch_configurations is_valid = is_arg_valid(conf) if is_valid is not None: return is_valid - scenario_path = Path(conf["scenario_path"]) - dataset_dir = scenario_path.parent if conf["dataset_dir"] == "" else Path(conf["dataset_dir"]) - output_dir = create_output_dir(conf["output_dir"], scenario_path) - conf["output_dir"] = output_dir.as_posix() - + scenario_path, dataset_dir, output_dir = prepare_paths(conf) yaml_obj = load_scenario(scenario_path) datasets = yaml_obj["Evaluation"]["Datasets"] dataset_index = get_dataset_index_from_conf(conf, datasets)