在 ROS 2/Nav2 中获取 Backtrace
概述
本文档解释了一组获取 ROS 2 和 Nav2 回溯的方法。 有很多方法可以实现这一点,但这对于没有 GDB 经验的新 C++ 开发人员来说是一个很好的起点。
以下步骤向 ROS 2 用户展示如何修改 Nav2 堆栈,以便在遇到问题时从特定服务器获取跟踪信息。 本教程适用于模拟机器人和物理机器人。
这将涵盖如何使用“ros2 run”从特定节点、使用“ros2 launch”从表示单个节点的启动文件以及从更复杂的节点编排获取回溯。 在本教程结束时,当您注意到 ROS 2 中的服务器崩溃时,您应该能够获得回溯。
预赛
GDB 是 Unix 系统上最流行的 C++ 调试器。 它可用于确定崩溃的原因并跟踪线程。 它还可用于在代码中添加断点,以检查软件中特定点的内存中的值。
对于所有使用 C/C++ 的软件开发人员来说,使用 GDB 是一项关键技能。 许多 IDE 都会内置某种调试器或分析器,但对于 ROS,几乎没有 IDE 可供选择。 因此,了解如何使用这些可用的原始工具而不是依赖 IDE 提供的工具非常重要。 此外,了解这些工具是 C/C++ 开发的一项基本技能,如果您更改角色并且不再有权访问它,或者通过 ssh 会话到远程资产进行即时开发,那么将其交给您的 IDE 可能会出现问题。
幸运的是,在掌握了基础知识之后,使用 GDB 就相当简单了。 第一步是将“-g”添加到您想要分析/调试的 ROS 包的编译器标志中。 该标志构建 GDB 和 valgrind 可以读取的调试符号,以告诉您项目中的特定代码行失败以及原因。 如果不设置此标志,您仍然可以获得回溯,但它不会提供失败的行号。 请务必在调试后删除此标志,它会降低运行时的性能。
将以下行添加到项目的“CMakeLists.txt”中应该可以解决问题。 如果您的项目已经有“add_compile_options()”,您只需添加“-g”即可。 然后只需使用此包“colcon build –packages-select <package-name>”重建您的工作区即可。 编译时间可能比平常要长一些。
add_compile_options(-g)
现在您已准备好调试代码了! 如果这是一个非 ROS 项目,此时您可能会执行如下操作。 这里我们启动一个 GDB 会话并告诉我们的程序立即运行。 一旦你的程序崩溃,它将返回一个 gdb 会话,并立即用“(gdb)”表示。 出现此提示时,您可以访问您感兴趣的信息。 然而,由于这是一个包含大量节点配置和其他事情的 ROS 项目,因此对于初学者或那些不喜欢大量命令行工作和了解文件系统的人来说,这不是一个很好的选择。
gdb ex run --args /path/to/exe/program
以下部分描述了基于 ROS 2 的系统可能遇到的 3 种主要情况。 阅读最能描述您要解决的问题的部分。
From a Node
就像我们的非 ROS 示例一样,我们需要在启动 ROS 2 节点之前设置 GDB 会话。 虽然我们可以使用 ROS 2 文件系统的一些知识通过命令行进行设置,但我们可以使用 Open Robotics 的人员为我们提供的启动“–prefix”选项。
“–prefix”将在“ros2”命令之前执行一些代码,允许我们插入一些信息。 如果您尝试执行类似于我们在预备部分中的示例的“gdb ex run –args ros2 run <pkg> <node>”,您会发现它找不到“ros2”命令。 如果您更聪明,您会发现尝试获取工作空间也会因类似的原因而失败。
我们可以使用“–prefix”,而不是重新找到可执行文件的安装路径并将其全部输入。 这允许我们使用您习惯的相同的“ros2 run”语法,而不必担心一些 GDB 细节。
ros2 run --prefix 'gdb -ex run --args' <pkg> <node> --all-other-launch arguments
和以前一样,此前缀将启动 GDB 会话并使用所有其他命令行参数运行您请求的节点。 现在,您的节点应该正在运行,并且应该会伴随着一些调试打印。
一旦您的服务器崩溃,您将看到如下提示。此时您现在可以获得回溯。
(gdb)
在此会话中,输入“backtrace”,它将为您提供回溯。 根据您的需要复制此内容。 例如:
(gdb) backtrace
#0 __GI_raise (sig=sig@entry=6) at ../sysdeps/unix/sysv/linux/raise.c:50
#1 0x00007ffff79cc859 in __GI_abort () at abort.c:79
#2 0x00007ffff7c52951 in ?? () from /usr/lib/x86_64-linux-gnu/libstdc++.so.6
#3 0x00007ffff7c5e47c in ?? () from /usr/lib/x86_64-linux-gnu/libstdc++.so.6
#4 0x00007ffff7c5e4e7 in std::terminate() () from /usr/lib/x86_64-linux-gnu/libstdc++.so.6
#5 0x00007ffff7c5e799 in __cxa_throw () from /usr/lib/x86_64-linux-gnu/libstdc++.so.6
#6 0x00007ffff7c553eb in ?? () from /usr/lib/x86_64-linux-gnu/libstdc++.so.6
#7 0x000055555555936c in std::vector<int, std::allocator<int> >::_M_range_check (
this=0x5555555cfdb0, __n=100) at /usr/include/c++/9/bits/stl_vector.h:1070
#8 0x0000555555558e1d in std::vector<int, std::allocator<int> >::at (this=0x5555555cfdb0,
__n=100) at /usr/include/c++/9/bits/stl_vector.h:1091
#9 0x000055555555828b in GDBTester::VectorCrash (this=0x5555555cfb40)
at /home/steve/Documents/nav2_ws/src/gdb_test_pkg/src/gdb_test_node.cpp:44
#10 0x0000555555559cfc in main (argc=1, argv=0x7fffffffc108)
at /home/steve/Documents/nav2_ws/src/gdb_test_pkg/src/main.cpp:25
在此示例中,您应该按照以下方式从底部开始阅读:
在主函数中,第 25 行我们调用函数 VectorCrash。
在 VectorCrash 中,第 44 行,我们在输入“100”的 Vector 的“at()”方法中崩溃了。
由于范围检查失败引发异常后,它在 STL 矢量第 1091 行的“at()”中崩溃。
这些跟踪需要一些时间来习惯阅读,但一般来说,从底部开始,沿着堆栈向上跟踪,直到看到它崩溃的行。 然后你就可以推断出它崩溃的原因。 当您完成 GDB 操作后,输入“quit”,它将退出会话并终止所有仍在运行的进程。 它可能会问你是否想在最后杀死一些线程,说是。
从启动文件
就像我们的非 ROS 示例一样,我们需要在启动 ROS 2 启动文件之前设置 GDB 会话。 虽然我们可以通过命令行进行设置,但我们可以使用与“ros2 run”节点示例中相同的机制,现在使用启动文件。
在启动文件中,找到您感兴趣的调试节点。
对于本节,我们假设您的启动文件仅包含一个节点(还可能包含其他信息)。
“launch_ros”包中使用的“Node”函数将接受一个字段“prefix”,该字段采用前缀参数列表。
我们将在此处插入 GDB 片段,并对我们的节点示例进行一项更改,即使用“xterm”。
xterm
将弹出一个新的终端窗口来显示 GDB 并与之交互。
我们这样做是因为在启动文件上处理“stdin”时出现问题(例如,如果您按 control+C,您是在与 GDB 还是启动对话?)。
有关更多信息,请参阅“此票证 <https://github.com/ros2/launch_ros/issues/165>”。
请参阅下面的调试 SLAM Toolbox 示例。
start_sync_slam_toolbox_node = Node(
parameters=[
get_package_share_directory("slam_toolbox") + '/config/mapper_params_online_sync.yaml',
{'use_sim_time': use_sim_time}
],
package='slam_toolbox',
executable='sync_slam_toolbox_node',
name='slam_toolbox',
prefix=['xterm -e gdb -ex run --args'],
output='screen')
和以前一样,这个前缀将启动一个 GDB 会话,现在在“xterm”中,并运行您请求的启动文件以及定义的所有附加启动参数。
一旦您的服务器崩溃,您将在“xterm”会话中看到如下所示的提示。此时您现在可以获得回溯。
(gdb)
在此会话中,输入“backtrace”,它将为您提供回溯。 根据您的需要复制此内容。 有关示例,请参阅上面部分中的示例跟踪。
这些跟踪需要一些时间来习惯阅读,但一般来说,从底部开始,沿着堆栈向上跟踪,直到看到它崩溃的行。
然后你就可以推断出它崩溃的原因。
当您完成 GDB 操作后,输入 quit
,它将退出会话并终止所有仍在运行的进程。
它可能会问你是否想在最后杀死一些线程,说是。
来自大型项目
使用多个节点的启动文件有点不同,因此您可以与 GDB 会话进行交互,而不会被同一终端中的其他日志记录所困扰。 因此,在处理较大的启动文件时,最好取出您感兴趣的特定服务器并单独启动它。 这些说明针对 Nav2,但适用于在一系列启动文件中具有任何类型的许多节点的任何大型项目。
因此,对于这种情况,当您发现想要调查的崩溃时,将此服务器与其他服务器分开是有益的。
如果您感兴趣的服务器是从嵌套启动文件(例如包含的启动文件)启动的,您可能需要执行以下操作:
注释掉父启动文件中包含的启动文件
使用调试符号的“-g”标志重新编译感兴趣的包
在终端中启动父启动文件
按照“从启动文件”中的说明在另一个终端中启动服务器的启动文件。
或者,如果您感兴趣的服务器直接在这些文件中启动(例如,您看到“Node”、“LifecycleNode”或“ComponentContainer”内部),则需要将其与其他服务器分开:
从父启动文件中注释掉节点的包含内容
使用调试符号的“-g”标志重新编译感兴趣的包
在终端中启动父启动文件
按照“从节点”中的说明在另一个终端中启动服务器的节点。
请注意,在这种情况下,您可能需要重新映射或向此节点提供参数文件(如果之前由启动文件提供)。使用“–ros-args”你可以给它新参数文件、重映射或名称的路径。有关所需的命令行参数,请参阅“此 ROS 2 教程 <https://docs.ros.org/en/rolling/Guides/Node-arguments.html>”。
我们知道这可能很痛苦,因此它可能会鼓励您将每个节点作为单独包含的启动文件以使调试更容易。一组示例参数可能是``–ros-args -r __node:=<node_name> –params-file /absolute/path/to/params.yaml``(作为模板)。
一旦您的服务器崩溃,您将在特定服务器的终端中看到如下提示。此时您现在可以获得回溯。
(gdb)
在此会话中,输入“backtrace”,它将为您提供回溯。 根据您的需要复制此内容。 有关示例,请参阅上面部分中的示例跟踪。
这些跟踪需要一些时间来习惯阅读,但一般来说,从底部开始,沿着堆栈向上跟踪,直到看到它崩溃的行。 然后你就可以推断出它崩溃的原因。 当您完成 GDB 操作后,输入“quit”,它将退出会话并终止所有仍在运行的进程。 它可能会问你是否想在最后杀死一些线程,说是。
来自 Nav2 启动
要直接从 nav2 Bringup 启动文件进行调试,您可能需要执行以下操作:
将``prefix=[‘xterm -e gdb -ex run –args’]`` 添加到相应启动文件中的非组合节点。
使用调试符号的“-g”标志重新编译感兴趣的包。
使用“ros2 launch nav2_bringup tb3_simulation_launch.py use_composition:=False”正常启动。将打开一个单独的 xterm 窗口,其中感兴趣的进程在 gdb 中运行。
关闭合成会对性能产生严重影响。如果这对您很重要,请遵循“来自大型项目”。
一旦您的服务器崩溃,您将在 xterm 窗口中看到如下所示的提示。此时您现在可以获得回溯。
(gdb)
在此会话中,输入“backtrace”,它将为您提供回溯。 根据您的需要复制此内容。 有关示例,请参阅上面部分中的示例跟踪。
这些跟踪需要一些时间来习惯阅读,但一般来说,从底部开始,沿着堆栈向上跟踪,直到看到它崩溃的行。 然后你就可以推断出它崩溃的原因。 当您完成 GDB 操作后,输入“quit”,它将退出会话并终止所有仍在运行的进程。 它可能会问你是否想在最后杀死一些线程,说是。
崩溃时自动回溯
backward-cpp 库提供了漂亮的堆栈跟踪,而 backward_ros 包装器简化了其集成。
只需将其添加为依赖项并将其“find_package”添加到您的 CMakeLists 中,向后库将被注入到您的所有可执行文件和库中。