从零开始学习cartographer源码之gflags与glog
gflags
gflags简介
gflags(Google Flags)是一个用于处理命令行标志的库,主要由Google开发,广泛应用于C++和Python项目中。它提供了一种简洁而强大的方式来定义、解析和使用命令行标志(flags)。
gflags主要作用
- 定义命令行标志:可以方便地定义各种类型的命令行标志,包括布尔值、整数、字符串等。
- 解析命令行标志:自动解析命令行参数,并将它们转换为相应的类型。
- 生成帮助信息:自动生成包含所有定义标志的帮助信息,帮助用户了解可用的命令行参数。
- 默认值和验证:支持为标志设置默认值和进行简单的验证,确保参数的有效性。
gflags在cartographer中的用法
库文件位置:\wsl.localhost\Ubuntu-18.04\usr\local\include\gflags\gflags.h(wsl内地址)
以node_main.cc为例
文件位置:src/cartographer_ros/cartographer_ros/cartographer_ros/node_main.cc
初始化flag
我们可以通过给可执行文件传输命令行参数来修改flag的默认值,只需要在main函数开头,对flag进行初始化google::ParseCommandLineFlags(&argc, &argv, true);
DEFINE有三个宏,其意义分别为:flag的名称,flag的默认值,help字符串。 gflags支持的变量类型如下:
DEFINE_bool: 布尔类型
DEFINE_int32: 32-bit 整型
DEFINE_int64: 64-bit 整型
DEFINE_uint64: 无符号 64-bit 整型
DEFINE_double: double
DEFINE_string: C++ string/* 名称: collect_metrics 默认值: false 描述: 如果激活,则收集运行时指标,并通过ROS服务访问这些指标。 */ DEFINE_bool(collect_metrics, false, "Activates the collection of runtime metrics. If activated, the " "metrics can be accessed via a ROS service."); /* 名称: configuration_directory 默认值: 空字符串 "" 描述: 配置文件搜索的第一个目录,第二个始终是Cartographer安装目录,以允许从那里包含文件。 */ DEFINE_string(configuration_directory, "", "First directory in which configuration files are searched, " "second is always the Cartographer installation to allow " "including files from there."); /* 名称: configuration_basename 默认值: 空字符串 "" 描述: 配置文件的基本名称,不包含任何目录前缀。 */ DEFINE_string(configuration_basename, "", "Basename, i.e. not containing any directory prefix, of the " "configuration file."); /* 名称: load_state_filename 默认值: 空字符串 "" 描述: 如果非空,则是要加载的.pbstream文件的文件名,其中包含保存的SLAM状态。 */ DEFINE_string(load_state_filename, "", "If non-empty, filename of a .pbstream file to load, containing " "a saved SLAM state."); /* 名称: load_frozen_state 默认值: true 描述: 加载保存的状态为冻结(非优化)的轨迹。 */ DEFINE_bool(load_frozen_state, true, "Load the saved state as frozen (non-optimized) trajectories."); /* 名称: start_trajectory_with_default_topics 默认值: true 描述: 启用后立即使用默认主题启动第一个轨迹。 */ DEFINE_bool( start_trajectory_with_default_topics, true, "Enable to immediately start the first trajectory with default topics."); /* 名称: save_state_filename 默认值: 空字符串 "" 描述: 如果非空,在关闭之前序列化状态并写入磁盘的文件名。 */ DEFINE_string( save_state_filename, "", "If non-empty, serialize state and write it to disk before shutting down.");
cartographer_node节点通常使用launch启动,以backpack_2d.launch为例
- 文件位置:src/cartographer_ros/cartographer_ros/launch/backpack_2d.launch
- 通过launch将configuration_director和configuration_basename两个参数通过launch传递给节点,未传递的其他变量均以默认值启动
<launch> <!-- 找到cartographer_ros功能包,读取backpack_2d.urdf --> <param name="robot_description" textfile="$(find cartographer_ros)/urdf/backpack_2d.urdf" /> <node name="robot_state_publisher" pkg="robot_state_publisher" type="robot_state_publisher" /> <!-- 启动节点,通过命令行将configuration_director和configuration_basename传递给节点 --> <node name="cartographer_node" pkg="cartographer_ros" type="cartographer_node" args=" -configuration_directory $(find cartographer_ros)/configuration_files -configuration_basename backpack_2d.lua" output="screen"> <remap from="echoes" to="horizontal_laser_2d" /> </node> <node name="cartographer_occupancy_grid_node" pkg="cartographer_ros" type="cartographer_occupancy_grid_node" args="-resolution 0.05" /> </launch>
glog
glog简介
Google Logging(glog)是一个由Google开发的C++日志库,提供了一种简单而强大的方式来记录程序的运行信息。glog支持四种日志级别(INFO、WARNING、ERROR和FATAL),可以方便地记录各种类型的日志信息。
glog主要作用
日志记录:
- INFO:记录一般信息,如程序启动和停止信息。
- WARNING:记录警告信息,表示可能会导致问题的情况。
- ERROR:记录错误信息,表示已经发生的问题。
- FATAL:记录致命错误信息,表示无法继续执行的问题,并导致程序终止。
条件日志:在特定条件下记录日志,减少不必要的日志记录。
频率控制日志:控制日志记录的频率,如每N次或每秒钟记录一次日志。
自动生成日志文件:按日期或大小自动生成和轮转日志文件,避免单个日志文件过大。
堆栈跟踪:在记录致命错误时,提供堆栈跟踪信息,帮助定位问题。
glog在cartographer中的用法
库文件位置:\wsl.localhost\Ubuntu-18.04\usr\include\glog\logging.h(wsl内地址)
以node_main.cc为例
- 文件位置:src/cartographer_ros/cartographer_ros/cartographer_ros/node_main.cc
- 初始化glog
使用glog之前需要在main函数中对其进行初始化。google::InitGoogleLogging(argv[0]);
- 可以使用glog对gflags传递的参数进行检查,
如果configuration_directory和configuration_basename有一个为空,就结束程序运行并输出logCHECK(!FLAGS_configuration_directory.empty()) << "-configuration_directory is missing."; CHECK(!FLAGS_configuration_basename.empty()) << "-configuration_basename is missing.";
- 在初始化ros之后将glog转化成roslog
cartographer_ros::ScopedRosLogSink ros_log_sink;
- 在文件ros_log_sink.cc中将glog转换成roslog
- 文件位置:\wsl.localhost\Ubuntu-18.04\home\lx\cartograptrer\ori\clion_carto_ws\src\cartographer_ros\cartographer_ros\cartographer_ros\ros_log_sink.cc
#include "cartographer_ros/ros_log_sink.h" #include <chrono> #include <cstring> #include <string> #include <thread> #include "glog/log_severity.h" #include "ros/console.h" namespace cartographer_ros { namespace { const char* GetBasename(const char* filepath) { const char* base = std::strrchr(filepath, '/'); return base ? (base + 1) : filepath; } } // namespace ScopedRosLogSink::ScopedRosLogSink() : will_die_(false) { AddLogSink(this); } ScopedRosLogSink::~ScopedRosLogSink() { RemoveLogSink(this); } void ScopedRosLogSink::send(const ::google::LogSeverity severity, const char* const filename, const char* const base_filename, const int line, const struct std::tm* const tm_time, const char* const message, const size_t message_len) { const std::string message_string = ::google::LogSink::ToString( severity, GetBasename(filename), line, tm_time, message, message_len); switch (severity) { case ::google::GLOG_INFO: ROS_INFO_STREAM(message_string); break; case ::google::GLOG_WARNING: ROS_WARN_STREAM(message_string); break; case ::google::GLOG_ERROR: ROS_ERROR_STREAM(message_string); break; case ::google::GLOG_FATAL: ROS_FATAL_STREAM(message_string); will_die_ = true; break; } } void ScopedRosLogSink::WaitTillSent() { if (will_die_) { // Give ROS some time to actually publish our message. std::this_thread::sleep_for(std::chrono::milliseconds(1000)); } } } // namespace cartographer_ros