How can I capture point clouds with highest density possible?

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

How can I capture point clouds with highest density possible?

FeriBolour
Hey Guys,
I just asked another question on this forum and mentioned that I've been facing some problems in the project that I'm working on using RTabMap. This post is for the second question that I had. Again I really appreciate all the help.

So in summary, I'm fairly new with RTabMap. I've been working with RTabMap using a D435i sensor based on the tutorial given by Intel,
https://github.com/IntelRealSense/realsense-ros/wiki/SLAM-with-D435i

And I am using
$ roslaunch realsense2_camera opensource_tracking.launch

I'm currently working on a project which deals with Autonomous 3D scanning of Cotton Plants and then using segmentation networks to detect the Cotton Bolls. Therefore the robot is not going to move in a loop and it is just going to move on a straight path with a constant speed (Assuming speed is a variable that I can control). It is very important to us that our point clouds be as high in density as possible. Right now, after I'm downloading the map graph from Rviz and extracting it from ~/.ros/rtabmap.db, I am setting the voxel size to 0 and decimation to lowest possible as well. And the result is fairly dense. I wanted to know if the density can get any higher? Is there any other parameter than I can work with that will increase the density even more without ruining anything else? like the quality of the point cloud.

Also is there a way to extract the point cloud automatically (for example using a command) to export the point cloud from the database without needing to manually open the standalone app from rtabmap.

Again, thank you for your help
Reply | Threaded
Open this post in threaded view
|

Re: How can I capture point clouds with highest density possible?

matlabbe
Administrator

Hi,

With voxel=0 and decimation set to 1, the remaining limitation to point cloud density is the resolution of the depth image.

To export the assembled point cloud offline:
rtabmap-export --voxel 0 ~/.ros/rtabmap.db

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

Re: How can I capture point clouds with highest density possible?

FeriBolour
Hello Mathieu.
I have been using your method and it works perfectly so thank you!
However, I also wanted to change the Cloud Maximum Depth but I can not figure out how to pass the corresponding parameter to your suggested command.
In RTabMap's export settings, this parameter seems to be called "regenerate_max_depth." But I have not been able to change the value of this parameter through your command. Could you please let me know if it is possible to do that if yes, how?

Thank You
Farshad
Reply | Threaded
Open this post in threaded view
|

Re: How can I capture point clouds with highest density possible?

matlabbe
Administrator
$ rtabmap-export --help

Usage:
rtabmap-exportCloud [options] database.db
Options:
    --mesh                Create a mesh.
    --texture             Create a mesh with texture.
    --texture_size  #     Texture size (default 4096).
    --texture_count #     Maximum textures generated (default 1).
    --texture_range #     Maximum camera range for texturing a polygon (default 0 meters: no limit).
    --texture_d2c         Distance to camera policy.
    --ba                  Do global bundle adjustment before assembling the clouds.
    --gain          #     Gain compensation value (default 1, set 0 to disable).
    --gain_gray           Do gain estimation compensation on gray channel only (default RGB channels).
    --no_blending         Disable blending when texturing.
    --no_clean            Disable cleaning colorless polygons.
    --low_gain      #     Low brightness gain 0-100 (default 0).
    --high_gain     #     High brightness gain 0-100 (default 10).
    --multiband           Enable multiband texturing (AliceVision dependency required).
    --poisson_depth #     Set Poisson depth for mesh reconstruction.
    --max_polygons  #     Maximum polygons when creating a mesh (default 500000, set 0 for no limit).
    --max_range     #     Maximum range of the created clouds (default 4 m, 0 m with --scan).
    --decimation    #     Depth image decimation before creating the clouds (default 4, 1 with --scan).
    --voxel         #     Voxel size of the created clouds (default 0.01 m, 0 m with --scan).
    --color_radius  #     Radius used to colorize polygons (default 0.05 m, 0 m with --scan). Set 0 for nearest color.
    --scan                Use laser scan for the point cloud.
    --save_in_db          Save resulting assembled point cloud or mesh in the database.

It would be max_range:
rtabmap-export --voxel 0 --max_range 0 ~/.ros/rtabmap.db

EDIT: In the ui, make sure to check regenerate clouds and the "3D cloud maximum depth" option will show up:


cheers,
Mathieu