Skip to content

Commit b8263b3

Browse files
authoredApr 8, 2024
feat: #403 annotationless scenario less mode (#405)
1 parent d713139 commit b8263b3

File tree

9 files changed

+199
-43
lines changed

9 files changed

+199
-43
lines changed
 

‎docs/overview/command.en.md

+9
Original file line numberDiff line numberDiff line change
@@ -67,6 +67,15 @@ dlr simulation run -p default -l play_rate:=0.5 -l input_pointcloud:=/sensing/li
6767

6868
# Set perception_mode to camera_lidar_fusion
6969
dlr simulation run -p default -l perception_mode:=camera_lidar_fusion
70+
71+
# Dry-run mode to obtain metrics without creating a scenario file
72+
# set bag, map, sensor_model, vehicle_model, [and vehicle_id] from arguments
73+
dlr simulation dry-run -p ${profile} -u ${use_case} -l sensor_model:=${sensor_model} -l vehicle_model:=${vehicle_model} -l map_path:=${map_path} -l input_bag:=${bag_path} [-l vehicle_id:=${vehicle_id}]
74+
75+
# Command example
76+
# The -p option is used to determine the output destination for bag and result.jsonl. If omitted, the output is sent to the output_directory of the default profile.
77+
# Currently, use_case is only annotationless_perception, so if -u is omitted, it automatically becomes annotationless_perception.
78+
dlr simulation dry-run -l input_bag:=$HOME/dlr_data/auto/annotationless/sample/input_bag -l sensor_model:=sample_sensor_kit -l vehicle_model:=sample_vehicle -l map_path:=$HOME/map/sample_map
7079
```
7180

7281
The arguments that can be specified can be displayed by using the -s option of ros2 launch.

‎docs/overview/command.ja.md

+9
Original file line numberDiff line numberDiff line change
@@ -48,6 +48,15 @@ dlr simulation show-result ${output_directory}
4848

4949
# 結果ファイルをjsonに変換する
5050
dlr simulation convert-result ${output_directory}
51+
52+
# シナリオファイルを作成せずに、メトリクスを得るために実行する予行演習モード
53+
# bag, map, sensor_model, vehicle_model [, vehicle_id] を引数で指定する
54+
dlr simulation dry-run -p ${profile} -u ${use_case} -l sensor_model:=${sensor_model} -l vehicle_model:=${vehicle_model} -l map_path:=${map_path} -l input_bag:=${bag_path} [-l vehicle_id:=${vehicle_id}]
55+
56+
# コマンド例
57+
# -pのオプションは、bagとresult.jsonlの出力先を決めるために使われる。省略するとdefaultプロファイルのoutput_directoryに出力される。
58+
# 現時点ではuse_caseはannotationless_perceptionのみなので-uを省略すると自動でanontationless_perceptionになる
59+
dlr simulation dry-run -l input_bag:=$HOME/dlr_data/auto/annotationless/sample/input_bag -l sensor_model:=sample_sensor_kit -l vehicle_model:=sample_vehicle -l map_path:=$HOME/map/sample_map
5160
```
5261

5362
#### dlr simulation run launch argument option

‎driving_log_replayer_cli/core/scenario.py

+12-4
Original file line numberDiff line numberDiff line change
@@ -19,14 +19,14 @@ class Scenario(BaseModel):
1919
SensorModel: str
2020
VehicleModel: str
2121
VehicleId: str | None = None
22-
LocalMapPath: Path | None = None
22+
LocalMapPath: Path | str = ""
2323
Evaluation: dict
2424

2525
@field_validator("LocalMapPath", mode="before")
2626
@classmethod
27-
def validate_local_path(cls, v: str | None) -> Path | None:
28-
if v is None:
29-
return None
27+
def validate_local_path(cls, v: str | None) -> Path | str:
28+
if v == "":
29+
return ""
3030
normal_path = Path(expandvars(v))
3131
if normal_path.exists():
3232
return normal_path
@@ -49,6 +49,14 @@ def load_scenario(scenario_path: Path) -> Scenario:
4949
return Scenario(**yaml.safe_load(scenario_file))
5050

5151

52+
def get_dry_run_scenario_path(use_case: str) -> Path:
53+
return (
54+
Path(__file__)
55+
.parent.parent.resolve()
56+
.joinpath("resources", "sample", use_case, "dry_run.yaml")
57+
)
58+
59+
5260
def backup_scenario_file(scenario_path: Path) -> None:
5361
bak_name = scenario_path.name + f".{datetime.now().strftime('%Y%m%d%H%M%S')}.bak" # noqa
5462
backup_file_path = scenario_path.parent.joinpath(bak_name)
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,2 @@
1+
# Save resource files to be used from cli in this directory.
2+
# refer https://github.com/psf/black/tree/main/src/black/resources
Original file line numberDiff line numberDiff line change
@@ -0,0 +1 @@
1+
../../sample

‎driving_log_replayer_cli/simulation/__init__.py

+23
Original file line numberDiff line numberDiff line change
@@ -6,6 +6,7 @@
66
from driving_log_replayer_cli.core.config import load_config
77
from driving_log_replayer_cli.core.result import convert_all
88
from driving_log_replayer_cli.core.result import display_all
9+
from driving_log_replayer_cli.simulation.run import dry_run as sim_dry_run
910
from driving_log_replayer_cli.simulation.run import run as sim_run
1011
from driving_log_replayer_cli.simulation.update import update_annotationless_scenario_condition
1112

@@ -40,6 +41,28 @@ def run(
4041
)
4142

4243

44+
@simulation.command(context_settings=CONTEXT_SETTINGS)
45+
@click.option("--profile", "-p", type=str, default="default")
46+
@click.option(
47+
"--use-case",
48+
"-u",
49+
type=click.Choice(["annotationless_perception"]),
50+
default="annotationless_perception",
51+
)
52+
@click.option("--launch_args", "-l", multiple=True, default=[])
53+
def dry_run(
54+
profile: str,
55+
use_case: str,
56+
launch_args: list[str],
57+
) -> None:
58+
config: Config = load_config(profile)
59+
sim_dry_run(
60+
config,
61+
use_case,
62+
launch_args,
63+
)
64+
65+
4366
@simulation.command(context_settings=CONTEXT_SETTINGS)
4467
@click.argument(
4568
"output_directory",

‎driving_log_replayer_cli/simulation/run.py

+110-28
Original file line numberDiff line numberDiff line change
@@ -10,6 +10,7 @@
1010
from driving_log_replayer_cli.core.result import convert_all
1111
from driving_log_replayer_cli.core.result import display_all
1212
from driving_log_replayer_cli.core.scenario import Datasets
13+
from driving_log_replayer_cli.core.scenario import get_dry_run_scenario_path
1314
from driving_log_replayer_cli.core.scenario import load_scenario
1415
from driving_log_replayer_cli.core.scenario import Scenario
1516
from driving_log_replayer_cli.simulation.update import update_annotationless_scenario_condition
@@ -48,19 +49,20 @@ def run(
4849
continue
4950
scenario = load_scenario(scenario_file)
5051
launch_cmd = None
52+
launch_arg_dict = args_to_dict(launch_args)
5153
if scenario.Evaluation["UseCaseName"] in USE_T4_DATASET:
5254
launch_cmd = cmd_use_t4_dataset(
5355
scenario_file,
5456
output_case,
5557
config.autoware_path,
56-
launch_args,
58+
launch_arg_dict,
5759
)
5860
else:
5961
launch_cmd = cmd_use_bag_only(
6062
scenario_file,
6163
output_case,
6264
config.autoware_path,
63-
launch_args,
65+
launch_arg_dict,
6466
)
6567

6668
if launch_cmd is None:
@@ -93,6 +95,54 @@ def run(
9395
display_all(output_dir_by_time)
9496

9597

98+
def dry_run(
99+
config: Config,
100+
use_case: str,
101+
launch_args: list[str],
102+
) -> None:
103+
output_dir_by_time = create_output_dir_by_time(config.output_directory)
104+
output_case = output_dir_by_time.joinpath("dry_run")
105+
scenario_file = get_dry_run_scenario_path(use_case)
106+
scenario = load_scenario(scenario_file)
107+
launch_cmd = None
108+
launch_arg_dict = args_to_dict(launch_args)
109+
if scenario.Evaluation["UseCaseName"] in USE_T4_DATASET:
110+
launch_cmd = cmd_use_t4_dataset(
111+
scenario_file,
112+
output_case,
113+
config.autoware_path,
114+
launch_arg_dict,
115+
)
116+
else:
117+
launch_cmd = cmd_use_bag_only(
118+
scenario_file,
119+
output_case,
120+
config.autoware_path,
121+
launch_arg_dict,
122+
)
123+
124+
if launch_cmd is None:
125+
return
126+
127+
# create dir for output bag and result.jsonl
128+
output_case.mkdir(exist_ok=True)
129+
130+
# save command as bash script
131+
run_script = output_case.joinpath("run.bash")
132+
with run_script.open("w") as f:
133+
f.write(launch_cmd)
134+
135+
# run simulation
136+
cmd = ["/bin/bash", run_script.as_posix()]
137+
try:
138+
run_with_log(cmd, output_case.joinpath("console.log"))
139+
except KeyboardInterrupt:
140+
termcolor.cprint("Simulation execution canceled by Ctrl+C", "red")
141+
# convert result file and display result
142+
convert_all(output_dir_by_time)
143+
display_all(output_dir_by_time)
144+
145+
96146
def create_output_dir_by_time(base_path: Path) -> Path:
97147
output_dir_by_time = base_path.joinpath(
98148
datetime.datetime.now().strftime("%Y-%m%d-%H%M%S") # noqa
@@ -117,22 +167,29 @@ def get_scenario_file(dataset_path: Path) -> Path | None:
117167
return scenario_file_path
118168

119169

120-
def extract_arg(launch_args: list[str]) -> str:
121-
extract_launch_arg = ""
170+
def args_to_dict(launch_args: list[str]) -> dict[str, str]:
171+
launch_arg_dict = {}
122172
for l_arg in launch_args:
123-
if len(l_arg.split(":=")) != 2: # noqa
173+
try:
174+
key, value = l_arg.split(":=")
175+
launch_arg_dict[key] = value
176+
except ValueError:
124177
# invalid argument
125178
termcolor.cprint(
126179
f"{l_arg} is ignored because it is invalid",
127180
"red",
128181
)
129-
else: # noqa
130-
# Enclose in single quotes to avoid being treated as special characters by shell
131-
if "{" in l_arg or "[" in l_arg:
132-
extract_launch_arg += f" '{l_arg}'"
133-
else:
134-
extract_launch_arg += f" {l_arg}"
135-
return extract_launch_arg
182+
return launch_arg_dict
183+
184+
185+
def launch_dict_to_str(launch_arg_dict: dict) -> str:
186+
rtn_str = ""
187+
for k, v in launch_arg_dict.items():
188+
if isinstance(v, str) and ("{" in v or "[" in v):
189+
rtn_str += f" '{k}:={v}'"
190+
else:
191+
rtn_str += f" {k}:={v}"
192+
return rtn_str
136193

137194

138195
def clean_up_cmd() -> str:
@@ -155,30 +212,40 @@ def cmd_use_bag_only(
155212
scenario_path: Path,
156213
output_path: Path,
157214
autoware_path: Path,
158-
launch_args: str,
215+
launch_args_dict: dict[str, str],
159216
) -> str | None:
160217
scenario: Scenario = load_scenario(scenario_path)
161-
launch_command = f"source {autoware_path.joinpath('install', 'setup.bash').as_posix()}\n"
162-
launch_command += f"ros2 launch driving_log_replayer {scenario.Evaluation['UseCaseName']}.launch.py map_path:={scenario.LocalMapPath} vehicle_model:={scenario.VehicleModel} sensor_model:={scenario.SensorModel} vehicle_id:={scenario.VehicleId}"
163-
launch_command += f" scenario_path:={scenario_path.as_posix()} result_json_path:={output_path.joinpath('result.json').as_posix()} input_bag:={scenario_path.parent.joinpath('input_bag').as_posix()} result_bag_path:={output_path.joinpath('result_bag').as_posix()}"
218+
launch_command = f"source {autoware_path.joinpath('install', 'setup.bash')}\n"
219+
launch_command += (
220+
f"ros2 launch driving_log_replayer {scenario.Evaluation['UseCaseName']}.launch.py"
221+
)
222+
launch_arg_dict_scenario = {
223+
"map_path": scenario.LocalMapPath,
224+
"vehicle_model": scenario.VehicleModel,
225+
"sensor_model": scenario.SensorModel,
226+
"vehicle_id": scenario.VehicleId,
227+
"scenario_path": scenario_path,
228+
"result_json_path": output_path.joinpath("result.json"),
229+
"input_bag": scenario_path.parent.joinpath("input_bag"),
230+
"result_bag_path": output_path.joinpath("result_bag"),
231+
}
164232
launch_localization = scenario.Evaluation.get("LaunchLocalization")
165233
if launch_localization is not None:
166-
launch_command += f" localization:={launch_localization}"
167-
launch_command += extract_arg(launch_args)
234+
launch_arg_dict_scenario["localization"] = launch_localization
235+
launch_arg_dict_scenario.update(launch_args_dict)
236+
launch_command += launch_dict_to_str(launch_arg_dict_scenario) + "\n"
168237
return launch_command + clean_up_cmd()
169238

170239

171240
def cmd_use_t4_dataset(
172241
scenario_path: Path,
173242
output_path: Path,
174243
autoware_path: Path,
175-
launch_args: str,
244+
launch_args_dict: dict[str, str],
176245
) -> str | None:
177246
dataset_path = scenario_path.parent
178247
scenario: Scenario = load_scenario(scenario_path)
179-
launch_command_for_all_dataset = (
180-
f"source {autoware_path.joinpath('install', 'setup.bash').as_posix()}\n"
181-
)
248+
launch_command_for_all_dataset = f"source {autoware_path.joinpath('install', 'setup.bash')}\n"
182249
t4_dataset_base_path = dataset_path.joinpath("t4_dataset")
183250
try:
184251
t4_datasets: Datasets = Datasets(Datasets=scenario.Evaluation["Datasets"])
@@ -202,12 +269,25 @@ def cmd_use_t4_dataset(
202269
)
203270
continue
204271

205-
launch_command = f"ros2 launch driving_log_replayer {scenario.Evaluation['UseCaseName']}.launch.py map_path:={map_path} vehicle_model:={scenario.VehicleModel} sensor_model:={scenario.SensorModel} vehicle_id:={vehicle_id}"
206-
launch_command += f" scenario_path:={scenario_path.as_posix()} result_json_path:={output_dir_per_dataset.joinpath('result.json').as_posix()} input_bag:={t4_dataset_path.joinpath('input_bag').as_posix()} result_bag_path:={output_dir_per_dataset.joinpath('result_bag').as_posix()}"
207-
launch_command += f" t4_dataset_path:={t4_dataset_path} result_archive_path:={output_dir_per_dataset.joinpath('result_archive').as_posix()}"
272+
launch_command = (
273+
f"ros2 launch driving_log_replayer {scenario.Evaluation['UseCaseName']}.launch.py"
274+
)
275+
launch_arg_dict_dataset = {
276+
"map_path": map_path,
277+
"vehicle_model": scenario.VehicleModel,
278+
"sensor_model": scenario.SensorModel,
279+
"vehicle_id": vehicle_id,
280+
"scenario_path": scenario_path,
281+
"result_json_path": output_dir_per_dataset.joinpath("result.json"),
282+
"input_bag": t4_dataset_path.joinpath("input_bag"),
283+
"result_bag_path": output_dir_per_dataset.joinpath("result_bag"),
284+
"t4_dataset_path": t4_dataset_path,
285+
"result_archive_path": output_dir_per_dataset.joinpath("result_archive"),
286+
}
208287
if t4_dataset[key].LaunchSensing is not None:
209-
launch_command += f" sensing:={t4_dataset[key].LaunchSensing}"
210-
launch_command += extract_arg(launch_args)
288+
launch_arg_dict_dataset["sensing"] = t4_dataset[key].LaunchSensing
289+
launch_arg_dict_dataset.update(launch_args_dict)
290+
launch_command += launch_dict_to_str(launch_arg_dict_dataset) + "\n"
211291
launch_command += clean_up_cmd()
212292
launch_command_for_all_dataset += launch_command
213293
if is_database_evaluation:
@@ -218,6 +298,8 @@ def cmd_use_t4_dataset(
218298
"driving_log_replayer",
219299
"perception_database_result.py",
220300
)
221-
database_result_command = f"python3 {database_result_script_path.as_posix()} -s {scenario_path} -r {output_path}\n"
301+
database_result_command = (
302+
f"python3 {database_result_script_path} -s {scenario_path} -r {output_path}\n"
303+
)
222304
launch_command_for_all_dataset += database_result_command
223305
return launch_command_for_all_dataset
Original file line numberDiff line numberDiff line change
@@ -1,31 +1,32 @@
1-
from driving_log_replayer_cli.simulation.run import extract_arg
1+
from driving_log_replayer_cli.simulation.run import args_to_dict
2+
from driving_log_replayer_cli.simulation.run import launch_dict_to_str
23

34

45
def test_extract_single_arg() -> None:
5-
args = extract_arg(["rate:=0.5"])
6-
assert args == " rate:=0.5"
6+
args = args_to_dict(["rate:=0.5"])
7+
assert launch_dict_to_str(args) == " rate:=0.5"
78

89

910
def test_extract_multiple_args() -> None:
10-
args = extract_arg(["rate:=0.5", "delay:=2.0"])
11-
assert args == " rate:=0.5 delay:=2.0"
11+
args = args_to_dict(["rate:=0.5", "delay:=2.0"])
12+
assert launch_dict_to_str(args) == " rate:=0.5 delay:=2.0"
1213

1314

1415
def test_extract_no_arg() -> None:
15-
args = extract_arg("not_arg")
16-
assert args == ""
16+
args = args_to_dict("not_arg")
17+
assert launch_dict_to_str(args) == ""
1718

1819

1920
def test_extract_dict_string() -> None:
2021
# annotationless perception argument
21-
args = extract_arg(
22+
args = args_to_dict(
2223
[
2324
'annotationless_pass_range:={"CAR":{"min":"0.0-1.1","max":"0.0-1.2","mean":"0.5-1.3"},"BUS":{"min":"0.0-1.1","max":"0.0-1.2","mean":"0.5-1.3"}}',
2425
"annotationless_threshold_file:=/home/autoware/result.jsonl",
2526
],
2627
)
2728
assert (
28-
args
29+
launch_dict_to_str(args)
2930
== ' \'annotationless_pass_range:={"CAR":{"min":"0.0-1.1","max":"0.0-1.2","mean":"0.5-1.3"},"BUS":{"min":"0.0-1.1","max":"0.0-1.2","mean":"0.5-1.3"}}\' annotationless_threshold_file:=/home/autoware/result.jsonl'
3031
)
3132
# confirm json load
@@ -37,5 +38,15 @@ def test_extract_dict_string() -> None:
3738

3839
def test_extract_array_string() -> None:
3940
# pose_initializer argument
40-
args = extract_arg(["initial_pose:=[89571.150,42301.188,-3.159,-0.009,-0.002,0.288,0.958]"])
41-
assert args == " 'initial_pose:=[89571.150,42301.188,-3.159,-0.009,-0.002,0.288,0.958]'"
41+
args = args_to_dict(["initial_pose:=[89571.150,42301.188,-3.159,-0.009,-0.002,0.288,0.958]"])
42+
assert (
43+
launch_dict_to_str(args)
44+
== " 'initial_pose:=[89571.150,42301.188,-3.159,-0.009,-0.002,0.288,0.958]'"
45+
)
46+
47+
48+
def test_override_arg() -> None:
49+
scenario_arg = {"vehicle_model": "sample_vehicle"}
50+
args = args_to_dict(["vehicle_model:=lexus"])
51+
scenario_arg.update(args)
52+
assert launch_dict_to_str(scenario_arg) == " vehicle_model:=lexus"
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,11 @@
1+
ScenarioFormatVersion: 2.2.0
2+
ScenarioName: dry_run_annotationless_perception
3+
ScenarioDescription: dry_run_annotationless_perception
4+
SensorModel: dry_run_sensor
5+
VehicleModel: dry_run_vehicle
6+
VehicleId: default
7+
Evaluation:
8+
UseCaseName: annotationless_perception
9+
UseCaseFormatVersion: 0.2.0
10+
Conditions:
11+
ClassConditions: {}

0 commit comments

Comments
 (0)
Please sign in to comment.