本教程展示了如何使用 ros2_tracing https://github.com/ros2/ros2_tracing来跟踪和分析 ROS 2 应用程序。在本教程中,应用程序将是 performance_test。https://gitlab.com/ApexAI/performance_test
概述
本教程涵盖:
运行和跟踪
performance_test
运行使用 tracetools_analysis https://github.com/ros-tracing/tracetools_analysis 分析跟踪数据以绘制回调持续时间
先决条件
本教程针对实时 Linux 系统。请参阅实时系统设置教程 https://docs.ros.org/en/jazzy/Tutorials/Miscellaneous/Building-Realtime-rt_preempt-kernel-for-ROS-2.html 。但是,如果您使用的是非实时 Linux 系统,本教程也适用。
安装和构建
按照安装说明在 Linux 上安装 ROS 2。https://docs.ros.org/en/jazzy/Installation.html
便条
本教程通常适用于所有受支持的 Linux 发行版。但是,您可能需要调整一些命令。
安装 babeltrace
和 ros2trace
。
sudo apt-get update
sudo apt-get install -y babeltrace ros-jazzy-ros2trace ros-jazzy-tracetools-analysis
源 ROS 2 安装并验证跟踪是否已启用:
source /opt/ros/jazzy/setup.bash
ros2 run tracetools status
您应该在输出中看到 Tracing enabled
。
然后创建一个工作区,并克隆 performance_test
和 tracetools_analysis
。
cd ~/
mkdir -p tracing_ws/src
cd tracing_ws/src/
git clone https://gitlab.com/ApexAI/performance_test.git
git clone https://github.com/ros-tracing/tracetools_analysis.git
cd ..
使用 rosdep 安装依赖项。
rosdep update
rosdep install --from-paths src --ignore-src -y
然后为 ROS 2 构建和配置 performance_test
。请参阅其文档。https://gitlab.com/ApexAI/performance_test/-/tree/master/performance_test#performance_test
colcon build --packages-select performance_test --cmake-args -DPERFORMANCE_TEST_RCLCPP_ENABLED=ON
接下来,我们将进行一个 performance_test
实验并追踪它。
追踪
第 1 步:追踪
在一个终端中,配置工作区并设置跟踪。运行命令时,将打印出 ROS 2 用户空间事件列表。它还会打印出包含结果跟踪的目录路径(在 ~/.ros/tracing
下)。
# terminal 1
cd ~/tracing_ws
source install/setup.bash
ros2 trace --session-name perf-test --list
按回车键开始跟踪。
cxy@ubuntu2404-cxy:~/tracing_ws$ ros2 trace --session-name perf-test --list
UST tracing enabled (35 events)
ros2:rcl_init
ros2:rcl_node_init
ros2:rmw_publisher_init
ros2:rcl_publisher_init
ros2:rclcpp_publish
ros2:rclcpp_intra_publish
ros2:rcl_publish
ros2:rmw_publish
ros2:rmw_subscription_init
ros2:rcl_subscription_init
ros2:rclcpp_subscription_init
ros2:rclcpp_subscription_callback_added
ros2:rmw_take
ros2:rcl_take
ros2:rclcpp_take
ros2:rcl_service_init
ros2:rclcpp_service_callback_added
ros2:rcl_client_init
ros2:rcl_timer_init
ros2:rclcpp_timer_callback_added
ros2:rclcpp_timer_link_node
ros2:rclcpp_callback_register
ros2:callback_start
ros2:callback_end
ros2:rcl_lifecycle_state_machine_init
ros2:rcl_lifecycle_transition
ros2:rclcpp_executor_get_next_ready
ros2:rclcpp_executor_wait_for_work
ros2:rclcpp_executor_execute
ros2:rclcpp_ipb_to_subscription
ros2:rclcpp_buffer_to_ipb
ros2:rclcpp_construct_ring_buffer
ros2:rclcpp_ring_buffer_enqueue
ros2:rclcpp_ring_buffer_dequeue
ros2:rclcpp_ring_buffer_clear
kernel tracing disabled
context (3 fields)
procname
vpid
vtid
writing tracing session to: /home/cxy/.ros/tracing/perf-test
press enter to start...
error: trace directory already exists, use the append option to append to it: /home/cxy/.ros/tracing/perf-test
第二次运行命令,需删除该文件夹
第 2 步:运行应用程序
在第二个终端中,配置工作区。
# terminal 2
cd ~/tracing_ws
source install/setup.bash
然后运行 performance_test
实验(或您自己的应用程序)。我们只是创建一个实验,让一个节点以尽可能快的速度向另一个节点发布约 1 MB 的消息,持续 60 秒,使用第二高的实时优先级,以便我们不会干扰关键的内核线程。我们需要以 root
的身份运行 performance_test
,才能使用实时优先级。
# terminal 2
sudo ./install/performance_test/lib/performance_test/perf_test -c rclcpp-single-threaded-executor -p 1 -s 1 -r 0 -m Array1m --reliability RELIABLE --max-runtime 60 --use-rt-prio 98
如果最后一个命令对您不起作用(出现类似“加载共享库时出错”的错误),请运行下面稍有不同的命令。这是因为出于安全原因,我们需要手动传递 *PATH
环境变量才能找到某些共享库(请参阅此解释 https://unix.stackexchange.com/a/251374 )。
# terminal 2
sudo env PATH="$PATH" LD_LIBRARY_PATH="$LD_LIBRARY_PATH" ./install/performance_test/lib/performance_test/perf_test -c rclcpp-single-threaded-executor -p 1 -s 1 -r 0 -m Array1m --reliability RELIABLE --max-runtime 60 --use-rt-prio 98
便条
如果你没有使用实时内核,只需运行:
# terminal 2
./install/performance_test/lib/performance_test/perf_test -c rclcpp-single-threaded-executor -p 1 -s 1 -r 0 -m Array1m --reliability RELIABLE --max-runtime 60
cxy@ubuntu2404-cxy:~/tracing_ws$ ./install/performance_test/lib/performance_test/perf_test -c rclcpp-single-threaded-executor -p 1 -s 1 -r 0 -m Array1m --reliability RELIABLE --max-runtime 60
WARNING: No output configured
Maximum runtime reached. Exiting.
cxy@ubuntu2404-cxy:~/tracing_ws$ ros2 trace --session-name perf-test --list
UST tracing enabled (35 events)
ros2:rcl_init
ros2:rcl_node_init
ros2:rmw_publisher_init
ros2:rcl_publisher_init
ros2:rclcpp_publish
ros2:rclcpp_intra_publish
ros2:rcl_publish
ros2:rmw_publish
ros2:rmw_subscription_init
ros2:rcl_subscription_init
ros2:rclcpp_subscription_init
ros2:rclcpp_subscription_callback_added
ros2:rmw_take
ros2:rcl_take
ros2:rclcpp_take
ros2:rcl_service_init
ros2:rclcpp_service_callback_added
ros2:rcl_client_init
ros2:rcl_timer_init
ros2:rclcpp_timer_callback_added
ros2:rclcpp_timer_link_node
ros2:rclcpp_callback_register
ros2:callback_start
ros2:callback_end
ros2:rcl_lifecycle_state_machine_init
ros2:rcl_lifecycle_transition
ros2:rclcpp_executor_get_next_ready
ros2:rclcpp_executor_wait_for_work
ros2:rclcpp_executor_execute
ros2:rclcpp_ipb_to_subscription
ros2:rclcpp_buffer_to_ipb
ros2:rclcpp_construct_ring_buffer
ros2:rclcpp_ring_buffer_enqueue
ros2:rclcpp_ring_buffer_dequeue
ros2:rclcpp_ring_buffer_clear
kernel tracing disabled
context (3 fields)
procname
vpid
vtid
writing tracing session to: /home/cxy/.ros/tracing/perf-test
press enter to start...
press enter to stop...
stopping & destroying tracing session
步骤 3:验证跟踪
一旦实验完成,在第一个终端中,再次按回车键以停止跟踪。使用 babeltrace
快速查看结果跟踪。
babeltrace ~/.ros/tracing/perf-test | less
上述命令的输出是原始通用跟踪格式(CTF)数据的可读版本,即跟踪事件列表。每个事件都有一个时间戳、事件类型、生成事件的进程信息以及给定事件类型字段的值。
使用箭头键滚动,或按 q
退出。
接下来,我们将分析轨迹。
分析
tracetools_analysis https://github.com/ros-tracing/tracetools_analysis 提供了一个 Python API,可以轻松分析跟踪。我们可以在 Jupyter notebook https://jupyter.org/ 中使用 bokeh https://docs.bokeh.org/en/latest/index.html 来绘制数据。 tracetools_analysis
仓库包含一些示例笔记本 https://github.com/ros-tracing/tracetools_analysis/tree/jazzy/tracetools_analysis/analysis ,包括一个用于分析订阅回调持续时间的笔记本 https://github.com/ros-tracing/tracetools_analysis/blob/jazzy/tracetools_analysis/analysis/callback_duration.ipynb 。
对于本教程,我们将在订阅者节点中绘制订阅回调的持续时间。
安装 Jupyter notebook 和 bokeh,然后打开示例 notebook。
pip3 install bokeh
jupyter notebook ~/tracing_ws/src/tracetools_analysis/tracetools_analysis/analysis/callback_duration.ipynb
这将在浏览器中打开笔记本。
将第二个单元格中 path
变量的值替换为跟踪目录的路径:
path = '~/.ros/tracing/perf-test'
运行笔记本时,请单击每个单元格的运行按钮。第一次运行执行跟踪处理的单元格可能需要几分钟,但随后的运行将快得多。
你应该得到一个类似这样的图表:
我们可以看到大多数回调的耗时少于 0.01 毫秒,但有一些异常值超过了 0.02 或 0.03 毫秒。
结论
本教程展示了如何安装与跟踪相关的工具。然后,它展示了如何使用 ros2_tracing https://github.com/ros2/ros2_tracing 跟踪 performance_test 实验https://gitlab.com/ApexAI/performance_test ,并使用 tracetools_analysis https://github.com/ros-tracing/tracetools_analysis 绘制回调持续时间。
要进行更多的跟踪分析,请查看其他示例笔记本 https://github.com/ros-tracing/tracetools_analysis/tree/jazzy/tracetools_analysis/analysis 和 tracetools_analysis API 文档 https://docs.ros.org/en/jazzy/p/tracetools_analysis/。ros2_tracing 设计文档 https://github.com/ros2/ros2_tracing/blob/jazzy/doc/design_ros_2.md 也包含了很多信息。
附录:
tracetools_analysis/analysis/callback_duration.ipynb
# 回调持续时间
#
# 使用提供的启动文件获取跟踪数据:
# $ ros2 launch tracetools_analysis pingpong.launch.py
# (等待至少几秒钟,然后使用 Ctrl+C 终止)
#
# 或者
#
# 使用提供的示例转换跟踪文件,将路径更改为:
# 'sample_data/converted_pingpong'
path = '~/.ros/tracing/pingpong/ust'
#path = 'sample_data/converted_pingpong'
import sys
# 添加 tracetools_analysis 和 tracetools_read 的路径。
# 有两种方式:
# 1. 从源码,假设工作空间包含:
# src/tracetools_analysis/
# src/ros2/ros2_tracing/tracetools_read/
sys.path.insert(0, '../')
sys.path.insert(0, '../../../ros2/ros2_tracing/tracetools_read/')
# 2. 从 Debian 软件包,设置正确的 ROS 2 发行版:
#ROS_DISTRO = 'rolling'
#sys.path.insert(0, f'/opt/ros/{ROS_DISTRO}/lib/python3.8/site-packages')
import datetime as dt
from bokeh.plotting import figure # 导入 bokeh 画图功能
from bokeh.plotting import output_notebook # 导入 bokeh 的输出到笔记本功能
from bokeh.io import show # 导入 bokeh 的显示功能
from bokeh.layouts import row # 导入 bokeh 布局功能
from bokeh.models import ColumnDataSource # 导入 bokeh 的数据源模型
from bokeh.models import DatetimeTickFormatter # 导入 bokeh 的日期时间格式化功能
from bokeh.models import PrintfTickFormatter # 导入 bokeh 的打印格式化功能
import numpy as np # 导入 NumPy 库
import pandas as pd # 导入 Pandas 库
from tracetools_analysis.loading import load_file # 导入 tracetools_analysis 的文件加载功能
from tracetools_analysis.processor.ros2 import Ros2Handler # 导入 tracetools_analysis 的 ROS 2 处理器
from tracetools_analysis.utils.ros2 import Ros2DataModelUtil # 导入 tracetools_analysis 的 ROS 2 数据模型工具
# 处理数据
events = load_file(path) # 加载跟踪文件
handler = Ros2Handler.process(events) # 处理事件
#handler.data.print_data() # 打印数据(注释掉)
data_util = Ros2DataModelUtil(handler.data) # 创建数据工具实例
callback_symbols = data_util.get_callback_symbols() # 获取回调符号
output_notebook() # 输出到笔记本
psize = 450 # 图表大小
# 如果跟踪包含更多回调,可以在这里添加颜色
# 或使用:https://docs.bokeh.org/en/3.2.2/docs/reference/palettes.html
colours = ['#29788E', '#DD4968', '#410967']
# 分别绘制持续时间
colour_i = 0
for obj, symbol in callback_symbols.items(): # 遍历每个回调符号
owner_info = data_util.get_callback_owner_info(obj) # 获取回调拥有者信息
if owner_info is None: # 如果没有拥有者信息
owner_info = '[unknown]' # 设置为未知
# 过滤掉内部订阅
if '/parameter_events' in owner_info:
continue
# 持续时间
duration_df = data_util.get_callback_durations(obj) # 获取回调持续时间数据
starttime = duration_df.loc[:, 'timestamp'].iloc[0].strftime('%Y-%m-%d %H:%M') # 获取开始时间
source = ColumnDataSource(duration_df) # 创建数据源
duration = figure(
title=owner_info,
x_axis_label=f'start ({starttime})',
y_axis_label='duration (ms)',
width=psize, height=psize,
)
duration.title.align = 'center' # 标题居中
duration.line(
x='timestamp',
y='duration',
legend_label=str(symbol),
line_width=2,
source=source,
line_color=colours[colour_i],
)
duration.legend.label_text_font_size = '11px' # 图例字体大小
duration.xaxis[0].formatter = DatetimeTickFormatter(seconds='%Ss') # X轴格式化
# 直方图
# (转换为毫秒)
dur_hist, edges = np.histogram(duration_df['duration'] * 1000 / np.timedelta64(1, 's')) # 计算直方图
duration_hist = pd.DataFrame({
'duration': dur_hist,
'left': edges[:-1],
'right': edges[1:],
})
hist = figure(
title='Duration histogram',
x_axis_label='duration (ms)',
y_axis_label='frequency',
width=psize, height=psize,
)
hist.title.align = 'center' # 标题居中
hist.quad(
bottom=0,
top=duration_hist['duration'],
left=duration_hist['left'],
right=duration_hist['right'],
fill_color=colours[colour_i],
line_color=colours[colour_i],
)
colour_i += 1
colour_i %= len(colours)
show(row(duration, hist)) # 显示图表
# 在一个图表中绘制所有持续时间
earliest_date = None
for obj, symbol in callback_symbols.items():
duration_df = data_util.get_callback_durations(obj)
thedate = duration_df.loc[:, 'timestamp'].iloc[0]
if earliest_date is None or thedate <= earliest_date:
earliest_date = thedate
starttime = earliest_date.strftime('%Y-%m-%d %H:%M')
duration = figure(
title='Callback durations',
x_axis_label=f'start ({starttime})',
y_axis_label='duration (ms)',
width=psize, height=psize,
)
colour_i = 0
for obj, symbol in callback_symbols.items():
# 过滤掉内部订阅
owner_info = data_util.get_callback_owner_info(obj)
if not owner_info or '/parameter_events' in owner_info:
continue
duration_df = data_util.get_callback_durations(obj)
source = ColumnDataSource(duration_df)
duration.title.align = 'center'
duration.line(
x='timestamp',
y='duration',
legend_label=str(symbol),
line_width=2,
source=source,
line_color=colours[colour_i],
)
colour_i += 1
colour_i %= len(colours)
duration.legend.label_text_font_size = '11px'
duration.xaxis[0].formatter = DatetimeTickFormatter(seconds='%Ss')
show(duration) # 显示图表