Cartogragper源码阅读
今后会对Cartogragper源码进行学习和记录
node_main.cc
一、知识储备
1.gflag
Gflags简明教程
GFlags使用文档
GFlags是Google开源的一套命令行参数处理的开源库,包括C++的版本和python 版本。
和 getopt() 之类的库不同,flag的定义可以散布在各个源码中,而不用放在一起。一个源码文件可以定义一些它自己的flag,链接了该文件的应用都能使用这些flag。这样就能非常方便地复用代码。如果不同的文件定义了相同的flag,链接时会报错。
例:
fgrep -l -f ./test ccc jjj
-l 与 -f 是命令行标记, 而 ccc 与 jjj 是命令行参数, 因为这两者不是以 - 开头的.
-l 是一个不带参数的标记, -f 是一个带了参数 ./test 的标记, 而gflags可以解析这
些标记以及参数并将其存储在某些数据结构中.
具体用法见gFlags使用指南
2.glog
Google glog是一个应用级别的日志系统库.它提供基于C++风格的流和各种辅助宏的日志API.
具体用法见glog使用指南
二、node_main.cc
DEFINE_bool在gflags.h中定义
- gflags主要支持的参数类型包括bool, int32, int64, uint64, double, string等
- 定义参数通过DEFINE_type宏实现, 该宏的三个参数含义分别为命令行参数名, 参数默认值, 以及参数的帮助信息
- 当参数被定义后, 通过FLAGS_name就可访问到对应的参数
DEFINE_bool(collect_metrics, false,
"Activates the collection of runtime metrics. If activated, the "
"metrics can be accessed via a ROS service.");
//configuration_directory在lx_rs16_2d_outdoor.launch文件内
DEFINE_string(configuration_directory, "",
"First directory in which configuration files are searched, "
"second is always the Cartographer installation to allow "
"including files from there.");
DEFINE_string(configuration_basename, "",
"Basename, i.e. not containing any directory prefix, of the "
"configuration file.");
DEFINE_string(load_state_filename, "",
"If non-empty, filename of a .pbstream file to load, containing "
"a saved SLAM state.");
DEFINE_bool(load_frozen_state, true,
"Load the saved state as frozen (non-optimized) trajectories.");
DEFINE_bool(
start_trajectory_with_default_topics, true,
"Enable to immediately start the first trajectory with default topics.");
DEFINE_string(
save_state_filename, "",
"If non-empty, serialize state and write it to disk before shutting down.");
首先关注collect_metrics,它后来出现在:
Node node(node_options, std::move(map_builder), &tf_buffer,
FLAGS_collect_metrics);
其次,configuration_directory、configuration_basename出现在lx_rs16_2d_outdoor.launch文件中,
<node name="cartographer_node" pkg="cartographer_ros"
type="cartographer_node" args="
-configuration_directory $(find cartographer_ros)/configuration_files
-configuration_basename lx_rs16_2d_outdoor.lua"
2.main函数
int main(int argc, char** argv) {
// note: 初始化glog库
google::InitGoogleLogging(argv[0]);
// 使用gflags进行参数的初始化. 其中第三个参数为remove_flag
// 如果为true, gflags会移除parse过的参数, 否则gflags就会保留这些参数, 但可能会对参数顺序进行调整.
google::ParseCommandLineFlags(&argc, &argv, true);
/**
* @brief glog里提供的CHECK系列的宏, 检测某个表达式是否为真
* 检测expression如果不为真, 则打印后面的description和栈上的信息
* 然后退出程序, 出错后的处理过程和FATAL比较像.
*/
CHECK(!FLAGS_configuration_directory.empty())
<< "-configuration_directory is missing.";
CHECK(!FLAGS_configuration_basename.empty())
<< "-configuration_basename is missing.";
// ros节点的初始化
::ros::init(argc, argv, "cartographer_node");
// 一般不需要在自己的代码中显式调用
// 但是若想在创建任何NodeHandle实例之前启动ROS相关的线程, 网络等, 可以显式调用该函数.
::ros::start();
// 使用ROS_INFO进行glog消息的输出
cartographer_ros::ScopedRosLogSink ros_log_sink;
// 开始运行cartographer_ros
cartographer_ros::Run();
// 结束ROS相关的线程, 网络等
::ros::shutdown();
}
3. Run函数
namespace cartographer_ros {
namespace {
void Run() {
constexpr double kTfBufferCacheTimeInSeconds = 10.;//缓存时间
tf2_ros::Buffer tf_buffer{::ros::Duration(kTfBufferCacheTimeInSeconds)};
// 开启监听tf的独立线程
tf2_ros::TransformListener tf(tf_buffer);
ROS时间概念总结
使用tf2消息的大部分工作通过tf2_ros::Buffer类完成,其通过tf2_ros::TransformListener完成对tf2_ros::Buffer类的初始化和构造,并订阅相应tf消息,后续操作都是用的tf2_ros::Buffer类的成员函数完成:ROS之tf2坐标转换包
- 该段代码前面部分都是在定义一些变量类型,通过调用LoadOptions函数读取目录下的配置文件,将一些参数赋给node_options, trajectory_options:
NodeOptions node_options;
TrajectoryOptions trajectory_options;
// c++11: std::tie()函数可以将变量连接到一个给定的tuple上,生成一个元素类型全是引用的tuple
// 根据Lua配置文件中的内容, 为node_options, trajectory_options 赋值
std::tie(node_options, trajectory_options) =
LoadOptions(FLAGS_configuration_directory, FLAGS_configuration_basename);
3.1 LoadOptions()解析:
进入node_options.cc中看LoadOptions()的定义*
* @param[in] configuration_directory 配置文件所在目录
* @param[in] configuration_basename 配置文件的名字
* @return std::tuple<NodeOptions, TrajectoryOptions> 返回节点的配置与轨迹的配置
*/
std::tuple<NodeOptions, TrajectoryOptions> LoadOptions(
const std::string& configuration_directory,
const std::string& configuration_basename) {
LoadOptions()可以自行了解NodeOptions, TrajectoryOption两个结构体的定义它们的参数都是在lua文件中体现
// 获取配置文件所在的目录
auto file_resolver =
absl::make_unique<cartographer::common::ConfigurationFileResolver>(
std::vector<std::string>{configuration_directory});//{}configuration_directory初始化后放入vector
ConfigurationFileResolver的定义继承于FileResolver
class ConfigurationFileResolver : public FileResolver {
public:
// c++11: explicit关键字 的作用就是防止类构造函数的隐式自动转换
explicit ConfigurationFileResolver(
const std::vector<std::string>& configuration_files_directories);
std::string GetFullPathOrDie(const std::string& basename) override;
std::string GetFileContentOrDie(const std::string& basename) override;
private:
std::vector<std::string> configuration_files_directories_;
};
进入ConfigurationFileResolver()定义,可以看到它的参数来源于configuration_files_directories以及kConfigurationFilesDirectory
ConfigurationFileResolver::ConfigurationFileResolver(
const std::vector<std::string>& configuration_files_directories)
: configuration_files_directories_(configuration_files_directories) {
configuration_files_directories_.push_back(kConfigurationFilesDirectory);
// 读取配置文件内容到code中
const std::string code =
file_resolver->GetFileContentOrDie(configuration_basename);
查看GetFileContentOrDie()定义:
std::string ConfigurationFileResolver::GetFileContentOrDie(
const std::string& basename) {
CHECK(!basename.empty()) << "File basename cannot be empty." << basename;
// 根据文件名查找是否在给定文件夹中存在
const std::string filename = GetFullPathOrDie(basename);
std::ifstream stream(filename.c_str());
// 读取配置文件内容并返回
return std::string((std::istreambuf_iterator<char>(stream)),
std::istreambuf_iterator<char>());
根据给定的字符串, 生成一个lua字典
cartographer::common::LuaParameterDictionary lua_parameter_dictionary(
code, std::move(file_resolver));
需要去lua_parameter_dictionary.cc里去看
创建元组tuple,元组定义了一个有固定数目元素的容器, 其中的每个元素类型都可以不相同
将配置文件的内容填充进NodeOptions与TrajectoryOptions, 并返回
return std::make_tuple(CreateNodeOptions(&lua_parameter_dictionary),
CreateTrajectoryOptions(&lua_parameter_dictionary));
自行看CreateNodeOptions、 CreateTrajectoryOptions函数
返回到node_main.cc中,进入map_builder.h和.cc中分别可以看到:
std::unique_ptr<MapBuilderInterface> CreateMapBuilder(
const proto::MapBuilderOptions& options) {
return absl::make_unique<MapBuilder>(options);
这里需要解释一下std::unique_ptr的定义,std::unique_ptr 是 C++11 起引入的智能指针。
std:make_unique<unique_ptr>作用是创建并返回unique_ptr至指定类型的对象,该对象是使用指定的参数构造的。比如本句中使用的参数就node_options.map_builder_options, 指定的返回类型就是cartographer::mapping::MapBuilder.
- 定义node
// c++11: std::move 是将对象的状态或者所有权从一个对象转移到另一个对象,
// 只是转移, 没有内存的搬迁或者内存拷贝所以可以提高利用效率,改善性能..
// 右值引用是用来支持转移语义的.转移语义可以将资源 ( 堆, 系统对象等 ) 从一个对象转移到另一个对象,
// 这样能够减少不必要的临时对象的创建、拷贝以及销毁, 能够大幅度提高 C++ 应用程序的性能.
// 临时对象的维护 ( 创建和销毁 ) 对性能有严重影响.
Node node(node_options, std::move(map_builder), &tf_buffer,
FLAGS_collect_metrics);
深入到node里,下次补充
- 剩余部分
// 如果加载了pbstream文件, 就执行这个函数
if (!FLAGS_load_state_filename.empty()) {
node.LoadState(FLAGS_load_state_filename, FLAGS_load_frozen_state);
}
// 使用默认topic 开始轨迹
if (FLAGS_start_trajectory_with_default_topics) {
node.StartTrajectoryWithDefaultTopics(trajectory_options);
}
::ros::spin();
// 结束所有处于活动状态的轨迹
node.FinishAllTrajectories();
// 当所有的轨迹结束时, 再执行一次全局优化
node.RunFinalOptimization();
// 如果save_state_filename非空, 就保存pbstream文件
if (!FLAGS_save_state_filename.empty()) {
node.SerializeState(FLAGS_save_state_filename,
true /* include_unfinished_submaps */);
}
总结
后续还需要对这里的内容进行进一步的总结,主要包括lua字典部分。