carto建图时去除动态障碍

cartographer的内容实在太庞大了,还有去除建图时动态障碍的模块。

在使用Cartographer建图时,存在环境中行人较多,或者建图时机器人周围人员一直跟随,导致最终建图后地图上存在行人噪点。

Cartographer在构建submap以及整体map时,实质是对栅格地图概率的更新,每一个node在栅格概率上的累加,可以去除建图时一般移动物体所产生的噪点。只要不是长时间停留在雷达探测范围内,栅格地图的概率会及时更新,最终生成的地图不会带有行人和车辆。但是实际建图中经常会出现多人跟在机器人周围建图或恰巧机器人旋转时周围人为移动,旋转时node快速生成,导致该部分submap中存在行人噪点,如果后期不重复走这条路径,最终生成的map会存在噪点,影响地图美观,以及路径规划是被视为障碍物。

cartographer在建图后比较每个栅格被击中和被路过的次数来判断动静态栅格。参数voxel_filter_and_remove_moving_objects和类OutlierRemovingPointsProcessor,可以用来配置Voxel过滤数据,并仅传递我们认为在非运动对象上的点。

追本溯源,发现这一机制只在cartographer_assets_writer中,顺序是 assets_writer_main.cc —— assets_writer.cc —— points_processor_pipeline_builder.cc中的RegisterBuiltInPointsProcessors —— OutlierRemovingPointsProcessor

cartographer_assets_writer 使用.bag中的数据团和.pbstream中的轨迹. 配置文件可以用来上色,过滤,导出SLAM点云数据成不同的格式。

逻辑

其实很简单,有三个阶段,筛选出 hit > 0 的 voxel,计算经过这些voxel的 rays-cast 次数,可以按miss集合理解,然后比较rays和hits数目关系

1
2
3
4
5
6
7
8
9
10
11
12
13
// 第二阶段
// 如果栅格之前的 hit>0,那么就 ray 次数增加
if (voxels_.value(index).hits > 0)
{
++voxels_.mutable_value(index)->rays;
}

// 第三阶段
// 如果点的 rays > 3*hits 那么就认为是动态障碍物
if (!(voxel.rays < miss_per_hit_limit_ * voxel.hits))
{
to_remove.insert(i);
}

这个逻辑有点过于简单了,如果一个栅格被障碍占据,那么rays为0,全是hits,不是动态障碍。如果rays次数过多,就认为是假障碍,进行清除。

运行

assets_writer_backup_2d.launch如下

1
2
3
4
5
6
7
8
9
10
11
12
<launch>
<arg name="config_file" default="assets_writer_backpack_2d.lua"/>
<node name="cartographer_assets_writer" pkg="cartographer_ros" required="true"
type="cartographer_assets_writer" args="
-configuration_directory $(find cartographer_ros)/configuration_files
-configuration_basename $(arg config_file)
-urdf_filename $(find cartographer_ros)/urdf/backpack_2d.urdf
-bag_filenames $(arg bag_filenames)
-pose_graph_filename $(arg pose_graph_filename)"
output="screen">
</node>
</launch>

参考:如何使用Cartographer生成的地图