SICKAG / sick_scan_xd

Based on the sick_scan drivers for ROS1, sick_scan_xd merges sick_scan, sick_scan2 and sick_scan_base repositories. The driver supports both Linux (native, ROS1, ROS2) and Windows (native and ROS2).
Apache License 2.0
105 stars 86 forks source link

sick_lms1xx range_max parameter not working #108

Closed dburgt98 closed 2 years ago

dburgt98 commented 2 years ago

The launch files in this repository for the lidar sensors contain a parameter called 'range_max'. For the lms_1xx sensor specifically, I have changed the value of this parameter with the intention to limit the range in the pointcloud output. However, when I launch a model with three sensors, and visualize the transformed pointcloud data in RVIZ, I notice that the parameter is not effective as the range is not limited in the visualization. As you can see in the image, pointcloud data of the 'wall' is still visible, though I only want to scan the item on the conveyor belt.

Could this be a bug in the repository? Or could there be any other reason why the range is not limited after changing the value? What would be advised for me to filter out the wall, or any other object outside the range of the conveyor belt? Please read further for more details.

Screenshot from 2022-09-19 13-44-17

roslaunch sick_scan sick_lms_1xx.launch

<launch>
    <arg name="hostname" default="192.168.0.1"/>
    <arg name="cloud_topic" default="cloud"/>
    <arg name="frame_id" default="cloud"/>
    <arg name="sw_pll_only_publish" default="true"/>
    <arg name="nodename" default="sick_lms_1xx"/>
    <arg name="add_transform_xyz_rpy" default="0,0,0,0,0,0"/>
    <arg name="range_max" default="0.5" />
    <arg name="min_ang" default="-2.35619" />
    <arg name="max_ang" default="2.35619" />
    <node name="$(arg nodename)" pkg="sick_scan" type="sick_generic_caller" respawn="false" output="screen" required="true">
        <param name="intensity" type="bool" value="True"/>
        <param name="intensity_resolution_16bit" type="bool" value="false"/>
        <param name="min_ang" type="double" value="$(arg min_ang)"/>
        <param name="max_ang" type="double" value="$(arg max_ang)"/>
        <param name="frame_id" type="str" value="$(arg frame_id)"/>
        <param name="use_binary_protocol" type="bool" value="true"/>
        <param name="scanner_type" type="string" value="sick_lms_1xx"/>
        <param name="range_max" type="double" value="$(arg range_max)"/>
        <param name="hostname" type="string" value="$(arg hostname)"/>
        <param name="cloud_topic" type="string" value="$(arg cloud_topic)"/>
        <param name="port" type="string" value="2112"/>
        <param name="timelimit" type="int" value="5"/>
        <param name="sw_pll_only_publish" type="bool" value="$(arg sw_pll_only_publish)"/>
        <param name="use_generation_timestamp" type="bool" value="true"/> <!-- Use the lidar generation timestamp (true, default) or send timestamp (false) for the software pll converted message timestamp -->
        <param name="start_services" type="bool" value="True"/> <!-- start ros service for cola commands -->
        <param name="activate_lferec" type="bool" value="True"/> <!-- activate field monitoring by lferec messages -->
        <param name="activate_lidoutputstate" type="bool" value="True"/> <!-- activate field monitoring by lidoutputstate messages -->
        <param name="activate_lidinputstate" type="bool" value="True"/> <!-- activate field monitoring by lidinputstate messages -->
        <param name="min_intensity" type="double" value="0.0"/> <!-- Set range of LaserScan messages to infinity, if intensity < min_intensity (default: 0) -->

        <param name="ang_res" type="double" value="0.5" /> <!-- Supported values are "0.25" and "0.50" -->
        <param name="scan_freq" type="double" value="50" /> <!-- Supported values are "25" and "50" -->
        <!-- Note: angular resolution and scanning frequency of a LMS111 can be configured by parameter "ang_res" (values "0.25" or "0.5") and "scan_freq"  (values "25" or "50") -->
        <!-- After setting "ang_res" and "scan_freq", it takes ca. 30 seconds until the pointcloud is published. -->
        <!-- Recommendation: It is recommended to specify the desired angular resolution and scan rate in this launch file. -->
        <!-- In this case, it is necessary to wait approx. 30 sec. until the Lidar changes to status "OK". -->
        <!-- Alternatively, these settings can be configured in SOPAS-ET, transferred to the EEProm of the lidar and -->
        <!-- then permanently stored. In this case, the explicit specification of scan rate and angular resolution -->
        <!-- can be omitted and the waiting time can be avoided. -->  

        <!-- Apply an additional transform to the cartesian pointcloud, default: "0,0,0,0,0,0" (i.e. no transform) -->
        <!-- Note: add_transform_xyz_rpy is specified by 6D pose x, y, z, roll, pitch, yaw in [m] resp. [rad] -->
        <!-- It transforms a 3D point in cloud coordinates to 3D point in user defined world coordinates: --> 
        <!-- add_transform_xyz_rpy := T[world,cloud] with parent "world" and child "cloud", i.e. P_world = T[world,cloud] * P_cloud -->
        <!-- The additional transform applies to cartesian lidar pointclouds and visualization marker (fields) -->
        <!-- It is NOT applied to polar pointclouds, radarscans, ldmrs objects or other messages -->
        <param name="add_transform_xyz_rpy" type="string" value="$(arg add_transform_xyz_rpy)" /> 

        <param name="message_monitoring_enabled" type="bool" value="True" />      <!-- Enable message monitoring with reconnect+reinit in case of timeouts, default: true -->
        <param name="read_timeout_millisec_default" type="int" value="5000"/>     <!-- 5 sec read timeout in operational mode (measurement mode), default: 5000 milliseconds -->
        <param name="read_timeout_millisec_startup" type="int" value="120000"/>   <!-- 120 sec read timeout during startup (sensor may be starting up, which can take up to 120 sec.), default: 120000 milliseconds -->
        <param name="read_timeout_millisec_kill_node" type="int" value="150000"/> <!-- 150 sec pointcloud timeout, ros node will be killed if no point cloud published within the last 150 sec., default: 150000 milliseconds -->
        <param name="client_authorization_pw" type="string" value="F4724744"/>    <!-- Default password for client authorization -->

    </node>
</launch>

I have modified the launch file a little, by making 'range_max', 'min_ang' and 'max_ang' configurable. I did this to be able to start multiple sensors from a different launch file, while being able to configure the values. I have not included that other launch file, as this issue also occurs when launching just a single sensor manually with the following commands (see result in second image):

roslaunch sick_scan sick_lms_1xx.launch rviz (second window, added pointcloud for topic '/cloud' to rviz) rosrun tf static_transform_publisher 0 0 0 0 0 0 /map /cloud 50 (third window)

Screenshot from 2022-09-19 13-58-07

rostest commented 2 years ago

Thanks for reporting! Basically we recommend to filter the pointcloud in the application according to the requirements. We will check and adjust the range filter.

dburgt98 commented 2 years ago

Thanks for reporting! Basically we recommend to filter the pointcloud in the application according to the requirements. We will check and adjust the range filter.

Thank you for the recommendation. I will try to filter out the ranges in my application then.

In case the range filter currently has a bug, I will keep an eye on new commits to see if it gets fixed. So that I can reduce the application code to keep it simple.

However, if you checked it and it is not a bug, but I simply made a mistake, then please let me know.

michael1309 commented 2 years ago

With version 2.8.7 and higher you can set the filter parameter as you proposed in your issue.