From 9dfed7e70d7cbb514aeb3d9f8d4f003dad2ca8e7 Mon Sep 17 00:00:00 2001 From: Shintaro Sakoda Date: Wed, 6 Nov 2024 17:57:55 +0900 Subject: [PATCH] Added a new argument "plot_function_level_processing_time" Signed-off-by: Shintaro Sakoda --- .../processing_time_plotter.py | 36 ++++++++++++------- .../system_performance_plotter_base.py | 13 ++++++- 2 files changed, 36 insertions(+), 13 deletions(-) diff --git a/common/autoware_debug_tools/autoware_debug_tools/system_performance_plotter/processing_time_plotter.py b/common/autoware_debug_tools/autoware_debug_tools/system_performance_plotter/processing_time_plotter.py index c865deff..6ebb6ad7 100644 --- a/common/autoware_debug_tools/autoware_debug_tools/system_performance_plotter/processing_time_plotter.py +++ b/common/autoware_debug_tools/autoware_debug_tools/system_performance_plotter/processing_time_plotter.py @@ -1,6 +1,6 @@ #!/usr/bin/env python3 -from tier4_debug_msgs.msg import Float64Stamped +from tier4_debug_msgs.msg import Float64Stamped, ProcessingTimeTree from .system_performance_plotter_base import PREDEFINED_COMPONENT_NAMES from .system_performance_plotter_base import SystemPerformancePlotterBase @@ -28,17 +28,29 @@ def check_topic(self, topic_name): return False return True - def update_metrics_func(self, topic_name, data, date_time): - if not isinstance(data, Float64Stamped): - return - - if topic_name not in self.stamp_and_metrics: - self.stamp_and_metrics[topic_name] = [] - self.max_metrics[topic_name] = 0.0 - - processing_time_ms = data.data - self.stamp_and_metrics[topic_name].append([date_time, processing_time_ms]) - self.max_metrics[topic_name] = max(self.max_metrics[topic_name], processing_time_ms) + def update_metrics_func(self, topic_name, data, date_time, parse_processing_time_tree=False): + if isinstance(data, Float64Stamped): + if topic_name not in self.stamp_and_metrics: + self.stamp_and_metrics[topic_name] = [] + self.max_metrics[topic_name] = 0.0 + + processing_time_ms = data.data + self.stamp_and_metrics[topic_name].append([date_time, processing_time_ms]) + self.max_metrics[topic_name] = max(self.max_metrics[topic_name], processing_time_ms) + elif isinstance(data, ProcessingTimeTree) and parse_processing_time_tree: + for node in data.nodes: + curr_name = topic_name + ":" + node.name + if curr_name not in self.stamp_and_metrics: + self.stamp_and_metrics[curr_name] = [] + self.max_metrics[curr_name] = 0.0 + + processing_time_ms = node.processing_time + self.stamp_and_metrics[curr_name].append( + [date_time, processing_time_ms] + ) + self.max_metrics[curr_name] = max( + self.max_metrics[curr_name], processing_time_ms + ) def main(): diff --git a/common/autoware_debug_tools/autoware_debug_tools/system_performance_plotter/system_performance_plotter_base.py b/common/autoware_debug_tools/autoware_debug_tools/system_performance_plotter/system_performance_plotter_base.py index 76e73360..ec58ec23 100644 --- a/common/autoware_debug_tools/autoware_debug_tools/system_performance_plotter/system_performance_plotter_base.py +++ b/common/autoware_debug_tools/autoware_debug_tools/system_performance_plotter/system_performance_plotter_base.py @@ -43,6 +43,10 @@ def __init__(self, args, ylabel, output_suffix): self.stamp_and_metrics = {} self.max_metrics = {} + self.additional_args = {} + if args.plot_function_level_processing_time: + self.additional_args["parse_processing_time_tree"] = True + def run(self): # read data from rosbag reader = create_reader(self.input_bag_dir) @@ -60,7 +64,7 @@ def run(self): time_stamp = stamp * to_nanosec date_time = datetime.fromtimestamp(time_stamp) - self.update_metrics_func(topic_name, data, date_time) + self.update_metrics_func(topic_name, data, date_time, **self.additional_args) # sort stamp_and_metrics by alphabetical order self.stamp_and_metrics = dict(sorted(self.stamp_and_metrics.items(), key=lambda x: x[0])) @@ -202,6 +206,13 @@ def create_common_argment(ymax=None): action="store_true", help="whether to skip plt.show()", ) + parser.add_argument( + "-f", + "--plot_function_level_processing_time", + default=False, + action="store_true", + help="whether to plot function level processing time", + ) args = parser.parse_args()