Skip to content
This repository has been archived by the owner on Dec 20, 2024. It is now read-only.

Commit

Permalink
feat(perception): allow to specify perception mode in scenario (#279)
Browse files Browse the repository at this point in the history
Signed-off-by: ktro2828 <[email protected]>
Co-authored-by: Hayato Mizushima <[email protected]>
  • Loading branch information
ktro2828 and hayato-m126 authored Oct 15, 2023
1 parent c8d63c2 commit ba0d070
Show file tree
Hide file tree
Showing 9 changed files with 31 additions and 10 deletions.
4 changes: 2 additions & 2 deletions driving_log_replayer/driving_log_replayer/launch_common.py
Original file line number Diff line number Diff line change
Expand Up @@ -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",
Expand All @@ -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:
Expand All @@ -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",
Expand Down
17 changes: 16 additions & 1 deletion driving_log_replayer_cli/simulation/generate.py
Original file line number Diff line number Diff line change
Expand Up @@ -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,
Expand Down Expand Up @@ -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,
Expand Down Expand Up @@ -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
Expand Down
2 changes: 1 addition & 1 deletion pyproject.toml
Original file line number Diff line number Diff line change
@@ -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 <[email protected]>",
Expand Down
3 changes: 2 additions & 1 deletion sample/perception/scenario.fp.ja.yaml
Original file line number Diff line number Diff line change
@@ -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
Expand Down
3 changes: 2 additions & 1 deletion sample/perception/scenario.fp.yaml
Original file line number Diff line number Diff line change
@@ -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
Expand Down
3 changes: 2 additions & 1 deletion sample/perception/scenario.ja.yaml
Original file line number Diff line number Diff line change
@@ -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
Expand Down
3 changes: 2 additions & 1 deletion sample/perception/scenario.yaml
Original file line number Diff line number Diff line change
@@ -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
Expand Down
3 changes: 2 additions & 1 deletion sample/perception_2d/scenario.ja.yaml
Original file line number Diff line number Diff line change
@@ -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
Expand Down
3 changes: 2 additions & 1 deletion sample/perception_2d/scenario.yaml
Original file line number Diff line number Diff line change
@@ -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
Expand Down

0 comments on commit ba0d070

Please sign in to comment.