hku-mars / r3live

A Robust, Real-time, RGB-colored, LiDAR-Inertial-Visual tightly-coupled state Estimation and mapping package
GNU General Public License v2.0
1.99k stars 431 forks source link

Get pointcloud data from ros messages fail #189

Closed HaogeZhou closed 1 year ago

HaogeZhou commented 1 year ago

Thanks for your work, I am very excited to try it! I am using Ubuntu 20.04 + ROS noetic + Ouster os1-64 lidar with inner imu data + zed2i camera. I was trying to start the r3live_bag_ouster.launch file to do mapping, but when I started to run bag, I received the error message related to the point cloud. See attached below. image

Could someone tell me how to fix this error? Thanks in advance.

alwynmathew commented 1 year ago

For some reason, it only works for lidar scans with fields.size() < 3 or fields.size() == 8 && fields[ 3 ].name == "intensity" && fields[ 4 ].name == "normal_x" or fields.size() == 4 && fields[ 3 ].name == "rgb" format as shown below: https://github.com/hku-mars/r3live/blob/6143a38537f28cb36eb24e9bbe2e39c8f7967157/r3live/src/r3live_lio.cpp#L91

HaogeZhou commented 1 year ago

Hi @alwynmathew , I also seen this code. Here is my lidar topic output.

> header: 
>   seq: 4430
>   stamp: 
>     secs: 528
>     nsecs: 948532131
>   frame_id: "os_sensor"
> height: 64
> width: 2048
> 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: "reflectivity"
>     offset: 24
>     datatype: 4
>     count: 1
>   - 
>     name: "ring"
>     offset: 26
>     datatype: 4
>     count: 1
>   - 
>     name: "ambient"
>     offset: 28
>     datatype: 4
>     count: 1
>   - 
>     name: "range"
>     offset: 32
>     datatype: 6
>     count: 1
> is_bigendian: False
> point_step: 48
> row_step: 98304

I have no idea about knowing my lidar(ouster os1-64) field size is suitable or not. How can I get the field size of my lidar?

alwynmathew commented 1 year ago

Your LiDAR field size is 9, as shown in the error screenshot above. A workaround is adding the below statement after L112 in r3live_lio.cpp

else if ( ( msg->fields.size() == 9 ) ) 
        {
            pcl::fromROSMsg( *msg, pcl_pc );
            return true;
        }

This should make the package work, but still, you will get a warning that normals are missing. They expect the input to be in PointXYZINormal format. Good luck!

HaogeZhou commented 1 year ago

Thanks for your help! As you imagine, the point cloud is shown in Rviz, but the "normal_x" "normal_y" "normal_z" are missing. image I'm trying to change PointXYZINormal to PointXYZI, but it seems not work.

stale[bot] commented 1 year ago

This issue has been automatically marked as stale because it has not had recent activity. It will be closed if no further activity occurs. Thank you for your contributions.

zxhasd commented 10 months ago

感谢您的帮助!正如您想象的那样,点云显示在 Rviz 中,但缺少“normal_x”、“normal_y”、“normal_z”。 我正在尝试将 PointXYZINormal 更改为 PointXYZI,但似乎不起作用。 图像

请问您解决这个问题了吗