使用octomap_server将点云地图转化为八叉树地图和占据栅格地图

说明

Octomap 在ROS环境下实时显示Lego_loam使用教程两篇博文对如何从PCD创建PointCloud2点云、如何用octomap_server创建八叉树地图和栅格地图已经说的很详细了,但是我在使用时还是遇到了一些问题。

问题1:点云与网格垂直

我用深度相机得到点云地图后,按照Octomap 在ROS环境下实时显示去创建点云地图后发现点云和网格时垂直的
点云与网格垂直主要是因为我的相机坐标系定义为:z轴往前,x轴往左(不是常见的往右是因为我的图像采集时镜像了),y轴往下,RVIZ默认显示的是xy平面,改成显示xz平面就正常了
在这里插入图片描述另一种办法是像Lego_loam使用教程中那样对点云坐标做变换,绕x轴旋转90度,将z轴指向上方。

    Eigen::Affine3f transform = Eigen::Affine3f::Identity();
    transform.rotate(Eigen::AngleAxisf(-M_PI/2, Eigen::Vector3f(1,0,0)));
    pcl::transformPointCloud(cloud, cloud, transform);

我用-pi/2而非pi/2还是因为的坐标镜像问题。

第二种方法其实更好,因为从octomap_server的参数来看,它的坐标系是定义z轴向上的,它得到栅格地图也是默认投影到xy平面。

问题2:八叉树显示不完整

构建八叉树地图时发现地图显示不完整,地面没有显示出来
在这里插入图片描述原因是我的相机与地面之间是有一定高度,octomap_server中的pointcloud_min_z不应该设置为0,而应该取一定的负数范围

    <param name="pointcloud_max_z" value="1000" />
    <param name="pointcloud_min_z" value="-1000" />

地面就正常显示了
在这里插入图片描述

问题3:地面滤除

生成栅格地图后发现地面也被认为是占据状态了
在这里插入图片描述原因是地面的点云也被投影了,应该把地面滤除掉,同样设置好pointcloud_min_z即可

<param name="pointcloud_max_z" value="1000" />
<param name="pointcloud_min_z" value="-0.2" />

在这里插入图片描述

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

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

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

请填写红包祝福语或标题

红包个数最小为10个

红包金额最低5元

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

抵扣说明:

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

余额充值