Note: This tutorial assumes that you have completed the previous tutorials: introduction to using laser scanners tutorial. |
Please ask about problems and questions regarding this tutorial on answers.ros.org. Don't forget to include in your question the link to this page, the versions of your OS & ROS, and also add appropriate tags. |
Using the laser filtering nodes
Description: Raw laser scans contain all points returned from the scanner without processing. Many applications, however, are better served by filtered scans which remove unnecessary points (such as unreliable laser hits or hits on the robot itself), or pre-process the scans in some way (such as by median filtering). This tutorial will teach you how to apply pre-existing filters to laser scans.Tutorial Level: INTERMEDIATE
Next Tutorial: laser_assembler/Tutorials/HowToAssembleLaserScans laser_filters/Tutorials/Laser filtering in C++
Contents
The laser filters package provides nodes that can run multiple filters internally. These nodes are useful if you want to do all the laser filtering in your system only once, and then let multiple other nodes use the result. This tutorial provides an example of how to use the scan_to_scan_filter_chain node.
Data
As in the introduction to using laser scanners tutorial, you can try the tools in this tutorial on the bag found here (save link as...).
Filtering a Scan: The Scan Shadows Filter
Laser scans sometimes hit objects at a grazing angle, resulting in "split pixels" or "shadows". These laser hits show up in the scan as single points in the middle of space, part-way between the object they grazed and a background object. For many tasks such as object model fitting, these points are simply noise and should be removed by using the scan shadows filter.
Filters can be applied to a laser scan in three ways: through calling the generic_laser_filter_node which applies the filter and then publishes the filtered scan, by including the code in your own node, or through the laser scan assembler. As always, the choice between filtering in a generic node versus within the node that will use the filtered scan is based on efficiency in your particular system set up.
The file shadow_filter_example.launch in the laser_filters package (examples folder) provides an example of calling the scan shadows filter as a node on the scan topic base_scan:
<launch> <node pkg="laser_filters" type="scan_to_scan_filter_chain" output="screen" name="laser_filter"> <remap from="scan" to="base_scan" /> <rosparam command="load" file="$(find laser_filters)/examples/shadow_filter_example.yaml" /> </node> </launch>
The launch file above refers to the following laser_filters/examples/shadow_filters_example.yaml file:
scan_filter_chain: - name: shadows type: laser_filters/ScanShadowsFilter params: min_angle: 10 max_angle: 170 neighbors: 20 window: 1 - name: dark_shadows type: laser_filters/LaserScanIntensityFilter params: lower_threshold: 100 upper_threshold: 10000 disp_histogram: 0
As this example shows, filters are defined in the filters tag. Each filter has a filter type and a name that differentiates it from filters of the same type. This particular example runs two filters, first the ScanShadowsFilter which removes shadow hits, and then the LaserScanIntensityFilter with parameters set to remove any hits with very low or very high intensity.
Exercise
Try creating a node and launch file that:
- filter an incoming laser scanner data stream using the filters in shadow_filters_example.xml, and
listen to the resulting filtered laser scan, convert it into a point cloud in the base_link frame and publish the cloud.
(Recall that you completed the second step in the previous tutorial: introduction to using laser scanners tutorial.)
Visualize the output of your node in rviz.
All in One Node: scan_to_cloud_filter_chain
The above exercise is so useful it's already been written up as one node. The scan_to_cloud_filter_chain node in the laser_filters package listens to a laser scan stream, applies the above filters, and outputs the result as a cloud.
IMPORTANT: scan_to_cloud_filter_chain has a parameter, use_hack, that defaults to true. If it is set to true, the resulting cloud will be offset slightly to "correct for incident angles", which is apparently very useful for navigation and using laser clouds at longer distances. If you are using the laser cloud at close ranges, i.e., for manipulation, you should set this parameter to be false, or your robot is likely to thwack into things.
Try running the scan_to_cloud_filter_chain on the /base_scan topic and visualize the resulting point cloud.