首页 关于
树枝想去撕裂天空 / 却只戳了几个微小的窟窿 / 它透出天外的光亮 / 人们把它叫做月亮和星星
目录

初始map_builder

通过对cartographer_ros的分析, 我们已经了解到在系统运行之初就构建了一个map_builder对象用于建图。 分析MapBuilderBridge和SensorBridge对象的时候,我们看到cartographer_ros只是用来将ROS系统中各种各样的消息转换之后,喂给Cartographer进行处理,也就是这里所说的map_builder对象。

下面是cartographer_ros构建对象map_builder的语句。可以看到它的数据类型是MapBuilder, 下面让我们先大体的浏览一下这个类的源文件(map_builder.h, map_builder.cc),了解一下它的功能和结构。

    auto map_builder = cartographer::common::make_unique<cartographer::mapping::MapBuilder>(node_options.map_builder_options);

1. MapBuilder类的成员变量

MapBuilder类的定义如下面的代码片段所示,我们省略了其中关于成员函数的声明。 可以看到它继承了一个接口类MapBuilderInterface, 这也就是为什么node对象要使用一个MapBuilderInterface的指针来记录该对象。 这是一种面向接口的编程思想,各个模块对外只对接口负责,至于接口背后的具体实现它并不关心。这样可以一定程度上降低系统的耦合度,如果我们还有别的什么建图算法,可以安静的在一个角落里实现它的核心, 然后按照MapBuilderInterface的定义实现一套接口。那么不修改node对象,我们就可以直接使用新的建图算法了。

        class MapBuilder : public MapBuilderInterface {
            // 省略成员函数的声明
        private:
            const proto::MapBuilderOptions options_;
            common::ThreadPool thread_pool_;
            std::unique_ptr<PoseGraph> pose_graph_;
            std::unique_ptr<sensor::CollatorInterface> sensor_collator_;
            std::vector<std::unique_ptr<mapping::TrajectoryBuilderInterface>> trajectory_builders_;
            std::vector<proto::TrajectoryBuilderOptionsWithSensorIds> all_trajectory_builder_options_;
        };

MapBuilder类的成员变量并不多,只有6个,但它们中的每一个都不简单。其中pose_graph_和trajectory_builders_两个对象是建图的核心逻辑对象, 它们分别用于后台的闭环检测和前台的局部子图构建。

2. 接口类MapBuilderInterface

下面的代码片段是接口类MapBuilderInterface的定义, 它是一个抽象类,需要继承的子类一一实现它所定义的各个抽象函数后,才可以通过子类例化对象。 在该类的一开始先通过using关键字定义了两个类型别名,用来替代原来很长的类型名。

        class MapBuilderInterface {
        public:
            using LocalSlamResultCallback = TrajectoryBuilderInterface::LocalSlamResultCallback;
            using SensorId = TrajectoryBuilderInterface::SensorId;

然后,定义和实现了默认的构造函数和析够函数,同时禁用了拷贝构造函数和赋值运算符。

            MapBuilderInterface() {}
            virtual ~MapBuilderInterface() {}
            MapBuilderInterface(const MapBuilderInterface&) = delete;
            MapBuilderInterface& operator=(const MapBuilderInterface&) = delete;

接口AddTrajectoryBuilder,我们已经在map_builder_bridge_对象中见识过了。 它被用来创建一个新的轨迹跟踪器并返回该跟踪器的索引。这个接口有三个参数,其中expected_sensor_ids中记录了用于建图的所有传感器名称和类型,trajectory_options是新建的轨迹跟踪器的配置, 最后的local_slam_result_callback则是一个回调函数对象,用于响应局部地图构建完成的事件。

            virtual int AddTrajectoryBuilder(const std::set<SensorId>& expected_sensor_ids,
                                             const proto::TrajectoryBuilderOptions& trajectory_options,
                                             LocalSlamResultCallback local_slam_result_callback) = 0;

AddTrajectoryForDeserialization同样也是一个用于新建轨迹跟踪器的接口,只是它的参数只有一个。这个参数处理记录了轨迹跟踪器的配置还包含传感器的配置。 这个参数的数据类型,和接口AddTrajectoryBuilder的参数trajectory_options的数据类型,都是通过protobuf根据proto文件生成的,文件内容很好懂,使用起来有点像C语言中的结构体定义,这里不再具体解释,详细可以参考官方文档

            virtual int AddTrajectoryForDeserialization(
                                             const proto::TrajectoryBuilderOptionsWithSensorIds& options_with_sensor_ids_proto) = 0;

我们可以通过接口GetTrajectoryBuilder获取一个索引为trajectory_id的轨迹跟踪器对象,如果输入的索引不对应一个跟踪器对象则返回空指针nullptr。 这个接口在介绍map_builder_bridge_对象的时候已经多次见到了。

            virtual mapping::TrajectoryBuilderInterface* GetTrajectoryBuilder(int trajectory_id) const = 0;

接口FinishTrajectory用于关闭trajectory_id对应的轨迹跟踪器,该跟踪器将不再响应新的传感器数据。

            virtual void FinishTrajectory(int trajectory_id) = 0;

接口SubmapToProto用于将submap_id所对应的子图信息填充到response中。如果出错将错误信息以字符串的形式返回,若成功运行则返回空字符串。

            virtual std::string SubmapToProto(const SubmapId& submap_id, proto::SubmapQuery::Response* response) = 0;

通过接口SerializeState可以将当前的系统状态转换成一个proto的流,完成序列化。

            virtual void SerializeState(io::ProtoStreamWriterInterface* writer) = 0;

LoadState可以说是SerializeState的逆操作,用于从proto流中加载SLAM状态。

            virtual void LoadState(io::ProtoStreamReaderInterface* reader, bool load_frozen_state) = 0;

最后的这三个接口分别用于获取当前轨迹跟踪器的数量、获取用于实现闭环检测的PoseGraph对象、获取所有的轨迹跟踪器的配置。

            virtual int num_trajectory_builders() const = 0;
            virtual mapping::PoseGraphInterface* pose_graph() = 0;
            virtual const std::vector<proto::TrajectoryBuilderOptionsWithSensorIds>& GetAllTrajectoryBuilderOptions() const = 0;
        };

3. 构造函数

下面是对象map_builder的构造函数的代码片段。在构造map_builder对象的时候,用其成员变量options_保存了配置选项,同时根据配置中关于线程数量的配置完成了线程池thread_pool_的构造。

        MapBuilder::MapBuilder(const proto::MapBuilderOptions& options)
            : options_(options), thread_pool_(options.num_background_threads()) {

接着检查配置项,确保在2D建图和3D建图之间二选一。

            CHECK(options.use_trajectory_builder_2d() ^ options.use_trajectory_builder_3d());

如果是2D建图,那么我们就构建一个PoseGraph2D的对象记录在pose_graph_下。

            if (options.use_trajectory_builder_2d()) {
                pose_graph_ = common::make_unique<PoseGraph2D>(options_.pose_graph_options(),
                              common::make_unique<optimization::OptimizationProblem2D>(options_.pose_graph_options().optimization_problem_options()), &thread_pool_);
            }

类似的,如果是一个3D建图,就构建一个PoseGraph3D的对象。

            if (options.use_trajectory_builder_3d()) {
                pose_graph_ = common::make_unique<PoseGraph3D>(options_.pose_graph_options(),
                              common::make_unique<optimization::OptimizationProblem3D>(options_.pose_graph_options().optimization_problem_options()), &thread_pool_);
            }

最后根据配置项collate_by_trajectory来构建修正器。

            if (options.collate_by_trajectory())
                sensor_collator_ = common::make_unique<sensor::TrajectoryCollator>();
            else
                sensor_collator_ = common::make_unique<sensor::Collator>();
        }

可以看到在构造函数中,我们完成了对options_、thread_pool_、pose_graph_、sensor_collator_的构建工作,而用于建立子图的轨迹跟踪器的对象则需要通过调用接口AddTrajectoryBuilder来完成构建。

4. 配置项浅析

在构造函数中,我们看到map_builder对象在疯狂的通过options获取配置项。那么对于我们的demo而言, 到底使用的是那些配置呢?构建的pose_graph_和sensor_collator_对象是什么呢?下面让我们简单的了解一下。

既然要研究配置文件,我们还是得回到运行demo的launch脚本上。 下面是加载运行cartographer_node的launch脚本的语句,可以看到demo所用的配置文件是backpack_2d.lua

        <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>

下面左侧的代码片段是backpack_2d.lua的内容, 在一开始通过include语句加载了map_builder和trajectory_builder的配置。这两个配置文件是cartographer代码的一部分, 我们可以在其configuration_files子目录中找到。 在代码片段的第8行中,我们可以看到demo所构建的地图是2D的。

下面右侧的代码片段分别是"map_builder.lua"trajectory_builder.lua的文件内容。从中我们可以看到线程数量的配置是4,此外还引入了位姿图(pose_graph)的配置文件pose_graph.lua

        -- backpack_2d.lua
        include "map_builder.lua"
        include "trajectory_builder.lua"

        options = {
            map_builder = MAP_BUILDER,
            trajectory_builder = TRAJECTORY_BUILDER,
            map_frame = "map",
            tracking_frame = "base_link",
            published_frame = "base_link",
            odom_frame = "odom",
            -- 省略了很多
        }

        MAP_BUILDER.use_trajectory_builder_2d = true
        TRAJECTORY_BUILDER_2D.num_accumulated_range_data = 10
        return options
        -- map_builder.lua
        include "pose_graph.lua"
        MAP_BUILDER = {
          use_trajectory_builder_2d = false,
          use_trajectory_builder_3d = false,
          num_background_threads = 4,
          pose_graph = POSE_GRAPH,
        }
        -- trajectory_builder.lua
        include "trajectory_builder_2d.lua"
        include "trajectory_builder_3d.lua"
        TRAJECTORY_BUILDER = {
          trajectory_builder_2d = TRAJECTORY_BUILDER_2D,
          trajectory_builder_3d = TRAJECTORY_BUILDER_3D,
          pure_localization = false,
        }

从lua文件的引用关系中,我们并没有看到collate_by_trajectory的配置。但是在cartographer的子目录"mapping/proto"中有一个文件map_builder_options.proto。这个文件应该是map_builder配置项的定义,其文件内容如下面的代码片段所示。

        syntax = "proto3";
        import "cartographer/mapping/proto/pose_graph_options.proto";
        package cartographer.mapping.proto;
        
        message MapBuilderOptions {
          bool use_trajectory_builder_2d = 1;
          bool use_trajectory_builder_3d = 2;
        
          // Number of threads to use for background computations.
          int32 num_background_threads = 3;
          PoseGraphOptions pose_graph_options = 4;
          // Sort sensor input independently for each trajectory.
          bool collate_by_trajectory = 5;
        }

我们先不去管proto文件的语法,在文件中可以看到字段collate_by_trajectory的定义。也就是说,如果我们想要配置这个选项, 只需要在刚刚分析的lua文件中关于MAP_BUILDER的配置下添加MAP_BUILDER.collate_by_trajectory = true即可。

6. 完

本文中通过对map_builder对象的分析,我们可以看到它用对象pose_graph_在后台完成闭环检测和全局的地图优化,并用trajectory_builders_在前台跟踪运动轨迹完成局部的子图构建。




Copyright @ 高乙超. All Rights Reserved. 京ICP备16033081号-1