diff --git a/test_runner/scenario_test_runner/launch/scenario_test_runner.launch.py b/test_runner/scenario_test_runner/launch/scenario_test_runner.launch.py index 047b9515896..36d6a688fbb 100755 --- a/test_runner/scenario_test_runner/launch/scenario_test_runner.launch.py +++ b/test_runner/scenario_test_runner/launch/scenario_test_runner.launch.py @@ -60,45 +60,47 @@ def default_autoware_launch_file_of(architecture_type): def launch_setup(context, *args, **kwargs): # fmt: off - architecture_type = LaunchConfiguration("architecture_type", default="awf/universe") - autoware_launch_file = LaunchConfiguration("autoware_launch_file", default=default_autoware_launch_file_of(architecture_type.perform(context))) - autoware_launch_package = LaunchConfiguration("autoware_launch_package", default=default_autoware_launch_package_of(architecture_type.perform(context))) - global_frame_rate = LaunchConfiguration("global_frame_rate", default=30.0) - global_real_time_factor = LaunchConfiguration("global_real_time_factor", default=1.0) - global_timeout = LaunchConfiguration("global_timeout", default=180) - initialize_duration = LaunchConfiguration("initialize_duration", default=30) - launch_autoware = LaunchConfiguration("launch_autoware", default=True) - 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")) - port = LaunchConfiguration("port", default=5555) - record = LaunchConfiguration("record", default=True) - rviz_config = LaunchConfiguration("rviz_config", default="") - scenario = LaunchConfiguration("scenario", default=Path("/dev/null")) - sensor_model = LaunchConfiguration("sensor_model", default="") - sigterm_timeout = LaunchConfiguration("sigterm_timeout", default=8) - vehicle_model = LaunchConfiguration("vehicle_model", default="") - workflow = LaunchConfiguration("workflow", default=Path("/dev/null")) + architecture_type = LaunchConfiguration("architecture_type", default="awf/universe") + autoware_launch_file = LaunchConfiguration("autoware_launch_file", default=default_autoware_launch_file_of(architecture_type.perform(context))) + autoware_launch_package = LaunchConfiguration("autoware_launch_package", default=default_autoware_launch_package_of(architecture_type.perform(context))) + consider_acceleration_by_road_slope = LaunchConfiguration("consider_acceleration_by_road_slope", default=False) + global_frame_rate = LaunchConfiguration("global_frame_rate", default=30.0) + global_real_time_factor = LaunchConfiguration("global_real_time_factor", default=1.0) + global_timeout = LaunchConfiguration("global_timeout", default=180) + initialize_duration = LaunchConfiguration("initialize_duration", default=30) + launch_autoware = LaunchConfiguration("launch_autoware", default=True) + 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")) + port = LaunchConfiguration("port", default=5555) + record = LaunchConfiguration("record", default=True) + rviz_config = LaunchConfiguration("rviz_config", default="") + scenario = LaunchConfiguration("scenario", default=Path("/dev/null")) + sensor_model = LaunchConfiguration("sensor_model", default="") + sigterm_timeout = LaunchConfiguration("sigterm_timeout", default=8) + vehicle_model = LaunchConfiguration("vehicle_model", default="") + workflow = LaunchConfiguration("workflow", default=Path("/dev/null")) # fmt: on - print(f"architecture_type := {architecture_type.perform(context)}") - print(f"autoware_launch_file := {autoware_launch_file.perform(context)}") - print(f"autoware_launch_package := {autoware_launch_package.perform(context)}") - print(f"global_frame_rate := {global_frame_rate.perform(context)}") - print(f"global_real_time_factor := {global_real_time_factor.perform(context)}") - print(f"global_timeout := {global_timeout.perform(context)}") - print(f"initialize_duration := {initialize_duration.perform(context)}") - 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"port := {port.perform(context)}") - print(f"record := {record.perform(context)}") - print(f"rviz_config := {rviz_config.perform(context)}") - print(f"scenario := {scenario.perform(context)}") - print(f"sensor_model := {sensor_model.perform(context)}") - print(f"sigterm_timeout := {sigterm_timeout.perform(context)}") - print(f"vehicle_model := {vehicle_model.perform(context)}") - print(f"workflow := {workflow.perform(context)}") + print(f"architecture_type := {architecture_type.perform(context)}") + print(f"autoware_launch_file := {autoware_launch_file.perform(context)}") + print(f"autoware_launch_package := {autoware_launch_package.perform(context)}") + print(f"consider_acceleration_by_road_slope := {consider_acceleration_by_road_slope.perform(context)}") + print(f"global_frame_rate := {global_frame_rate.perform(context)}") + print(f"global_real_time_factor := {global_real_time_factor.perform(context)}") + print(f"global_timeout := {global_timeout.perform(context)}") + print(f"initialize_duration := {initialize_duration.perform(context)}") + 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"port := {port.perform(context)}") + print(f"record := {record.perform(context)}") + print(f"rviz_config := {rviz_config.perform(context)}") + print(f"scenario := {scenario.perform(context)}") + print(f"sensor_model := {sensor_model.perform(context)}") + print(f"sigterm_timeout := {sigterm_timeout.perform(context)}") + print(f"vehicle_model := {vehicle_model.perform(context)}") + print(f"workflow := {workflow.perform(context)}") def make_parameters(): parameters = [ @@ -115,7 +117,7 @@ def make_parameters(): ] parameters += make_vehicle_parameters() return parameters - + def make_vehicle_parameters(): parameters = [] @@ -131,21 +133,21 @@ def description(): return [ # fmt: off - DeclareLaunchArgument("architecture_type", default_value=architecture_type ), - DeclareLaunchArgument("autoware_launch_file", default_value=autoware_launch_file ), + DeclareLaunchArgument("architecture_type", default_value=architecture_type), + DeclareLaunchArgument("autoware_launch_file", default_value=autoware_launch_file), DeclareLaunchArgument("autoware_launch_package", default_value=autoware_launch_package), - DeclareLaunchArgument("global_frame_rate", default_value=global_frame_rate ), + DeclareLaunchArgument("global_frame_rate", default_value=global_frame_rate), DeclareLaunchArgument("global_real_time_factor", default_value=global_real_time_factor), - DeclareLaunchArgument("global_timeout", default_value=global_timeout ), - DeclareLaunchArgument("launch_autoware", default_value=launch_autoware ), - DeclareLaunchArgument("launch_rviz", default_value=launch_rviz ), - DeclareLaunchArgument("output_directory", default_value=output_directory ), - 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("vehicle_model", default_value=vehicle_model ), - DeclareLaunchArgument("workflow", default_value=workflow ), + DeclareLaunchArgument("global_timeout", default_value=global_timeout), + DeclareLaunchArgument("launch_autoware", default_value=launch_autoware), + DeclareLaunchArgument("launch_rviz", default_value=launch_rviz), + DeclareLaunchArgument("output_directory", default_value=output_directory), + 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("vehicle_model", default_value=vehicle_model), + DeclareLaunchArgument("workflow", default_value=workflow), # fmt: on Node( package="scenario_test_runner", @@ -156,12 +158,12 @@ def description(): on_exit=ShutdownOnce(), arguments=[ # fmt: off - "--global-frame-rate", global_frame_rate, + "--global-frame-rate", global_frame_rate, "--global-real-time-factor", global_real_time_factor, - "--global-timeout", global_timeout, - "--output-directory", output_directory, - "--scenario", scenario, - "--workflow", workflow, + "--global-timeout", global_timeout, + "--output-directory", output_directory, + "--scenario", scenario, + "--workflow", workflow, # fmt: on ], ), @@ -171,7 +173,8 @@ def description(): namespace="simulation", output="screen", on_exit=ShutdownOnce(), - parameters=[{"port": port}]+make_vehicle_parameters(), + parameters=[{"port": port}, {"consider_acceleration_by_road_slope", + consider_acceleration_by_road_slope}] + make_vehicle_parameters(), condition=IfCondition(launch_simple_sensor_simulator), ), # The `name` keyword overrides the name for all created nodes, so duplicated nodes appear.