Pointcloud behind objects get colored

classic Classic list List threaded Threaded
9 messages Options
Reply | Threaded
Open this post in threaded view
|

Pointcloud behind objects get colored

dinossht

Is there a good way to avoid coloring pointclouds behind other pointcloud clusters such as here?
Reply | Threaded
Open this post in threaded view
|

Re: Pointcloud behind objects get colored

dinossht
Reply | Threaded
Open this post in threaded view
|

Re: Pointcloud behind objects get colored

matlabbe
Administrator
Ho did you try to color the point cloud?

What could be happening is that if the camera image resolution is high and point cloud "sparse", it means that some background point may be "seen" by the camera between closer points. One way to avoid this would be to decrease resolution of the camera, so that background points are overridden by foreground points for same pixel in the camera image. Other solution is to change the distance policy to select closest camera to points instead of using the cameras with projected points closer to center of the camera.

Note that if the camera frame has also a corresponding depth image, it should ignore points that are too off the depth image values.
Reply | Threaded
Open this post in threaded view
|

Re: Pointcloud behind objects get colored

dinossht
I used rtabmap-export command with:
rtabmap-export \
--opt 2 \
--cloud \
--scan \
--cam_projection \
--cam_projection_keep_all \
--cam_projection_mask "path_to_lidar_mask_file" \
--voxel 0 \
--min_range 1.0 \
--max_range 20.0 \
--color_radius 0.1 \
--noise_radius 0.1 \
--output_dir output_dir \
--texture_range 0.0 \
db_file

Reply | Threaded
Open this post in threaded view
|

Re: Pointcloud behind objects get colored

dinossht
1. One way to avoid this would be to decrease resolution of the camera, so that background points are overridden by foreground points for same pixel in the camera image.

2. Other solution is to change the distance policy to select closest camera to points instead of using the cameras with projected points closer to center of the camera.

How does these methods help with this problem? Could you explain a bit more?
Reply | Threaded
Open this post in threaded view
|

Re: Pointcloud behind objects get colored

matlabbe
Administrator
You can give a try with different values for "--cam_projection_decimation" option. For each point, we search the best camera looking at it to attribute its color. If you have a sparse point cloud and high resolution image, the background points may be colored by foreground pixels. Here an example:


For the resolution setting, let's look at cam1 first (ignore cam2). On the left is the setup, the cam1 sees the top of the red table but cannot see most of the blue box under it. In the middle is how looks like the sparse point cloud if we project it on cam1. For each pixel, we color only the closest point projected in that pixel. Because the point cloud is sparse, some background points are "seen" in the camera, so some points of the blue box will be colored red. On the right, we decimated the camera image by 2, thus for all red pixels, there is a point on the table in them, so the background blue points are ignored by cam1.

The cam2 example is there to show the other option about the distance to cam policy ("--texture_d2c" option). In that case, most blue points are seen by cam2, even if some are seen by cam1 (at high resolution), they will still be colored by cam2.

cheers,
Mathieu
Reply | Threaded
Open this post in threaded view
|

Re: Pointcloud behind objects get colored

dinossht
Very clear explanation, thank you!. But wouldn't this also influence the density of the pointcloud exported using the rtabmap-export command? When I tested this using rtabmap-databaseViewer, I saw that the density was reduced when using decimated images..
Reply | Threaded
Open this post in threaded view
|

Re: Pointcloud behind objects get colored

matlabbe
Administrator
I re-tested and yeah, it would indeed influence the density of the point cloud. Only the best point per pixel is kept, so reducing the resolution means less points kept in the final cloud.

I revisited the implementation to still colorize close points to the closest one. The improved approach has been added in this commit.

By default, the old behavior is done, like the second image below. To enable it with rtabmap-export, use --texture_depth_error:
rtabmap-export --cloud --cam_projection --texture_depth_error 0.05 --cam_projection_decimation 16 rtabmap.db



In DatabaseViewer, the new option has been added under Camera Projection group:


cheers,
Mathieu
Reply | Threaded
Open this post in threaded view
|

Re: Pointcloud behind objects get colored

dinossht
Thank you!