Skip to content

Commit

Permalink
Add launch argument parameter_file_path to scenario_test_runner
Browse files Browse the repository at this point in the history
Signed-off-by: yamacir-kit <httperror@404-notfound.jp>
  • Loading branch information
yamacir-kit committed Jan 8, 2025
1 parent a0e5548 commit abbcdc4
Show file tree
Hide file tree
Showing 3 changed files with 35 additions and 1 deletion.
4 changes: 4 additions & 0 deletions mock/cpp_mock_scenarios/launch/mock_test.launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -115,6 +115,7 @@ def launch_setup(context, *args, **kwargs):
launch_rviz = LaunchConfiguration("launch_rviz", default=False)
launch_simple_sensor_simulator = LaunchConfiguration("launch_simple_sensor_simulator", default=True)
output_directory = LaunchConfiguration("output_directory", default=Path("/tmp"))
parameter_file_path = LaunchConfiguration("parameter_file_path", default=Path(get_package_share_directory("scenario_test_runner")) / "config/parameters.yaml")
port = LaunchConfiguration("port", default=5555)
publish_empty_context = LaunchConfiguration("publish_empty_context", default=False)
record = LaunchConfiguration("record", default=False)
Expand All @@ -140,6 +141,7 @@ def launch_setup(context, *args, **kwargs):
print(f"launch_autoware := {launch_autoware.perform(context)}")
print(f"launch_rviz := {launch_rviz.perform(context)}")
print(f"output_directory := {output_directory.perform(context)}")
print(f"parameter_file_path := {parameter_file_path.perform(context)}")
print(f"port := {port.perform(context)}")
print(f"publish_empty_context := {publish_empty_context.perform(context)}")
print(f"record := {record.perform(context)}")
Expand Down Expand Up @@ -174,6 +176,7 @@ def make_parameters():
{"junit_path": junit_path},
]
parameters += make_vehicle_parameters()
parameters += [parameter_file_path.perform(context)]
return parameters

def make_vehicle_parameters():
Expand Down Expand Up @@ -218,6 +221,7 @@ def description():
DeclareLaunchArgument("global_timeout", default_value=global_timeout ),
DeclareLaunchArgument("launch_autoware", default_value=launch_autoware ),
DeclareLaunchArgument("launch_rviz", default_value=launch_rviz ),
DeclareLaunchArgument("parameter_file_path", default_value=parameter_file_path ),
DeclareLaunchArgument("publish_empty_context", default_value=publish_empty_context ),
DeclareLaunchArgument("output_directory", default_value=output_directory ),
DeclareLaunchArgument("rviz_config", default_value=rviz_config ),
Expand Down
25 changes: 25 additions & 0 deletions test_runner/scenario_test_runner/config/parameters.yaml
Original file line number Diff line number Diff line change
@@ -0,0 +1,25 @@
simulation:
normal_distribution:
ros__parameters:
/localization/kinematic_state:
seed: 0 # If 0 is specified, a random seed value will be generated for each run.
pose:
pose:
position:
x: { mean: 0.0, standard_deviation: 0.0 }
y: { mean: 0.0, standard_deviation: 0.0 }
z: { mean: 0.0, standard_deviation: 0.0 }
orientation:
r: { mean: 0.0, standard_deviation: 0.0 }
p: { mean: 0.0, standard_deviation: 0.0 }
y: { mean: 0.0, standard_deviation: 0.0 }
twist:
twist:
linear:
x: { mean: 0.0, standard_deviation: 0.0 }
y: { mean: 0.0, standard_deviation: 0.0 }
z: { mean: 0.0, standard_deviation: 0.0 }
angular:
x: { mean: 0.0, standard_deviation: 0.0 }
y: { mean: 0.0, standard_deviation: 0.0 }
z: { mean: 0.0, standard_deviation: 0.0 }
Original file line number Diff line number Diff line change
Expand Up @@ -80,6 +80,7 @@ def launch_setup(context, *args, **kwargs):
launch_rviz = LaunchConfiguration("launch_rviz", default=False)
launch_simple_sensor_simulator = LaunchConfiguration("launch_simple_sensor_simulator", default=True)
output_directory = LaunchConfiguration("output_directory", default=Path("/tmp"))
parameter_file_path = LaunchConfiguration("parameter_file_path", default=Path(get_package_share_directory("scenario_test_runner")) / "config/parameters.yaml")
port = LaunchConfiguration("port", default=5555)
publish_empty_context = LaunchConfiguration("publish_empty_context", default=False)
record = LaunchConfiguration("record", default=True)
Expand All @@ -106,6 +107,7 @@ def launch_setup(context, *args, **kwargs):
print(f"launch_autoware := {launch_autoware.perform(context)}")
print(f"launch_rviz := {launch_rviz.perform(context)}")
print(f"output_directory := {output_directory.perform(context)}")
print(f"parameter_file_path := {parameter_file_path.perform(context)}")
print(f"port := {port.perform(context)}")
print(f"publish_empty_context := {publish_empty_context.perform(context)}")
print(f"record := {record.perform(context)}")
Expand Down Expand Up @@ -164,6 +166,8 @@ def collect_prefixed_parameters():
if (it := collect_prefixed_parameters()) != []:
parameters += [{"autoware.": it}]

parameters += [parameter_file_path.perform(context)]

return parameters

return [
Expand All @@ -180,13 +184,14 @@ def collect_prefixed_parameters():
DeclareLaunchArgument("launch_autoware", default_value=launch_autoware ),
DeclareLaunchArgument("launch_rviz", default_value=launch_rviz ),
DeclareLaunchArgument("output_directory", default_value=output_directory ),
DeclareLaunchArgument("parameter_file_path", default_value=parameter_file_path ),
DeclareLaunchArgument("publish_empty_context", default_value=publish_empty_context ),
DeclareLaunchArgument("rviz_config", default_value=rviz_config ),
DeclareLaunchArgument("scenario", default_value=scenario ),
DeclareLaunchArgument("sensor_model", default_value=sensor_model ),
DeclareLaunchArgument("sigterm_timeout", default_value=sigterm_timeout ),
DeclareLaunchArgument("simulate_localization", default_value=simulate_localization ),
DeclareLaunchArgument("speed_condition", default_value=speed_condition ),
DeclareLaunchArgument("speed_condition", default_value=speed_condition ),
DeclareLaunchArgument("use_sim_time", default_value=use_sim_time ),
DeclareLaunchArgument("vehicle_model", default_value=vehicle_model ),
# fmt: on
Expand Down

0 comments on commit abbcdc4

Please sign in to comment.