diff --git a/driving_log_replayer/driving_log_replayer/launch_common.py b/driving_log_replayer/driving_log_replayer/launch_common.py index 9c7736268..42b80d5b4 100644 --- a/driving_log_replayer/driving_log_replayer/launch_common.py +++ b/driving_log_replayer/driving_log_replayer/launch_common.py @@ -83,6 +83,7 @@ def add_launch_arg( add_launch_arg("vehicle_id", default_value="default", description="vehicle specific ID") # additional argument + add_launch_arg("perception_mode", default_value="lidar", description="perception mode") add_launch_arg( "t4_dataset_path", default_value="/opt/autoware/t4_dataset", @@ -105,7 +106,6 @@ def get_autoware_launch( planning: str = "false", control: str = "false", scenario_simulation: str = "false", - perception_mode: str = "lidar", pose_source: str = "ndt", twist_source: str = "gyro_odom", ) -> launch.actions.IncludeLaunchDescription: @@ -129,7 +129,7 @@ def get_autoware_launch( "planning": planning, "control": control, "scenario_simulation": scenario_simulation, - "perception_mode": perception_mode, + "perception_mode": LaunchConfiguration("perception_mode"), "pose_source": pose_source, "twist_source": twist_source, "rviz": "false", diff --git a/driving_log_replayer_cli/simulation/generate.py b/driving_log_replayer_cli/simulation/generate.py index dcf484fe0..04ca7217b 100644 --- a/driving_log_replayer_cli/simulation/generate.py +++ b/driving_log_replayer_cli/simulation/generate.py @@ -9,6 +9,14 @@ class TestScriptGenerator: + PERCEPTION_MODES = ( + "camera_lidar_radar_fusion", + "camera_lidar_fusion", + "lidar_radar_fusion", + "lidar", + "radar", + ) + def __init__( self, data_directory: str, @@ -190,7 +198,7 @@ def __create_launch_command( print("launch command generated! => " + launch_command) # noqa return launch_command - def __create_launch_command_with_t4_dataset( + def __create_launch_command_with_t4_dataset( # noqa TODO: fix logic self, scenario_root: str, scenario_name: str, @@ -263,6 +271,13 @@ def __create_launch_command_with_t4_dataset( launch_args += " sensor_model:=" + scenario_yaml_obj["SensorModel"] launch_args += " vehicle_id:=" + vehicle_id launch_args += " rviz:=true" + if scenario_yaml_obj.get("PerceptionMode") is not None: + perception_mode: str = scenario_yaml_obj["PerceptionMode"] + assert perception_mode in self.PERCEPTION_MODES, ( + f"perception_mode must be chosen from {self.PERCEPTION_MODES}, " + f"but got {perception_mode}" + ) + launch_args += " perception_mode:=" + perception_mode # t4_dataset launch_args += " t4_dataset_path:=" + t4_dataset_path diff --git a/pyproject.toml b/pyproject.toml index 0e6f66c1e..89d418d1b 100644 --- a/pyproject.toml +++ b/pyproject.toml @@ -1,6 +1,6 @@ [tool.poetry] name = "driving_log_replayer_cli" -version = "1.6.7" +version = "1.7.0" description = "command line tool for driving_log_replayer" authors = [ "Hayato Mizushima ", diff --git a/sample/perception/scenario.fp.ja.yaml b/sample/perception/scenario.fp.ja.yaml index 4baea2a8b..ad52eb483 100644 --- a/sample/perception/scenario.fp.ja.yaml +++ b/sample/perception/scenario.fp.ja.yaml @@ -1,8 +1,9 @@ -ScenarioFormatVersion: 3.0.0 +ScenarioFormatVersion: 3.1.0 ScenarioName: fp_sample ScenarioDescription: fp_sample SensorModel: sample_sensor_kit VehicleModel: sample_vehicle +PerceptionMode: lidar Evaluation: UseCaseName: perception UseCaseFormatVersion: 0.6.0 diff --git a/sample/perception/scenario.fp.yaml b/sample/perception/scenario.fp.yaml index 07e82d6c1..90392a182 100644 --- a/sample/perception/scenario.fp.yaml +++ b/sample/perception/scenario.fp.yaml @@ -1,8 +1,9 @@ -ScenarioFormatVersion: 3.0.0 +ScenarioFormatVersion: 3.1.0 ScenarioName: fp_sample ScenarioDescription: fp_sample SensorModel: sample_sensor_kit VehicleModel: sample_vehicle +PerceptionMode: lidar Evaluation: UseCaseName: perception UseCaseFormatVersion: 0.6.0 diff --git a/sample/perception/scenario.ja.yaml b/sample/perception/scenario.ja.yaml index 2e40529f5..e9c69d603 100644 --- a/sample/perception/scenario.ja.yaml +++ b/sample/perception/scenario.ja.yaml @@ -1,8 +1,9 @@ -ScenarioFormatVersion: 3.0.0 +ScenarioFormatVersion: 3.1.0 ScenarioName: perception_use_bag_concat_data ScenarioDescription: sensing_module_off_and_use_pointcloud_in_the_rosbag SensorModel: sample_sensor_kit VehicleModel: sample_vehicle +PerceptionMode: lidar Evaluation: UseCaseName: perception UseCaseFormatVersion: 0.6.0 diff --git a/sample/perception/scenario.yaml b/sample/perception/scenario.yaml index cecfd917f..2b20b0db9 100644 --- a/sample/perception/scenario.yaml +++ b/sample/perception/scenario.yaml @@ -1,8 +1,9 @@ -ScenarioFormatVersion: 3.0.0 +ScenarioFormatVersion: 3.1.0 ScenarioName: perception_use_bag_concat_data ScenarioDescription: sensing_module_off_and_use_pointcloud_in_the_rosbag SensorModel: sample_sensor_kit VehicleModel: sample_vehicle +PerceptionMode: lidar Evaluation: UseCaseName: perception UseCaseFormatVersion: 0.6.0 diff --git a/sample/perception_2d/scenario.ja.yaml b/sample/perception_2d/scenario.ja.yaml index b2b912cc3..e540818d7 100644 --- a/sample/perception_2d/scenario.ja.yaml +++ b/sample/perception_2d/scenario.ja.yaml @@ -1,8 +1,9 @@ -ScenarioFormatVersion: 3.0.0 +ScenarioFormatVersion: 3.1.0 ScenarioName: perception_2d_x2 ScenarioDescription: perception_2d_x2 SensorModel: aip_x2 VehicleModel: gsm8 +PerceptionMode: camera_lidar_fusion Evaluation: UseCaseName: perception_2d UseCaseFormatVersion: 0.3.0 diff --git a/sample/perception_2d/scenario.yaml b/sample/perception_2d/scenario.yaml index 94e65ad08..40219e705 100644 --- a/sample/perception_2d/scenario.yaml +++ b/sample/perception_2d/scenario.yaml @@ -1,8 +1,9 @@ -ScenarioFormatVersion: 3.0.0 +ScenarioFormatVersion: 3.1.0 ScenarioName: perception_2d_x2 ScenarioDescription: perception_2d_x2 SensorModel: aip_x2 VehicleModel: gsm8 +PerceptionMode: camera_lidar_fusion Evaluation: UseCaseName: perception_2d UseCaseFormatVersion: 0.3.0