控制台日志记录#
ROS 2 日志记录是了解和调试 ROS 节点的强大工具.
本页重点介绍如何在 Autoware 中设计控制台日志记录,并展示几个实际示例. 要全面了解 ROS 2 日志记录的工作原理,请参阅 日志记录文档.
在 Autoware 中记录用例#
- 开发人员通过查看控制台日志来调试代码.
- 车辆作员根据控制台日志采取适当的风险规避措施.
- 日志分析师对 rosbag 文件中记录的控制台日志进行分析.
为了有效地支持这些使用案例,需要干净且高度可见的日志. 为此,下面定义了几条规则.
规则#
选择适当的严重性级别(必需、非自动化)#
理由#
如果严重性级别不合适,则令人困惑,如下所示:
- 无用的消息被标记为
FATAL. - 非常重要的错误消息被标记为
INFO.
示例#
使用以下标准作为参考:
- DEBUG: 使用此级别为开发人员显示调试信息.请注意,默认情况下,具有此级别的日志是隐藏的.
- INFO: 使用此级别可向作员通知事件(初始化期间的循环通知、状态更改、服务响应等).
- 当节点可以继续正常工作,但可能会发生意外行为时,请使用此级别.
- 例如,
路径优化失败,但可以使用之前的数据、定位(Localization)分数较低等.
- 例如,
- 错误: 当节点无法继续正常工作,并且会发生意外行为时,请使用此级别.
- 例如,
路径优化失败,路径为空、车辆将触发紧急停止等.
- 例如,
- 致命: 当整个系统无法继续正常工作,并且必须停止系统时,请使用此级别.
- 例如,
车辆控制 ECU 没有响应、系统存储崩溃等.
- 例如,
通过设置日志记录选项过滤掉不必要的日志(必需,非自动化)#
理由#
某些第三方节点(如驱动程序)可能不遵循 Autoware 的准则. 如果日志有干扰,则应过滤掉不必要的日志.
示例#
使用 --log-level {level} 选项更改要显示的最低日志级别:
<launch>
<!-- This outputs only FATAL level logs. -->
<node pkg="demo_nodes_cpp" exec="talker" ros_args="--log-level fatal" />
</launch>
如果您只想禁用特定的输出目标,请使用 --disable-stdout-logs、--disable-rosout-logs 和/或 --disable-external-lib-logs 选项:
<launch>
<!-- This outputs to rosout and disk. -->
<node pkg="demo_nodes_cpp" exec="talker" ros_args="--disable-stdout-logs" />
</launch>
<launch>
<!-- This outputs to stdout. -->
<node pkg="demo_nodes_cpp" exec="talker" ros_args="--disable-rosout-logs --disable-external-lib-logs" />
</launch>
当日志不必要地重复显示时使用 throttled logging(必需,非自动化)#
理由#
如果控制台上显示大量日志,则用户会错过重要消息.
示例#
在等待某些消息时,受限制的日志通常就足够了. 在这种情况下,请等待大约 5 秒作为参考值.
// Compliant
void FooNode::on_timer() {
if (!current_pose_) {
RCLCPP_ERROR_THROTTLE(get_logger(), *get_clock(), 5000, "Waiting for current_pose_.");
return;
}
}
// Non-compliant
void FooNode::on_timer() {
if (!current_pose_) {
RCLCPP_ERROR(get_logger(), "Waiting for current_pose_.");
return;
}
}
异常#
以下情况是可以接受的,即使它没有受到限制.
- 这条信息真的值得每次都显示.
- 消息级别为 DEBUG.
不要依赖核心库类中的 rclcpp::Node,而只依赖 rclcpp/logging.hpp (咨询性,非自动化)#
理由#
核心库类包含可重用的算法,也可用于非 ROS 平台. 将库移植到其他平台时,首选较少的依赖项.
示例#
// Compliant
#include <rclcpp/logging.hpp>
class FooCore {
public:
explicit FooCore(const rclcpp::Logger & logger) : logger_(logger) {}
void process() {
RCLCPP_INFO(logger_, "message");
}
private:
rclcpp::Logger logger_;
};
// Compliant
// Note that logs aren`t published to `/rosout` if the logger name is different from the node name.
#include <rclcpp/logging.hpp>
class FooCore {
void process() {
RCLCPP_INFO(rclcpp::get_logger("foo_core_logger"), "message");
}
};
// Non-compliant
#include <rclcpp/node.hpp>
class FooCore {
public:
explicit FooCore(const rclcpp::NodeOptions & node_options) : node_("foo_core_node", node_options) {}
void process() {
RCLCPP_INFO(node_.get_logger(), "message");
}
private:
rclcpp::Node node_;
};
小贴士#
使用 rqt_console 过滤日志#
要过滤日志,使用 rqt_console 很有用:
ros2 run rqt_console rqt_console
有关更多详细信息,请参阅 ROS 2 文档.
有用的 marco 表达式#
要调试程序,有时需要查看执行了哪些函数和代码行.
在这种情况下,您可以使用 __FILE__、__LINE__ 和 __FUNCTION__ 宏:
void FooNode::on_timer() {
RCLCPP_DEBUG(get_logger(), "file: %s, line: %s, function: %s" __FILE__, __LINE__, __FUNCTION__);
}
示例输出如下:
[DEBUG] [1671720414.395456931] [foo]: file: /path/to/file.cpp, line: 100, function: on_timer