ROS—laser_filters屏蔽无效雷达数据

一、概述

激光雷达通常可以检测360度等范围内的物体,但由于机械结构设计等原因,机器人本体可能会遮挡部分激光雷达扫描数据。如果将激光雷达原始点云直接用于建图或导航,则机器人本体的一部分会被当作障碍物导致建图或导航无法正常工作。

为了解决这个问题,就需要对激光雷达的原始点云进行过滤处理,屏蔽掉不需要的数据,ros laser filters就提供了这样一种机制,可以支持通过角度、BOX等方式过滤原始点云数据,本文就带大家一起了解下。

二、准备工作

1.安装laser-filters

sudo apt install ros-$ROS_DISTRO-laser-filters

2.准备测试项目

cd ~/catkin_ws/src
catkin_create_pkg laser_filter_test

三、点云过滤

1.角度边界过滤器

顾名思义,这个LaserScanAngularBoundsFilter过滤器是通过配置角度范围来过滤点云。

我们配置一个范围为-2.5~2.5弧度的过滤器,对应实际雷达角度大概在-143~143度左右。

vim ~/catkin_ws/src/laser_filter_test/config/angle_filter.yaml

scan_filter_chain:
- name: angle_filter
  type: laser_filters/LaserScanAngularBoundsFilter
  params:
    lower_angle: -2.5
    upper_angle: 2.5

launch添加laser_filters节点,指定角度过滤文件:

vim ~/catkin_ws/src/laser_filter_test/angle_filter.launch

<launch>
  <node pkg="laser_filters" type="scan_to_scan_filter_chain"  name="laser_filter">
      <rosparam command="load" file="$(find laser_filter_test)/config/angle_filter.yaml" />
      <remap from="scan" to="scan_filtered" />
  </node>
</launch>

启动激光雷达节点之后,启动角度点云过滤:

# 启动lidar(这个使用自己的lidar节点即可)
roslaunch robot_navigation lidar.launch

# 启动点云过滤
roslaunch laser_filter_test angle_filter.launch

打开rviz添加两个LaserScan,分别订阅原始点云/scan、过滤后点云/scan_filtered,分别设置为红色和绿色,可以看到指定角度的红色点云被过滤掉了。

2.BOX盒子过滤器

顾名思义,这个过滤器可以设置矩形框过滤点云,如果你的机器人底盘为方形,且激光雷达周围各个方向都有柱子等干扰物体的话,可以设置底盘的形状来过滤底盘内部的干扰点云。

我们配置一个基于base_laser_link为原点,范围为0.2距离的矩形框过滤器。

vim ~/catkin_ws/src/laser_filter_test/config/box_filter.yaml

scan_filter_chain:
- name: box_filter
  type: laser_filters/LaserScanBoxFilter
  params:
    box_frame: base_laser_link
    min_x: -0.2
    max_x: 0.2
    min_y: -0.2
    max_y: 0.2
    min_z: -0.2
    max_z: 0.2

launch添加laser_filters节点,指定角度过滤文件:

vim ~/catkin_ws/src/laser_filter_test/box_filter.launch

<launch>
  <node pkg="laser_filters" type="scan_to_scan_filter_chain"  name="laser_filter">
      <rosparam command="load" file="$(find laser_filter_test)/config/box_filter.yaml" />
      <remap from="scan" to="scan_filtered" />
  </node>
</launch>

启动激光雷达节点之后,启动BOX点云过滤:

# 启动lidar(这个使用自己的lidar节点即可)
roslaunch robot_navigation lidar.launch

# 启动点云过滤
roslaunch laser_filter_test box_filter.launch

打开rviz添加两个LaserScan,分别订阅原始点云/scan、过滤后点云/scan_filtered,分别设置为红色和绿色,可以看到靠近机器人本体设定方框范围的红色点云被过滤掉了。

四、总结

好了,今天带大家了下2D点云的基础过滤方法,laser_filters也支持更复杂的过滤方式,比如根据点云强度、扫描范围等。将laser_filters节点添加到你的机器人lidar launch中,并修改点云的输出topic即可使用过滤后的点云数据了。

 

yan 24.7.16

 

参考:

https://wiki.ros.org/laser_filters

欢迎关注下方“非著名资深码农“公众号进行交流~

发表评论

邮箱地址不会被公开。