【cartographer without ros】八、使用MapBuilder建图,存储,定位

上一节介绍了在脱离ros环境后,引入和使用Rosbag,并进行传感器数据的读写。
本节就将介绍在自己的工程中,使用cartographer的接口进行功能实现。
事实上,这部分是仿照cartographer_ros进行实现:通过使用MapBuilderInterfaceTrajectoryBuilderInterface实现对应的建图,存储和定位。

目录

1:定义和实现接口指针以及参数文件

2:添加传感器数据

3:建图保存

4:加载地图

5:定位回调


1:定义和实现接口指针以及参数文件

#include "cartographer/mapping/map_builder.h"

std::unique_ptr<MapBuilderInterface> map_builder_;
std::unique_ptr<TrajectoryBuilderInterface> trajectory_builder_;
proto::MapBuilderOptions map_builder_options_;
proto::TrajectoryBuilderOptions trajectory_builder_options_;
int trajectory_id_;

void MyMapBuilder::MyMapBuilder()
{
    const std::string kMapBuilderLua = R"text(
            include "my_map_builder.lua"
            return MAP_BUILDER)text";
    auto map_builder_parameters = cartographer::mapping::slamhelper::ResolveLuaParameters(kMapBuilderLua);
    map_builder_options_ = CreateMapBuilderOptions(map_builder_parameters.get());

    const std::string kTraje
评论 2
添加红包

请填写红包祝福语或标题

红包个数最小为10个

红包金额最低5元

当前余额3.43前往充值 >
需支付:10.00
成就一亿技术人!
领取后你会自动成为博主和红包主的粉丝 规则
hope_wisdom
发出的红包

打赏作者

CloudFlame

你的鼓励将是我创作的最大动力

¥1 ¥2 ¥4 ¥6 ¥10 ¥20
扫码支付:¥1
获取中
扫码支付

您的余额不足,请更换扫码支付或充值

打赏作者

实付
使用余额支付
点击重新获取
扫码支付
钱包余额 0

抵扣说明:

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

余额充值