cartographer参数读取过程上
Kong Liangqian Lv6

配置参数对于用户来说是十分重要的,本文简单介绍lua参数在代码中的参数运行流程

打开node_main.cc,在这里关于参数配置的内容有

1
2
3
4
5
6
7
8
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);

NodeOption和TrajectoryOptions都是两个定义了参数的结构体

1
2
3
4
5
6
7
8
9
10
11
struct NodeOptions {
::cartographer::mapping::proto::MapBuilderOptions map_builder_options;
std::string map_frame;
double lookup_transform_timeout_sec;
double submap_publish_period_sec;
double pose_publish_period_sec;
double trajectory_publish_period_sec;
bool publish_to_tf = true;
bool publish_tracked_pose = false;
bool use_pose_extrapolator = true; //是否使用位姿推测器
};
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
// 一条轨迹的基础参数配置
struct TrajectoryOptions {
::cartographer::mapping::proto::TrajectoryBuilderOptions
trajectory_builder_options;
std::string tracking_frame;
std::string published_frame;
std::string odom_frame;
bool provide_odom_frame;
bool use_odometry;
bool use_nav_sat;
bool use_landmarks;
bool publish_frame_projected_to_2d;
int num_laser_scans;
int num_multi_echo_laser_scans;
int num_subdivisions_per_laser_scan;
int num_point_clouds;
double rangefinder_sampling_ratio;
double odometry_sampling_ratio;
double fixed_frame_pose_sampling_ratio;
double imu_sampling_ratio;
double landmarks_sampling_ratio;
};

这两个option参数对应在最外层的lua文件,对应的内容是

1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
include "map_builder.lua"
include "trajectory_builder.lua"

options = {
map_builder = MAP_BUILDER, -- map_builder.lua的配置信息
trajectory_builder = TRAJECTORY_BUILDER, -- trajectory_builder.lua的配置信息

map_frame = "map", -- 地图坐标系的名字
tracking_frame = "imu_link", -- 将所有传感器数据转换到这个坐标系下
published_frame = "odom", -- tf: map -> footprint
odom_frame = "odom", -- 里程计的坐标系名字
provide_odom_frame = false, -- 是否提供odom的tf, 如果为true,则tf树为map->odom->footprint
-- 如果为false tf树为map->footprint
publish_frame_projected_to_2d = false, -- 是否将坐标系投影到平面上
--use_pose_extrapolator = false, -- 发布tf时是使用pose_extrapolator的位姿还是前端计算出来的位姿

use_odometry = true, -- 是否使用里程计,如果使用要求一定要有odom的tf
use_nav_sat = false, -- 是否使用gps
use_landmarks = false, -- 是否使用landmark
num_laser_scans = 0,

通过std::tie来对node_options, trajectory_options两个 变量进行赋值,此时需要查看一下LoadOptions函数,他应该返回两个分别为NodeOptionsTrajectoryOptions的一个tuple。因为tie只接受来自tuple的赋值

在这里,点开LoadOptions,其返回值为std::tuple,注意return,是通过make_tuple生成的tuple

1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
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));
}

代码前面三段可以理解为生成一个lua参数的一个字典,然后把这个字典lua_parameter_dictionary转换为两个Options,

通过CreateNodeOptions和CreateTrajectoryOptions创建出NodeOptions和TrajectoryOptions。

CreateNodeOptions定义在node_options.h文件中,他返回一个NodeOptions,传入的是一个字典

1
2
NodeOptions CreateNodeOptions(
::cartographer::common::LuaParameterDictionary* lua_parameter_dictionary);

实现则在node_option.cpp

1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
NodeOptions CreateNodeOptions(
::cartographer::common::LuaParameterDictionary* const
lua_parameter_dictionary) {

NodeOptions options;

// 根据lua字典中的参数, 生成protobuf的序列化数据结构 proto::MapBuilderOptions
options.map_builder_options =
::cartographer::mapping::CreateMapBuilderOptions(
lua_parameter_dictionary->GetDictionary("map_builder").get());

options.map_frame = lua_parameter_dictionary->GetString("map_frame");
options.lookup_transform_timeout_sec =
lua_parameter_dictionary->GetDouble("lookup_transform_timeout_sec");
options.submap_publish_period_sec =
lua_parameter_dictionary->GetDouble("submap_publish_period_sec");
options.pose_publish_period_sec =
lua_parameter_dictionary->GetDouble("pose_publish_period_sec");
options.trajectory_publish_period_sec =
lua_parameter_dictionary->GetDouble("trajectory_publish_period_sec");
if (lua_parameter_dictionary->HasKey("publish_to_tf")) {
options.publish_to_tf =
lua_parameter_dictionary->GetBool("publish_to_tf");
}
if (lua_parameter_dictionary->HasKey("publish_tracked_pose")) {
options.publish_tracked_pose =
lua_parameter_dictionary->GetBool("publish_tracked_pose");
}
if (lua_parameter_dictionary->HasKey("use_pose_extrapolator")) {
options.use_pose_extrapolator =
lua_parameter_dictionary->GetBool("use_pose_extrapolator");
}
return options;
}

内容即为对NodeOptions对象进行赋值,因为publish_to_tf等三个参数是有默认值的,所以lua配置文件里面,及时没有他们也没有关系。如果if语句false也没有关系。

CreateTrajectoryOptions和CreateNodeOptions一样。

 Comments