Cartographer源码解析(6)——加载配置文件2

前言:

上篇文章主要对LoadOptions() 函数进行了整体上的分析,接下来将对LoadOptions() 函数体内的函数进行细致的分析,其主要的核心都是围绕这 cartographer::common::ConfigurationFileResolver 的类对象 file_resolver 展开,该类的实现于 src/cartographer/cartographer/common/configuration_file_resolver.cc 文件中。其继承自 FileResolver:

// Resolves file paths and file content for the Lua 'read' and 'include'
// functions. Use this to configure where those functions load other files from.
class FileResolver {
 public:
  virtual ~FileResolver() {}
  virtual std::string GetFullPathOrDie(const std::string& basename) = 0;
  virtual std::string GetFileContentOrDie(const std::string& basename) = 0;
};

该类的声明如下:

class ConfigurationFileResolver : public FileResolver {
 public:
  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_;
};

一、构造函数

configuration_file_resolver.h 文件中定义 ConfigurationFileResolver 的构造函数时,使用到了explicit关键字→作用就是防止类构造函数的隐式自动转换。比如在一个构造函数中,其期待传入的数据类型并非 int 类型,而用户误传入了一个 int 10 进去,其就有可能发生隐式转换,比如编译器把 int 10 封装成一个类对象传入。 构造函数的实现如下:

/**
 * @brief Construct a new Configuration File Resolver:: Configuration File Resolver object
 * 
 * @param[in] configuration_files_directories 配置文件目录
 */
ConfigurationFileResolver::ConfigurationFileResolver(
    const std::vector<std::string>& configuration_files_directories)
    : configuration_files_directories_(configuration_files_directories) {
  configuration_files_directories_.push_back(kConfigurationFilesDirectory);
}

这里使用初始化列表的方法将configuration_files_directories(配置文件目录) 直接赋值给 configuration_files_directories_,然后把kConfigurationFilesDirectory 这个变量追加到 configuration_files_directories_ 之中。该变量可以在/home/lxy/carto_ws/cartographer_detailed_comments_ws/build_isolated/cartographer/install/cartographer/common/config.h中找到。

#ifndef CARTOGRAPHER_COMMON_CONFIG_H_
#define CARTOGRAPHER_COMMON_CONFIG_H_

namespace cartographer {
namespace common {

constexpr char kConfigurationFilesDirectory[] =
    "/home/lxy/carto_ws/cartographer_detailed_comments_ws/install_isolated/share/cartographer/configuration_files";
constexpr char kSourceDirectory[] = "/home/lxy/carto_ws/cartographer_detailed_comments_ws/src/cartographer";

}  // namespace common
}  // namespace cartographer

#endif  // CARTOGRAPHER_COMMON_CONFIG_H_

其是一个编译生成的文件,那么其是如何生成的呢?又在哪里配置? 来看

#ifndef CARTOGRAPHER_COMMON_CONFIG_H_
#define CARTOGRAPHER_COMMON_CONFIG_H_

namespace cartographer {
namespace common {

constexpr char kConfigurationFilesDirectory[] =
    "@CARTOGRAPHER_CONFIGURATION_FILES_DIRECTORY@";
constexpr char kSourceDirectory[] = "@PROJECT_SOURCE_DIR@";

}  // namespace common
}  // namespace cartographer

#endif  // CARTOGRAPHER_COMMON_CONFIG_H_

其仅仅配置了两个变量,分别为 kConfigurationFilesDirectory,kSourceDirectory。

二、GetFileContentOrDie 与 GetFullPathOrDie

接下来在看看其他两个成员函数:

ConfigurationFileResolver::GetFileContentOrDie() 与 ConfigurationFileResolver::GetFullPathOrDie()函数:

/**
 * @brief 在所有的配置文件目录中 根据给定配置文件的名字 搜索 配置文件
 * 
 * @param[in] basename 给定配置文件的名字
 * @return std::string 如果搜索成功, 返回配置文件的全路径名
 */
std::string ConfigurationFileResolver::GetFullPathOrDie(
    const std::string& basename) {
  for (const auto& path : configuration_files_directories_) {
    const std::string filename = path + "/" + basename;
    std::ifstream stream(filename.c_str());
    // 只要找到就退出
    if (stream.good()) {
      LOG(INFO) << "Found '" << filename << "' for '" << basename << "'.";
      return filename;
    }
  }
  // 如果找不到配置文件就退出整个程序
  LOG(FATAL) << "File '" << basename << "' was not found.";
}

/**
 * @brief 读取配置文件内容
 * 
 * @param[in] basename 文件名
 * @return std::string 文件内容的数据流
 */
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>());
}

GetFullPathOrDie () 函数中是一个循环,其会对 configuration_files_directories_ 中的所有目录进行查找,查找 basename(.lua) 文件,找到,或者没有找到都会打印相应的信息。最后GetFileContentOrDie() 函数从找到的文件中读出内容返回。


三、LuaParameterDictionary

在将配置文件的内容读取到code之后,还会去根据给定的字符串去生成一个lua字典。

  // 读取配置文件内容到code中
  const std::string code =
      file_resolver->GetFileContentOrDie(configuration_basename);

  // 根据给定的字符串, 生成一个lua字典
  cartographer::common::LuaParameterDictionary lua_parameter_dictionary(
      code, std::move(file_resolver));

LuaParameterDictionary 这个类在src/cartographer/cartographer/common/lua_parameter_dictionary.cc文件中实现,

先来看看它的头文件的包含:

#include <map>
#include <memory>
#include <string>
#include <vector>

#include "cartographer/common/lua.h"
#include "cartographer/common/port.h"
#include "glog/logging.h"

上面的lua.h头文件内容是:

#ifndef CARTOGRAPHER_COMMON_LUA_H_
#define CARTOGRAPHER_COMMON_LUA_H_

// 这个头文件包含了使用lua所需的所有头文件
#include <lua.hpp>

#endif  // CARTOGRAPHER_COMMON_LUA_H_

可以看到LuaParameterDictionary 这个类的实现用到了lua这个标准库,接下来再去看这个LuaParameterDictionary 的构造函数:

/**
 * @brief Construct a new Lua Parameter Dictionary:: Lua Parameter Dictionary object
 * 
 * @param[in] code 配置文件内容
 * @param[in] file_resolver FileResolver类
 */
LuaParameterDictionary::LuaParameterDictionary(
    const std::string& code, std::unique_ptr<FileResolver> file_resolver)
    : LuaParameterDictionary(code, ReferenceCount::YES,
                             std::move(file_resolver)) {}

/**
 * @brief Construct a new Lua Parameter Dictionary:: Lua Parameter Dictionary object
 *        根据给定的字符串, 生成一个lua字典
 * 
 * @param[in] code 配置文件内容
 * @param[in] reference_count 
 * @param[in] file_resolver FileResolver类
 */
LuaParameterDictionary::LuaParameterDictionary(
    const std::string& code, ReferenceCount reference_count,
    std::unique_ptr<FileResolver> file_resolver)
    : L_(luaL_newstate()),
      index_into_reference_table_(-1),
      file_resolver_(std::move(file_resolver)),
      reference_count_(reference_count) {
  CHECK_NOTNULL(L_);
  SetDictionaryInRegistry(L_, this);

  luaL_openlibs(L_);

  lua_register(L_, "choose", LuaChoose);
  // 将LuaInclude注册为Lua的全局函数变量,使得Lua可以调用C函数
  lua_register(L_, "include", LuaInclude);
  lua_register(L_, "read", LuaRead);

  // luaL_loadstring()函数 将一个字符串code加载为 Lua 代码块
  CheckForLuaErrors(L_, luaL_loadstring(L_, code.c_str()));
  CheckForLuaErrors(L_, lua_pcall(L_, 0, 1, 0));
  CheckTableIsAtTopOfStack(L_);
}

可以看到其有两个重载函数,在初始化 LuaParameterDictionary 的时候,传入的为两个参数 code、file_resolver。所以其是调用第一个重载函数,其使用初始化列表对进行初始化的时候,会调用第二个重载函数,多了一个传入的参数为 ReferenceCount::YES。ReferenceCount 是枚举类型: enum class ReferenceCount { YES, NO };enum class是C++11中新增的枚举类,也称作限定作用域枚举类,具体可参考下面这篇文章:https://blog.csdn.net/euxnijuoh/article/details/126929245?utm_medium=distribute.pc_relevant.none-task-blog-2~default~baidujs_baidulandingword~default-1-126929245-blog-109029172.235^v27^pc_relevant_recovery_v2&spm=1001.2101.3001.4242.2&utm_relevant_index=4

lua相关的这个库还是比较复杂的,更多Lua的学习可以参考:

https://www.cnblogs.com/chevin/p/5884657.html

四、LuaParameterDictionary使用

对于lua_parameter_dictionary这个字典会使用即可,使用就是 LoadOptions() 中调用的四句代码。此外,lua_parameter_dictionary.cc文件中也有如下函数:

  std::string GetString(const std::string& key);
  double GetDouble(const std::string& key);
  int GetInt(const std::string& key);
  bool GetBool(const std::string& key);
  int GetNonNegativeInt(const std::string& key);
  std::vector<double> GetArrayValuesAsDoubles();
  ......

都是从 LuaParameterDictionary 字典获取值是使用的,即传入一个 key,返回其对应的 value,同时还会根据调用的函数不同,对数据进行校验。其实我们会配置,更改参数就行了,不用理解得那么细。平常情况下,我们使用 yml 文件就可以了,并没有这么复杂。

结语:

本文对 LoadOptions()这个函数体中的相关函数作了详细的说明,大概了解了Cartographer 是如何加载配置文件的了,再次回到node_main.cc 文件:

// 根据Lua配置文件中的内容, 为node_options, trajectory_options 赋值
  std::tie(node_options, trajectory_options) =
      LoadOptions(FLAGS_configuration_directory, FLAGS_configuration_basename);

  // MapBuilder类是完整的SLAM算法类
  // 包含前端(TrajectoryBuilders,scan to submap) 与
  // 后端(用于查找回环的PoseGraph)
  auto map_builder =
      cartographer::mapping::CreateMapBuilder(node_options.map_builder_options);

  // c++11: std::move 是将对象的状态或者所有权从一个对象转移到另一个对象,
  // 只是转移, 没有内存的搬迁或者内存拷贝所以可以提高利用效率,改善性能..
  // 右值引用是用来支持转移语义的.转移语义可以将资源 ( 堆, 系统对象等 )
  // 从一个对象转移到另一个对象,
  // 这样能够减少不必要的临时对象的创建、拷贝以及销毁, 能够大幅度提高 C++
  // 应用程序的性能. 临时对象的维护 ( 创建和销毁 ) 对性能有严重影响.

  // Node类的初始化, 将ROS的topic传入SLAM, 也就是MapBuilder
  Node node(node_options, std::move(map_builder), &tf_buffer,
            FLAGS_collect_metrics);
下面将围绕CreateMapBuilder这个接口与Node类进行展开。

评论
添加红包

请填写红包祝福语或标题

红包个数最小为10个

红包金额最低5元

当前余额3.43前往充值 >
需支付:10.00
成就一亿技术人!
领取后你会自动成为博主和红包主的粉丝 规则
hope_wisdom
发出的红包
实付
使用余额支付
点击重新获取
扫码支付
钱包余额 0

抵扣说明:

1.余额是钱包充值的虚拟货币,按照1:1的比例进行支付金额的抵扣。
2.余额无法直接购买下载,可以购买VIP、付费专栏及课程。

余额充值