Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

range image to pointcloud with additional fields #426

Closed
saikumar-kolla opened this issue Jan 26, 2025 · 8 comments
Closed

range image to pointcloud with additional fields #426

saikumar-kolla opened this issue Jan 26, 2025 · 8 comments
Assignees
Labels
enhancement New feature or request question Further information is requested

Comments

@saikumar-kolla
Copy link

I am currently working on segmenting the point cloud. I used reflective images for image segmentation using Yolo and I could map those pixels to the metadata to get XYZ values and publish them as a new pointcloud. Now I want additional fields like reflectivity and range to the created pointcloud data. what kind of solutions do you think will work

1-approach
I have tried filtering range values from my ROI and mapped the range values with values present in the Original scan data which also have range values. I extracted the whole row in the scan data when my range values from the ROI matched the range values in the original cloud data.
The problem was I was getting extra points and my ROI was not accurate.

2- approach.
After creating ROI in range image I used metadata and got a point cloud that accurately matched my ROI in the scene. I am trying to use pandas to match XYZ values from the ROI cloud to the Original scan data to add additional fields to the ROI Cloud. The problem here is The ROI values have 12 digits after decimal and Original has 6 digits after decimal in the XYZ fields. How can I effectively match both XYZ fields and then get additional fields to the ROI cloud.

I still don't know whether this approach is good enough

I am looking for new ideas and alternatives if available

I am using Ouster-OS1 rosbag data, ROS Noetic, Python language, Ubuntu 20.04

@saikumar-kolla saikumar-kolla added the enhancement New feature or request label Jan 26, 2025
@Samahu Samahu self-assigned this Jan 27, 2025
@Samahu
Copy link
Contributor

Samahu commented Jan 27, 2025

Have you considered defining your own custom point similar to what I have prototyped here #290

@Samahu
Copy link
Contributor

Samahu commented Jan 27, 2025

Have you considered defining your own custom point similar to what I have prototyped here #290

You can pretty much add/remove any fields you like using within the Point Cloud Customization Framework feature.

@Samahu Samahu added the question Further information is requested label Jan 27, 2025
@saikumar-kolla
Copy link
Author

Hi @Samahu Thanks for the reply. I think I may have misunderstood the issue you gave me to check or I have not conveyed my question properly. The problem for me is that I am getting the /ouster/points with all fields which is perfect for my case.

However, I am creating a new cloud from a range image using metadata provided by the Ouster SDK. but I have minute errors in the values I got from the range image pointcloud and original cloud. I have uploaded two files original_cloud_df is my lidar data and valid_xyzrange_df is my pointcloud data from the range image.

valid_xyzrange_df.csv

original_cloud_df.csv

The below code is the logic I use for creating segmented pointcloud Can you help me with which steps have an error

roi_range_image = np.where(mask_bool,range_image,np.nan)
destaggered_image = client.destagger(self.sensor_info, roi_range_image, inverse=True)
destaggered_image_clean = np.nan_to_num(destaggered_image, nan=0)
xyz_points = self.xyzlut(destaggered_image_clean).reshape(-1, 3)
valid_xyz = xyz_points[~np.isnan(xyz_points).any(axis=1)]
valid_xyz_df = pd.DataFrame(valid_xyz, columns=['x', 'y', 'z'])
valid_xyz_df.to_csv('valid_xyz_df.csv', index=False)

I kept zero values for all points other than my ROI in range image and got a pointcloud and then used indices of point cloud data and filtered the original cloud to get exact points from the original cloud for my ROI. Both values were not equal and my output has changed a bit. Below is the image containing both ROI values left is my Original cloud and Right is my range image cloud.
Image

@Samahu
Copy link
Contributor

Samahu commented Jan 29, 2025

I have examined the two attached files and these are not minute errors but large differences check the point on line 800 for example:

  • In the original file it is:
-1.4494499,-7.730894,3.036977,958.0,76755912,8,0,236,8419

In the processed file it is:

-0.746823479205664,-2.8221716161501345,1.1471861170018771

These are not minute errors. there is some flow in your script that leads to that which is not clear from what you have shared.

How are you obtaining the range image from the driver by the way, is it from /ouster/points. Note that the driver publishes the destaggered point cloud by default.

@saikumar-kolla
Copy link
Author

Hello @Samahu

I have subscribed to the ouster/range_image topic and ouster/points topic

I have attached a text file. Please check the code and point me to where the problem occurred.

range_to_pointcloud.txt

I am using ROS Noetic and Python

@Samahu
Copy link
Contributor

Samahu commented Jan 29, 2025

The ouster/range_image is already in the destaggered form, I am not sure why did you had to stagger it by using destagger(inverse=True) then use xyzlut to convert the results to xyz point cloud and compare the results with the data from /ouster/points which publishes destaggered point cloud. It seems to me that the problem is you are comparing the results of a staggered vs destaggered point cloud.

There is another problem contributing to this issue which is, the /ouster/range_image topic uses 16 bits images to encode the range values this good since you can readily visualize the results in RVIZ with Image views, however, the full bit width of the RANGE data is 19 bits meaning there are 3 bits of precision thrown away during the encoding, checkout the note here:

// TODO: re-examine this truncation later
.

Luckily for you, I have this problem solved on a branch which you can check it out here #349. I haven't merged it out yet since I need to manage how to display 32-bit RANGE images in RVIZ.

Hope this help you solve the issue.

@saikumar-kolla
Copy link
Author

saikumar-kolla commented Feb 4, 2025

I'm sorry for not getting back to you sooner.

I used your suggestion to take the range image and directly passing to the xyzlut function which gave me a destaggered cloud but in rviz it looks like this

Image

and csv file is valid_xyzrange_df.csv

May I know why the destaggered range image cloud looks like this in rviz But when I stagger the image and then produce the cloud the pointcloud is good. but as you said the values are bad when compared to the original cloud data

Image

I also updated the image_processor.h file in the src folder by downloading the file from the branch you mentioned before and did catkin_make

@Samahu
Copy link
Contributor

Samahu commented Feb 4, 2025

I am not sure how you producing the PointCloud, probably a destagger is being performed during this step, which in this case you should provide a staggered range image.

Hope this helped!

@Samahu Samahu closed this as completed Feb 4, 2025
Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
enhancement New feature or request question Further information is requested
Projects
None yet
Development

No branches or pull requests

2 participants