一、描述
上篇文章大概论述了下Run()函数的流程,但没有深入了解,下面就其中一段代码作以讲解:
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);
首先定义了两个结构体,然后对这两个结构体进行赋值。其上的 std::tie 是 c++11 新加的函数,作用和 python 比较类似,可以对多个变量同时进行赋值,但是注意,其只能接收 tuple 这个数据类型。有关std::tuple和std::tie的用法可以参考https://blog.youkuaiyun.com/m0_37809890/article/details/89367406
二、NodeOptions与TrajectoryOptions
1. NodeOptions
struct NodeOptions {
//来自于src/cartographer/configuration_files/map_builder.lua
::cartographer::mapping::proto::MapBuilderOptions map_builder_options;
std::string map_frame; //地图名称
double lookup_transform_timeout_sec; //查询tf时的超时时间
double submap_publish_period_sec; //发布submap的时间间隔
double pose_publish_period_sec; //发布pose的时间间隔
double trajectory_publish_period_sec; //发布轨迹的时间间隔
bool publish_to_tf = true; //是否发布tf
bool publish_tracked_pose = false; //是否发布追踪位姿
bool use_pose_extrapolator = true; //发布tf时是使用pose_extrapolator的位姿还是前端计算出来的位姿
};
需要注意的是,最后的三个变量并不是在 .lua 文件中配置的,也就是说其为固定初值,只能通过源码进行修改。
2.TrajectoryOptions
// 一条轨迹的基础参数配置
struct TrajectoryOptions {
//来自于 src/cartographer/configuration_files/trajectory_builder.lua
::cartographer::mapping::proto::TrajectoryBuilderOptions
trajectory_builder_options;
std::string tracking_frame; //由SLAM算法追踪的ROS坐标系ID,如果使用IMU,应该使用其坐标系,通常选择是 “imu_link”
std::string published_frame; //用于发布位姿子坐标系的ROS坐标系ID,例如“odom”坐标系,如果一个“odom”坐标系由系统的不同部分提供,在这种情况下,map_frame中的“odom”姿势将被发布。 否则,将其设置为“base_link”可能是合适的。
std::string odom_frame; //在provide_odom_frame为真才启用,坐标系在published_frame和map_frame之间用于发布局部SLAM结果,通常是“odom”
bool provide_odom_frame; //如果启用,局部,非闭环,持续位姿会作为odom_frame发布在map_frame中发布。
bool use_odometry; //如果启用,订阅关于“odom”话题的nav_msgs/Odometry消息。里程信息会提供,这些信息包含在SLAM里
bool use_nav_sat; //是否使用gps
bool use_landmarks; //是否使用landmark
bool publish_frame_projected_to_2d; //是否将坐标系投影到平面上
int num_laser_scans; //订阅的激光扫描话题数量。在一个激光扫描仪的“scan”话题上订sensor_msgs/LaserScan或在多个激光扫描仪上订阅话题“scan_1”,“scan_2”等。
int num_multi_echo_laser_scans; //订阅的多回波激光扫描主题的数量。在一个激光扫描仪的“echoes”话题上订阅sensor_msgs/MultiEchoLaserScan,或者为多个激光扫描仪订阅话题“echoes_1”,“echoes_2”等。
int num_subdivisions_per_laser_scan; //将每个接收到的(多回波)激光扫描分成的点云数。分扫描可以在扫描仪移动时取消扫描获取的扫描。有一个相应的轨迹构建器选项可将细分扫描累积到将用于扫描匹配的点云中。
int num_point_clouds; //要订阅的点云话题的数量。在一个测距仪的“points2”话题上订阅sensor_msgs/PointCloud2或者为多个测距仪订阅话题“points2_1”,“points2_2”等。
double rangefinder_sampling_ratio; //范围传感器数据的采样频率
double odometry_sampling_ratio; //里程计数据的采样频率
double fixed_frame_pose_sampling_ratio; //GPS数据的采样频率
double imu_sampling_ratio; //imu数据的采样频率
double landmarks_sampling_ratio; //landmarks数据的采样频率
};
三、LoadOptions()
LoadOptions()函数的声明在src/cartographer_ros/cartographer_ros/cartographer_ros/node_options.h中
LoadOptions()函数的定义在
src/cartographer_ros/cartographer_ros/cartographer_ros/node_options.cc中
/**
* @brief 加载lua配置文件中的参数
*
* @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) {
// 获取配置文件所在的目录
auto file_resolver =
absl::make_unique<cartographer::common::ConfigurationFileResolver>(
std::vector<std::string>{configuration_directory});
// 读取配置文件内容到code中
const std::string code =
file_resolver->GetFileContentOrDie(configuration_basename);
// 根据给定的字符串, 生成一个lua字典
cartographer::common::LuaParameterDictionary lua_parameter_dictionary(
code, std::move(file_resolver));
// 创建元组tuple,元组定义了一个有固定数目元素的容器, 其中的每个元素类型都可以不相同
// 将配置文件的内容填充进NodeOptions与TrajectoryOptions, 并返回
return std::make_tuple(CreateNodeOptions(&lua_parameter_dictionary),
CreateTrajectoryOptions(&lua_parameter_dictionary));
}
1.首先函数中的
configuration_directory是字符串$(find cartographer_ros)/configuration_files
configuration_basename是字符串test01.lua
显然,它们是我们建图时的参数配置文件,该函数返回的NodeOptions和TrajectoryOptions其实就是两个struct,分别声明在node_options.h和trajectory_options.h中。
构建一个 cartographer::common::ConfigurationFileResolver 类指针对象 file_resolver,对他的私有成员 configuration_files_directories_进行赋值,它的类型为std::vector<std::string>,初始化赋值的时候,其存储了两个元素,如下:
//配置文件的目录,本人如下:
configuration_directory = "/home/lxy/carto_ws/cartographer_detailed_comments_ws/install_isolated/share/cartographer_ros/configuration_files"
//本人的如下,每个人的不一样,其是在编译的时候自动生成的
constexpr char kConfigurationFilesDirectory[] = "/home/lxy/carto_ws/cartographer_detailed_comments_ws/install_isolated/share/cartographer/configuration_files";
2. 在创建的时候,已经指定了配置文件的所在的目录。只需把配置文件名 configuration_basename 传入到 file_resolver->GetFileContentOrDie() 函数即可获得配置文件中的内容。
3.调用初始化一个 cartographer::common::LuaParameterDictionary 字典(对象),对配置文件中的 code 进行解析。关于配置文件的信息基本都在这个参数字典之中。
4.构建一个元组返回,元组存储两个类型分别 NodeOptions 与 TrajectoryOptions 类型的元素。这两个元素使用过 CreateNodeOptions(&lua_parameter_dictionary) 与 CreateTrajectoryOptions(&lua_parameter_dictionary) 函数构建的。
结语:
这篇博客以及上一篇博客,可以了解到,在 node_main.cc 中的 Run 函数中,其会调用 LoadOptions() 函数,获得 node_options,trajectory_options 两个结构体对象,其主要存储了 .lua 文件中的配置信息,node_options,trajectory_options 主要作用如下:
// Node类的初始化, 将ROS的topic传入SLAM, 也就是MapBuilder
Node node(node_options, std::move(map_builder), &tf_buffer,
FLAGS_collect_metrics);
// 使用默认topic 开始轨迹
if (FLAGS_start_trajectory_with_default_topics) {
node.StartTrajectoryWithDefaultTopics(trajectory_options);
}
下篇文章将对LoadOptions()函数体中的相关函数作一解释。