【cartographer】assets_writer的lua文件配置

最近研究cartographer的3d建图,发现用3d建图直接生成的pbstream转出来的pgm图没有白色可行区域,就顺着找到了assets_writer。虽然研究完了以后觉得没有白色区域极大可能是因为我只用了一个水平方向的多线雷达,如果加一个纵向的多线雷达可能好了(有时间再试试),不过怕我以后要用的时候忘记,所以在这里记录一下。

如果文章有误,欢迎在评论区指出讨论。


总览

VOXEL_SIZE = 5e-2

include "transform.lua"

options = {
  tracking_frame = "base_link",
  pipeline = {
    {
      action = "min_max_range_filter",
      min_range = 0.5,
      max_range = 30.,
    },
    {
      action = "dump_num_points",
    },
    {
      action = "color_points",
      frame_id = "base_footprint",
      color = {255., 0., 0.},
    },

    {
      action = "write_xray_image",
      voxel_size = VOXEL_SIZE,
      filename = "xray_yz_all_color",
      transform = YZ_TRANSFORM,
    },
    {
      action = "write_xray_image",
      voxel_size = VOXEL_SIZE,
      filename = "xray_xy_all_color",
      transform = XY_TRANSFORM,
    },
    {
      action = "write_xray_image",
      voxel_size = VOXEL_SIZE,
      filename = "xray_xz_all_color",
      transform = XZ_TRANSFORM,
    },
    {
      action = "write_ply",
      filename = "points.ply"
    },
    {
      action = "write_probability_grid", 
      resolution = 0.05, 
      range_data_inserter = { 
        insert_free_space = true, 
        hit_probability = 0.55, 
        miss_probability = 0.49, 
      }, 
      draw_trajectories = false, 
      output_type = "png", 
      filename = "map" 
    },
  }
}

return options

下面只涉及到pipeline里的内容

1、min_max_range_filter

	{
      action = "min_max_range_filter",
      min_range = 0.5,
      max_range = 30.,
    },

点云数据距离的过滤器,没什么好说的

2、color_points

	{
      action = "color_points",
      frame_id = "laser_link",
      color = {255., 0., 0.},
    },

对frame_id下的点云数据进行染色,color里是rgb值,可以用来区分不同雷达的点云数据,要写在后文提到的action的前面才能染色

3、write_xray_image

	{
      action = "write_xray_image",
      voxel_size = VOXEL_SIZE,
      filename = "xray_yz_all_color",
      transform = YZ_TRANSFORM,
    },
    {
      action = "write_xray_image",
      voxel_size = VOXEL_SIZE,
      filename = "xray_xy_all_color",
      transform = XY_TRANSFORM,
    },
    {
      action = "write_xray_image",
      voxel_size = VOXEL_SIZE,
      filename = "xray_xz_all_color",
      transform = XZ_TRANSFORM,
    },

输出一个.png文件,相当于给点云图在transform的角度拍张照。transform的格式如下:

XY_TRANSFORM =  {
  translation = { 0., 0., 0. },
  rotation = { 0., -math.pi / 2., 0., },
}

4、write_ply

	{
      action = "write_ply",
      filename = "points.ply"
    },

输出.ply格式文件

5、write_pcd

	{
      action = "write_pcd",
      filename = "points.pcd"
    },

输出.pcd格式文件

6、write_xyz

	{
      action = "write_xyz",
      filename = "points.xyz"
    },

输出.xyz格式文件

7、write_probability_grid

	{
      action = "write_probability_grid", 
      resolution = 0.05, 
      range_data_inserter = { 
        insert_free_space = true, 
        hit_probability = 0.55, 
        miss_probability = 0.49, 
      }, 
      draw_trajectories = false, 
      output_type = "png", 
      filename = "map" 
    },

输出概率栅格文件,output_type可选png和pb(似乎pb已经不用了)

  • 0
    点赞
  • 0
    收藏
    觉得还不错? 一键收藏
  • 0
    评论

“相关推荐”对你有帮助么?

  • 非常没帮助
  • 没帮助
  • 一般
  • 有帮助
  • 非常有帮助
提交
评论
添加红包

请填写红包祝福语或标题

红包个数最小为10个

红包金额最低5元

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

抵扣说明:

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

余额充值