How to change the range of Lidar on Limo?

Introduction to Lidar on Limo

The lidar on Limo is EAI X2L(a single-line lidar).
image

A single-line Lidar has only one laser transmitter and receiver. When the motor rotates, it projects a line to the obstacle in front. The advantage of this is that the amount of data to be processed is relatively small, the efficiency is high, the stability is good, and the technology is mature. However, it can only detect obstacles at the same height.

The common working principles of single-line LiDAR include triangulation and Time-of-Flight (TOF) ranging methods.

In the Time-of-Flight (TOF) ranging principle, the LiDAR emitter emits a laser beam that, upon hitting an object, undergoes diffuse reflection and returns to the laser receiver. The radar module calculates the distance between the emitter and the object by multiplying the time interval between the emission and reception of the signal by the speed of light and then dividing by 2.

In the triangulation method, the LiDAR emitter sends out a laser beam, which is reflected by the object and captured by the receiver. A dashed line parallel to the incident light is drawn through the focal point, creating two similar triangles. The distance between the object and the laser emitter can be calculated through geometric relationships. The working principle is illustrated in figure below.
image
image

The ranging process can be derived from the above formula, where f is the focal length, x is the length of the laser receiver, s is the distance between the laser emitter and the laser receiver, q is the laser ranging value, d is the distance from the laser emitter to the object, and β is the laser emission angle.

The mapping effect of a single-line lidar is shown in the figure
image

Three ways to modify the scanning range of LiDAR

What is LaserScan
sensor_msgs::LaserScan is a laser data format defined by ROS. It defines point cloud data according to the order and parameters of a circle of laser scans, rather than directly giving the xyz value of each laser point.
The sensor_msgs/LaserScan message type defines the following fields:

â—Ź header:
metadata of the message, including the message serial number, timestamp, coordinate system and other information
â—Ź angle_min:
minimum scanning angle of the laser beam (radians)
â—Ź angle_max:
maximum scanning angle of the laser beam (radians)
â—Ź angle_increment:
angle increment between each scanning point (radians)
â—Ź time_increment:
time increment between each scanning point (seconds)
â—Ź scan_time:
duration of each scan (seconds)
â—Ź range_min:
minimum distance for laser ranging (meters)
â—Ź range_max:
maximum distance for laser ranging (meters)
â—Ź ranges:
distance value of each scanning point, expressed in the form of an array
â—Ź intensities:
reflection intensity value of each scanning point, expressed in the form of an array (optional field)

Why should some of the LiDAR data be shielded?

Shielding LiDAR data means filtering out data from certain areas measured by LiDAR during data processing, thereby preventing these data from interfering with robot control and navigation.

Generally speaking, we will set some shielding rules based on actual application needs, such as ignoring data beyond a certain distance, ignoring certain specific areas or objects, etc.

3 ways to shield lidar data

1. Modify the launch file to perform data shielding
This method needs an understanding of the parameters of the lidar. It is an easy way to modify. Generally speaking, you can directly modify the parameters of the launch file. Take the launch file of the Limo’s EAI X2L lidar as an example.

<launch>
  <node name="ydlidar_node"  pkg="ydlidar_ros"  type="ydlidar_node" output="screen" respawn="false" >
    <param name="port"         type="string" value="/dev/ydlidar"/>  
    <param name="baudrate"         type="int" value="115200"/>  
    <param name="frame_id"     type="string" value="laser_link"/>
    <param name="resolution_fixed"    type="bool"   value="true"/>
    <param name="auto_reconnect"    type="bool"   value="true"/>
    <param name="reversion"    type="bool"   value="true"/>
    
    <param name="angle_min"    type="double" value="-90" />
    <param name="angle_max"    type="double" value="90" />
    <param name="range_min"    type="double" value="0.1" />
    <param name="range_max"    type="double" value="12.0" />
    
    <param name="ignore_array" type="string" value="" />
    <param name="frequency"    type="double" value="8"/>
    <param name="samp_rate"    type="int"    value="3"/>
    <param name="isSingleChannel"    type="bool"   value="true"/>
  </node>
</launch>

In this launch file, the parameters for shielding the laser radar data are angle_min, angle_max, range_min, and range_max. Previously, we know that these four parameters represent the starting angle of the lidar, the ending angle of the laser radar, the minimum scanning distance of the laser radar, and the maximum scanning angle of the laser radar.

For example, the X2L laser radar can perform 360° full-range scanning. From the above parameters, we can see that the starting angle of the laser radar is -90°~90°, and the scanning angle is only 180°. Why is it set like this?

This is because it is related to the placement of the lidar. The lidar is placed on the front of the limo. Due to mechanical design, the 180° range behind the lidar is blocked by the Limo body. If it is scanned at a 360° scanning angle, the laser radar will judge itself as an obstacle, resulting in the inability to avoid obstacles normally. Therefore, it is necessary to shield the data of the second half of the lidar.

When we want to use the laser radar for 360° scanning, we only need to change the above angle_min to -180 and angle_max to 180 to achieve this effect.

2. Programming to shield the LiDAR data
This requires processing the LiDAR data in the program and filtering out unnecessary data. The advantage of this method is that it is highly flexible and can be customized according to specific needs. The disadvantage is that it requires writing a corresponding program and it will be relatively difficult for beginners.
The following are the specific steps to use C++ programming to shield the data of the 30° in front of the laser radar:

  1. Create a function package named scan_example_0, which depends on roscpp sensor_msgs.
catkin_create_pkg scan_example_0 roscpp sensor_msgs
  1. Create the change_scan_range.cpp file and write the following code.
    First, you need to include the relevant header files and define the ROS node.
#include "ros/ros.h"
#include "sensor_msgs/LaserScan.h"

int main(int argc, char **argv)
{
    ros::init(argc, argv, "laser_scan_filter");
    ros::NodeHandle nh;
    ...
}

Subscribe to the LiDAR topic “scan”

ros::Subscriber scan_sub = nh.subscribe<sensor_msgs::LaserScan>("scan", 1000, scanCallback);

In the callback function, shield the laser radar data from 90° to 270°. First, define a new sensor_msgs::LaserScan type variable new_scan, save the received laser radar data in the variable, and shield the data from 90° to 270°.

void scanCallback(const sensor_msgs::LaserScan::ConstPtr& scan_msg)
{
    sensor_msgs::LaserScan new_scan;
    new_scan = *scan_msg;

    std::cout<<"The size of the LiDAR distance array is"<<(new_scan.angle_max-new_scan.angle_min)/new_scan.angle_increment<<std::endl;
    float s= 1.57/scan_msg->angle_increment;  //90°
    float e=4.71/scan_msg->angle_increment;   //270°
    std::cout<<"K is"<<s<<std::endl;
    std::cout<<"end is:"<<e<<std::endl;


    for(int i=(int)s; i < e ; i++)
    {
        new_scan.ranges[i]=0;
    }
    // Publish the processed data
    new_scan.header.stamp = ros::Time::now();
    pub.publish(new_scan);
}

Finally, the processed data is published with the topic “new_scan”.
The complete code is:

#include "ros/ros.h"
#include "sensor_msgs/LaserScan.h"

ros::Publisher pub;

void scanCallback(const sensor_msgs::LaserScan::ConstPtr& scan_msg)
{
    sensor_msgs::LaserScan new_scan;
    new_scan = *scan_msg;

    std::cout<<"The size of the LiDAR distance array is"<<(new_scan.angle_max-new_scan.angle_min)/new_scan.angle_increment<<std::endl;
    float s= 1.57/scan_msg->angle_increment;  //90°
    float e=4.71/scan_msg->angle_increment;   //270°
    std::cout<<"K is:"<<s<<std::endl;
    std::cout<<"end is"<<e<<std::endl;

    for(int i=(int)s; i < e ; i++)
    {
        new_scan.ranges[i]=0;
    }
    // Publish the processed data
    new_scan.header.stamp = ros::Time::now();
    pub.publish(new_scan);
}

int main(int argc, char **argv)
{
    ros::init(argc, argv, "laser_scan_filter");
    ros::NodeHandle nh;
  
    ros::Subscriber sub = nh.subscribe<sensor_msgs::LaserScan>("/MS200/scan", 1000, scanCallback);
    // Publish new Laserscan type data to the topic "new_scan"
    pub = nh.advertise<sensor_msgs::LaserScan>("new_scan", 1000);
    // Loop through ROS callback functions
    ros::spin();
    
    return 0;
}
  1. Add these two lines in CMakeLists.txt
add_executable(change_scan_range_node src/change_scan_range.cpp)

target_link_libraries(change_scan_range_node
   ${catkin_LIBRARIES}
 )
  1. Run the code
    First, open the X2L laser radar on LIMO
roslaunch ydlidar_ros X2L.launch

Then run the code we wrote

rosrun scan_example_0 change_scan_range_node
  1. Open rviz to see the effect.

3. Use the laser_filter package to shield the laser radar data
Use the laser_filter package to shield the laser radar data. This method uses the laser_filter package in ROS to process data and filter out unnecessary data.
The advantage of this method is that it is convenient and easy to use, and does not require writing additional programs. The disadvantage is that the function is relatively simple and not as flexible as the programming method.

There are mainly the following types of laser_filter:

  1. LaserArrayFilter
    This filter uses the filter implementation of the floating-point array filter internally (using mathematical filters to filter distance and intensity). It extracts the range and intensity values ​​and treats each value as an independent floating-point array passed through the internal filter chain.
    Parameter setting example:
scan_filter_chain:
- type: laser_filters/LaserArrayFilter  
name: laser_median_filter  
  params:    
range_filter_chain:      
- name: median_5        
      type: MultiChannelMedianFilterFloat        
params:          
number_of_observations: 5          
  unused: 10    
    intensity_filter_chain:      
- name: median_5        
type: MultiChannelMedianFilterFloat        
params:          
number_of_observations: 5          
          unused: 10
  1. ScanShadowsFilter
    This filter removes laser readings that are most likely caused by shadowing effects when scanning the edges of objects. For any two points P1 and P2, we do this by calculating the vertical angle. That is, assuming the origin of the laser is O, the angle OP1P2 is formed. If the vertical angle is less than a certain minimum value or greater than a certain maximum value, we remove all nearby points of that point.
    Filter out data that may be caused by shadowing effects.
    Parameter setting example:
scan_filter_chain:
- name: shadows  
type: laser_filters/ScanShadowsFilter  
  params:    
min_angle: 10    
    max_angle: 170    
    neighbors: 20    
    window: 1
  1. InterpolationFilter
    For any invalid measurement in the scan, a measurement is generated that is an interpolation between the surrounding good values.
    Interpolate data between trusted points
    Parameter setting example:
scan_filter_chain:
- name: interpolation
type: laser_filters/InterpolationFilter
  1. LaserScanIntensityFilter
    This filter removes all measurements from sensor_msgs/LaserScan with an intensity greater than upper_threshold or less than lower_threshold. These points are “removed” by setting the corresponding range value to range_max + 1, which is assumed to be an error condition.
    Filter out data outside the given density upper and lower bounds
    Parameter setting example:
scan_filter_chain:
- name: intensity  
type: laser_filters/LaserScanIntensityFilter  
  params:    
lower_threshold: 8000    
    upper_threshold: 100000    
    disp_histogram: 0
  1. LaserScanRangeFilter
    This filter removes all measurements from sensor_msgs/LaserScan that are greater than upper_threshold or less than lower_threshold. These points are “removed” by setting the corresponding range value to NaN, which is assumed to be an error condition or lower_replacement_value/upper_replacement_value. If use_message_range_limits is true, the range in the laserscan message is used.
    Filter out radar data outside the specified scan distance range
    Parameter setting example:
scan_filter_chain:
- name: range  
  type: laser_filters/LaserScanRangeFilter  
  params:    
    use_message_range_limits: false  # Whether to use threshold information from the scan message, defaults to false    
    lower_threshold: 0.3             # Minimum threshold    
    upper_threshold: .inf            # Maximum threshold    
    lower_replacement_value: -.inf   # Replace data below the minimum threshold with this value, default is NaN    
    upper_replacement_value: .inf    # Replace data above the maximum threshold with this value, default is NaN
  1. LaserScanAngularBoundsFilter
    This filter removes points outside certain angle ranges in sensor_msgs/LaserScan by changing the minimum and maximum angles.
    Filters out radar data outside the specified scan angle range
    Parameter setting example:
scan_filter_chain:
- name: angle  
  type: laser_filters/LaserScanAngularBoundsFilter  
  params:
    lower_angle: -1.57
    upper_angle: 1.57
  1. LaserScanAngularBoundsFilterInPlace
    This filter removes points from the sensor_msgs/LaserScan within certain angular ranges (it does not remove data outside the target angular sectors). The points are “removed” by setting the corresponding range values to range_max + 1, which is assumed to indicate an error condition.
    It filters out LiDAR data within the specified scan angular range.

Example parameter configuration:

scan_filter_chain:
- name: angle  
type: laser_filters/LaserScanAngularBoundsFilterInPlace  
params:    
    lower_angle: 0.685398163    
    upper_angle: 0.885398163
  1. LaserScanBoxFilter
    This filter removes data within a specified box (commonly used to ignore interference from the robot’s body in LiDAR data). The points are “removed” by setting the corresponding range values to NaN, which is assumed to indicate an error condition.
    It filters out data within the specified box range.

Example parameter configuration:

scan_filter_chain:
- name: box  
type: laser_filters/LaserScanBoxFilter  
  params:    
box_frame: scan_link    
    min_x: -1.0    
    max_x: 1.0    
    min_y: -1.0    
    max_y: 1.0    
    min_z: -1.0    
    max_z: 1.0

Download the Lidar filter:

git clone https://github.com/ros-perception/laser_filters

Use laser_filter to mask the lidar data according to the effect you want.

Test results

Programming to shield 90~270° radar data. The left picture is unshielded, the right picture shows the effect after shielding.

The following pictures are comparison pictures before and after filtering.
image
image
image
image

Quiz

● Write a ROS node using the LaserScan message type in ROS. This node should subscribe to the /scan topic and, upon receiving a LaserScan message, modify the LiDAR’s scan range. For example, narrow the scan range to the area between 15 degrees and 30 degrees. You can use the rostopic echo /scan command to inspect the contents of the LaserScan message.
â—Ź Package the above node as a ROS package and use the roslaunch command to start the node. Before starting the node, ensure that the correct ROS topics and parameters are specified in the launch file. Verify that the node is running correctly and observe changes in the LiDAR scan range using the rviz visualization tool.

About Limo

Limo is a smart educational robot published by AgileX Robotics. More details please visit: https://global.agilex.ai/


If you are interested in Limo or have some technical questions about it, feel free to join AgileX Robotics or AgileX Robotics. Let’s talk about it!

2 Likes