PGM地图文件读取

说明

众所周知,ROS/ROS2的地图默认文件是*.pgm+*.yaml的组合,其中yaml文件保存一些配置项,比如

image: /home/cwj/debug/hai_ning/0802/map.pgm
resolution: 0.050000
origin: [-18.700000, -31.000000, 0.0]
negate: 0
occupied_thresh: 0.65
free_thresh: 0.195

pgm文件是一个图片文件,可以通过图片浏览器打开
PGM格式是portable graymap format的缩写,并没有对图片进行压缩或者别的操作,保存的是灰度信息

请添加图片描述

头部保存了一些文件的信息,比如

P5
#-22.739351 -12.346523 0.0
1132 694
255

分别是P5格式,P2是ASCII码保存,可以直接用文件看内容,P5是二进制保存,第二行的是坐标原点,该信息不一定都有,可能会被OpenCV覆盖,第三行是图片的高和宽,第四行是图像的灰度最大值

如果我们直接用map_server加载pgm,可以看到/map中内容

rosrun map_server map_server map.yaml

请添加图片描述

相比与pgm原始文件,会发现缺失了一部分信息

请添加图片描述

读取方法

读取一个pgm可以使用文本的方式读取,即处理完头信息后,对后续部分按char读取,然后按照头文件中的height, width生成一个二维矩阵;也可以使用OpenCV的方式读取,以GRAY_SCALE,uint8_t读取;还可以参考map_server用SDL方式读取;

读取数据后有两点需要注意,图片的排布方式为

00 01 02
10 11 12
20 21 22

nav_msgs/OccupancyGrid读取时,是按照从左下角开始的方式转存成一个一维数组的,所以需要使用一次上下镜像操作

index = (height - i - 1) * width + width;

此外就是读取到的值范围为[0, 255]代表了黑->白, 而实际OccupancyGrid的表示方式为[0, 100]表示白->黑,其中-1代表未知,也需要一次反色的操作和归一化操作

if (value == 128) {
	msg.data.emplace_back(-1);
} else {
	value = int(std::round((1 - value / 255.0) * 100));
	msg.data.emplace_back(gray_value);
}

这样就能生成一个基本一致的图案

请添加图片描述

map_server为什么会失去一些信息

map_server中的image_loader.cpp代码

occ = (255 - color_avg) / 255.0;

// Apply thresholds to RGB means to determine occupancy values for
// map.  Note that we invert the graphics-ordering of the pixels to
// produce a map with cell (0,0) in the lower-left corner.
if(occ > occ_th)
  value = +100;
else if(occ < free_th)
  value = 0;
else if(mode==TRINARY || alpha < 1.0)
  value = -1;
else {
  double ratio = (occ - free_th) / (occ_th - free_th);
  value = 1 + 98 * ratio;
}

我们会发现有这样一个东西

occ_th, free_th, 这两个值会过滤一部分的值,将其赋值为-1和100,我们将值设置为1.0, 0, 这样就不再有过滤作用了,
发现修改后地图一片苍茫

请添加图片描述

关键在于mode == TRINARY模式,也就是3色模式,会直接将其余部分转成-1,那么选成Scale或者Raw模式呢,Scale模式下,会缺失-1的情况,Raw模式下信息都保留了,但是没有进行归一
请添加图片描述

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

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

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

请填写红包祝福语或标题

红包个数最小为10个

红包金额最低5元

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

抵扣说明:

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

余额充值