LiDAR_IMU_Init
LiDAR_IMU_Init copied to clipboard
warning in terminal
Hi, when i run the launch file I get this message in the terminal indefinitely:
Failed to find match for field 'ring'.
Here's the info about my rosbag:
path: calib_3.bag
version: 2.0
duration: 1:06s (66s)
start: Jul 19 2023 15:15:13.51 (1689759913.51)
end: Jul 19 2023 15:16:19.87 (1689759979.87)
size: 1007.3 MB
messages: 35466
compression: none [664/664 chunks]
types: sensor_msgs/Imu [6a62c6daae103f4ff57a132d6f95cec2]
sensor_msgs/PointCloud2 [1158d486dd51d683ce2f1be655c3c181]
topics: /imu0 33284 msgs : sensor_msgs/Imu
/mavros/imu/data 1519 msgs : sensor_msgs/Imu
/ouster_11/points 663 msgs : sensor_msgs/PointCloud2
Thanks
The point type for your pointcloud may be different from what is expected by this package. I would check the point fields in the pointcloud2 message and match them with the point types defined here https://github.com/hku-mars/LiDAR_IMU_Init/blob/6d20db38557d80fcc289e4e7b09f02a468d78549/src/preprocess.h#L35-L115 Most likely the datatype for the ring field is different (e.g. the bag as the ring as a uint8 instead of a uint16) in which case you can just make the change in these lines.
I have simular warning:
Failed to find match for field 'reflectivity'.
Failed to find match for field 'ring'.
Failed to find match for field 'ambient'.
Failed to find match for field 'range'.
These warnings occur due to the specifics of different lidar data. You need to look at the data header and figure out which fields you have.
I handle this warning this way:
-
Collect some of the lidar data
rostopic echo /os1_points > test_lidar.txt -
Display header of one message:
$ head test_lidar.txt -n42 header: seq: 5 stamp: secs: 1565943694 nsecs: 928035526 frame_id: "ouster" height: 1 width: 65537 fields: - name: "x" offset: 0 datatype: 7 count: 1 - name: "y" offset: 4 datatype: 7 count: 1 - name: "z" offset: 8 datatype: 7 count: 1 - name: "intensity" offset: 16 datatype: 7 count: 1 - name: "t" offset: 20 datatype: 6 count: 1 - name: "ring" offset: 24 datatype: 5 count: 1 is_bigendian: False point_step: 32 row_step: 2097184 data: [.......] is_dense: True --- -
Update
preprocess.hfile:You can check the docks to choose the right fuild types: sensor_msgs/PointField and sensor_msgs/PointCloud2
-
Rebuild project:
catkin build