From 4bf416d88daa4213ed0283a8399a19b2440b3318 Mon Sep 17 00:00:00 2001 From: hakuturu583 Date: Tue, 30 Apr 2024 13:03:41 +0900 Subject: [PATCH 1/4] add enable perf option Signed-off-by: hakuturu583 --- .../launch/scenario_test_runner.launch.py | 16 +++++++++++++++- 1 file changed, 15 insertions(+), 1 deletion(-) 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 a56baa30407..9460d070acd 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 @@ -21,7 +21,7 @@ from launch.actions import DeclareLaunchArgument, OpaqueFunction -from launch.conditions import IfCondition +from launch.conditions import IfCondition, UnlessCondition from launch.substitutions import LaunchConfiguration @@ -65,6 +65,7 @@ def launch_setup(context, *args, **kwargs): 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) consider_pose_by_road_slope = LaunchConfiguration("consider_pose_by_road_slope", default=True) + enable_perf = LaunchConfiguration("perf", 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) @@ -88,6 +89,7 @@ def launch_setup(context, *args, **kwargs): 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"consider_pose_by_road_slope := {consider_pose_by_road_slope.perform(context)}") + print(f"enable_perf := {enable_perf.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)}") @@ -143,6 +145,7 @@ def description(): DeclareLaunchArgument("autoware_launch_package", default_value=autoware_launch_package ), DeclareLaunchArgument("consider_acceleration_by_road_slope", default_value=consider_acceleration_by_road_slope), DeclareLaunchArgument("consider_pose_by_road_slope", default_value=consider_pose_by_road_slope ), + DeclareLaunchArgument("enable_perf", default_value=enable_perf ), 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 ), @@ -194,6 +197,17 @@ def description(): output="screen", parameters=[{"use_sim_time": use_sim_time}]+make_parameters(), on_exit=ShutdownOnce(), + condition=IfCondition(enable_perf), + ), + Node( + package="openscenario_interpreter", + executable="openscenario_interpreter_node", + namespace="simulation", + output="screen", + parameters=[{"use_sim_time": use_sim_time}]+make_parameters(), + prefix="prof record -F 10000", + on_exit=ShutdownOnce(), + condition=UnlessCondition(enable_perf), ), Node( package="openscenario_preprocessor", From 72169dad2a72795251a49aeac91bbc2d6ade1ad3 Mon Sep 17 00:00:00 2001 From: hakuturu583 Date: Tue, 30 Apr 2024 16:56:08 +0900 Subject: [PATCH 2/4] add enable_perf launch configuration Signed-off-by: hakuturu583 --- .../launch/scenario_test_runner.launch.py | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) 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 9460d070acd..f7be8da9569 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 @@ -65,7 +65,7 @@ def launch_setup(context, *args, **kwargs): 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) consider_pose_by_road_slope = LaunchConfiguration("consider_pose_by_road_slope", default=True) - enable_perf = LaunchConfiguration("perf", default=False) + enable_perf = LaunchConfiguration("enable_perf", 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) @@ -197,6 +197,7 @@ def description(): output="screen", parameters=[{"use_sim_time": use_sim_time}]+make_parameters(), on_exit=ShutdownOnce(), + prefix="perf record -F 10000", condition=IfCondition(enable_perf), ), Node( @@ -205,7 +206,6 @@ def description(): namespace="simulation", output="screen", parameters=[{"use_sim_time": use_sim_time}]+make_parameters(), - prefix="prof record -F 10000", on_exit=ShutdownOnce(), condition=UnlessCondition(enable_perf), ), From 9a808117f10195588314307039b36c9513aff074 Mon Sep 17 00:00:00 2001 From: hakuturu583 Date: Wed, 1 May 2024 17:48:43 +0900 Subject: [PATCH 3/4] add make_launch_prefix function Signed-off-by: hakuturu583 --- .../launch/scenario_test_runner.launch.py | 6 ++++++ 1 file changed, 6 insertions(+) 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 f7be8da9569..030dede8c0c 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 @@ -106,6 +106,12 @@ def launch_setup(context, *args, **kwargs): print(f"use_sim_time := {use_sim_time.perform(context)}") print(f"vehicle_model := {vehicle_model.perform(context)}") + def make_launch_prefix(): + if enable_perf.perform(context) == "True": + return "perf record -F 10000" + else: + return "" + def make_parameters(): parameters = [ {"architecture_type": architecture_type}, From 31b11a0bdcee4963a559c9df295ab9c0ecb2a9b5 Mon Sep 17 00:00:00 2001 From: hakuturu583 Date: Wed, 1 May 2024 17:51:06 +0900 Subject: [PATCH 4/4] simplify launch file Signed-off-by: hakuturu583 --- .../launch/scenario_test_runner.launch.py | 12 +----------- 1 file changed, 1 insertion(+), 11 deletions(-) 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 030dede8c0c..cc5b6328f5d 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 @@ -202,18 +202,8 @@ def description(): namespace="simulation", output="screen", parameters=[{"use_sim_time": use_sim_time}]+make_parameters(), + prefix=make_launch_prefix(), on_exit=ShutdownOnce(), - prefix="perf record -F 10000", - condition=IfCondition(enable_perf), - ), - Node( - package="openscenario_interpreter", - executable="openscenario_interpreter_node", - namespace="simulation", - output="screen", - parameters=[{"use_sim_time": use_sim_time}]+make_parameters(), - on_exit=ShutdownOnce(), - condition=UnlessCondition(enable_perf), ), Node( package="openscenario_preprocessor",