-
Notifications
You must be signed in to change notification settings - Fork 4.8k
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
Generate a colorized PCL point cloud #1143
Comments
Hi @summer1216 , you're almost there, after creating the points and mapping the color texture to them just like you've done, you can use librealsense/examples/example.hpp Lines 268 to 279 in 489c9a6
|
@zivsha thank you very much for your reply. I guess I miss the knowledge of texture coordinates, I don't know what it is, and couldn't understand immediately after google it. Since I don't need to use openGL at all, I just want the r, g, b, values of the points. Is there a conversion which can convert the 'texture coordinates' directly to rgb values? Thank you! |
Hi @summer1216 , librealsense/src/proc/pointcloud.cpp Line 178 in 9437bc2
librealsense/src/proc/pointcloud.cpp Line 37 in 9437bc2
As you can see we take the pixel's (x,y) and devise it by the width and height of the image to get a normalized value between [0,1] (well actually, this could be <0 or >1 since the projection might suffer from distortions - such values should be discarded when you revert the process). |
@zivsha Thank you very much. Your explanation is clear and very helpful. Now I have achieved the colorized point cloud by using PCL. But I still have small problems I need to handle with: (1)The values from get_texture_coordonates() are negative, I need to change them to the opposite number. (2)My rgb and depth image do not have 100% the same view, the not matched parts need to be excluded. But the main question is solved and this issue can be closed. Thanks again! |
Hello, d_intrinsics = depth_stream.asrs2::video_stream_profile().get_intrinsics(); void CreatePointCloud(pcl::PointCloudpcl::PointXYZRGB::Ptr cloud, std::vector<uint16_t> vec_depth, std::vector<uint8_t> vec_color, int sz_depth = vec_depth.size(); // cloud->resize(sz_depth);
// int udepth = i % d_intrinsics.width;
// cloud->points[i] = p; // cloud->resize(actual_size); auto end = std::chrono::high_resolution_clock::now(); |
I think I understood the problem. It seems to me that the viewer colorizes in some way (perhaps the closest valid pixel) the points where the retroprojection on the RGB sensor is not valid. |
[Realsense Customer Engineering Team Comment] |
Yes, thank you. |
@summer1216 Hello. I faced the similar problem for the colored point cloud (but I am coding in python). What is your solution of solving the problems like |
I stumbled across a similar issue when trying to add texture mapping to an example of librealsense-rust. It wasn't until I found #6234 that I got it to work. This comment gave it away:
In my case, the texture coordinates are reported as int32 values, but they really appear to be 32-bit floating points. By re-interpreting It does feel a bit weird that the UV coordinates are presented as |
I have already generated a live PCL point cloud but in the form of pcl::PointCloud < pcl::PointXYZ >, that means, with no color information. I want to have that in pcl::PointCloud < pcl::PointXYZRGB > form.
What I have done:
I used the following code to generate the rs2::pointcloud,
and I used points.get_vertices() to get the x,y,z values of each point and write them to PCL point cloud. However, I couldn't find any method that I can get the color information (r, g, b values) at each point.
I tried to use rs2::align and rs2_project_point_to_pixel to map the 3D point to the Point in color image, but I still don't know how I can get the r,g,b value of a given point in color image.
What is the best way to do that? Thank you!
The text was updated successfully, but these errors were encountered: