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

Export 3D point cloud without GUI via command line #918

Closed
mgow001 opened this issue Oct 26, 2022 · 15 comments
Closed

Export 3D point cloud without GUI via command line #918

mgow001 opened this issue Oct 26, 2022 · 15 comments

Comments

@mgow001
Copy link

mgow001 commented Oct 26, 2022

Hello,

I am looking for a way to export 3D point cloud without using RTAB-map GUI. I know that the standard way of exporting is by clicking through: File -> Export 3D clouds -> Save. However, in my use-case I cannot use the GUI and I am looking for a method that can be executed through the command line along with the parameters for exporting point cloud. Is there such a method or service?

Also, I know that the alternative option is to save point cloud via ROS topic rosrun pcl_ros pointcloud_to_pcd input:=/rtabmap/cloud_map but I'd like to avoid that if possible since it does not allow exporting 3D cloud using custom parameters.

Thanks!

@matlabbe
Copy link
Member

matlabbe commented Nov 7, 2022

Check rtabmap-export tool, you would find almost all options available in the GUI Export dialog.

rtabmap-export 

Usage:
rtabmap-export [options] database.db
Options:
    --output ""           Output name (default: name of the database is used).
    --output_dir ""       Output directory (default: same directory than the database).
    --ascii               Export PLY in ascii format.
    --las                 Export cloud in LAS instead of PLY (PDAL dependency required).
    --mesh                Create a mesh.
    --texture             Create a mesh with texture.
    --texture_size  #     Texture size 1024, 2048, 4096, 8192, 16384 (default 8192).
    --texture_count #     Maximum textures generated (default 1). Ignored by --multiband option (adjust --multiband_contrib instead).
    --texture_range #     Maximum camera range for texturing a polygon (default 0 meters: no limit).
    --texture_angle #     Maximum camera angle for texturing a polygon (default 0 deg: no limit).
    --texture_depth_error # Maximum depth error between reprojected mesh and depth image to texture a face (-1=disabled, 0=edge length is used, default=0).
    --texture_roi_ratios "# # # #" Region of interest from images to texture or to color scans. Format is "left right top bottom" (e.g. "0 0 0 0.1" means 10% of the image bottom not used).
    --texture_d2c         Distance to camera policy.
    --texture_blur #      Motion blur threshold (default 0: disabled). Below this threshold, the image is considered blurred. 0 means disabled. 50 can be good default.
    --cam_projection      Camera projection on assembled cloud and export node ID on each point (in PointSourceId field).
    --cam_projection_keep_all  Keep not colored points from cameras (node ID will be 0 and color will be red).
    --cam_projection_decimation  Decimate images before projecting the points.
    --cam_projection_mask ""  File path for a mask. Format should be 8-bits grayscale. The mask should cover all cameras in case multi-camera is used and have the same resolution.
    --poses               Export optimized poses of the robot frame (e.g., base_link).
    --poses_camera        Export optimized poses of the camera frame (e.g., optical frame).
    --poses_scan          Export optimized poses of the scan frame.
    --poses_format #      Format used for exported poses (default is 11):
                              0=Raw 3x4 transformation matrix (r11 r12 r13 tx r21 r22 r23 ty r31 r32 r33 tz)
                              1=RGBD-SLAM (in motion capture coordinate frame)
                              2=KITTI (same as raw but in optical frame)
                              3=TORO
                              4=g2o
                              10=RGBD-SLAM in ROS coordinate frame (stamp x y z qx qy qz qw)
                              11=RGBD-SLAM in ROS coordinate frame + ID (stamp x y z qx qy qz qw id)
    --images              Export images with stamp as file name.
    --images_id           Export images with node id as file name.
    --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.
    --min_cluster   #     When meshing, filter clusters of polygons with size less than this threshold (default 200, -1 means keep only biggest contiguous surface).
    --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).
    --multiband_downscale #   Downscaling reduce the texture quality but speed up the computation time (default 2).
    --multiband_contrib "# # # # "  Number of contributions per frequency band for the multi-band blending, should be 4 values! (default "1 5 10 0").
    --multiband_unwrap #      Method to unwrap input mesh: 0=basic (default, >600k faces, fast), 1=ABF (<=300k faces, generate 1 atlas), 2=LSCM (<=600k faces, optimize space).
    --multiband_fillholes     Fill Texture holes with plausible values.
    --multiband_padding #     Texture edge padding size in pixel (0-100) (default 5).
    --multiband_scorethr #    0 to disable filtering based on threshold to relative best score (0.0-1.0). (default 0.1).
    --multiband_anglethr #    0 to disable angle hard threshold filtering (0.0, 180.0) (default 90.0).
    --multiband_forcevisible  Triangle visibility is based on the union of vertices visibility.
    --poisson_depth #     Set Poisson depth for mesh reconstruction.
    --poisson_size  #     Set target polygon size when computing Poisson's depth for mesh reconstruction (default 0.03 m).
    --max_polygons  #     Maximum polygons when creating a mesh (default 300000, set 0 for no limit).
    --min_range     #     Minimum range of the created clouds (default 0 m).
    --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).
    --ground_normals_up  #  Flip ground normals up if close to -z axis (default 0, 0=disabled, value should be >0 and <1, typical 0.9).
    --noise_radius  #     Noise filtering search radius (default 0, 0=disabled).
    --noise_k       #     Noise filtering minimum neighbors in search radius (default 5, 0=disabled).
    --prop_radius_factor #  Proportional radius filter factor (default 0, 0=disabled). Start tuning from 0.01.
    --prop_radius_scale  #  Proportional radius filter neighbor scale (default 2).
    --random_samples #    Number of output samples using a random filter (default 0, 0=disabled).
    --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.
    --xmin #              Minimum range on X axis to keep nodes to export.
    --xmax #              Maximum range on X axis to keep nodes to export.
    --ymin #              Minimum range on Y axis to keep nodes to export.
    --ymax #              Maximum range on Y axis to keep nodes to export.
    --zmin #              Minimum range on Z axis to keep nodes to export.
    --zmax #              Maximum range on Z axis to keep nodes to export.
    --filter_ceiling #    Filter points over a custom height (default 0 m, 0=disabled).
    --filter_floor #      Filter points below a custom height (default 0 m, 0=disabled).

RTAB-Map options:
   --help                         Show usage.
   --version                      Show version of rtabmap and its dependencies.
   --params                       Show all parameters with their default value and description. 
                                  If a database path is set as last argument, the parameters in the 
                                  database will be shown in INI format.
   --"parameter name" "value"     Overwrite a specific RTAB-Map's parameter :
                                    --SURF/HessianThreshold 150
                                   For parameters in table format, add ',' between values :
                                    --Kp/RoiRatios 0,0,0.1,0
Logger options:
   --nolog              Disable logger
   --logconsole         Set logger console type
   --logfile "path"     Set logger file type
   --logfilea "path"    Set logger file type with appending mode if the file already exists
   --udebug             Set logger level to debug
   --uinfo              Set logger level to info
   --uwarn              Set logger level to warn
   --uerror             Set logger level to error
   --logtime "bool"     Print time when logging
   --logwhere "bool"    Print where when logging
   --logthread "bool"   Print thread id when logging

@mgow001
Copy link
Author

mgow001 commented Nov 9, 2022

Thank you for the reply. The rtabmap-export tool will work great. However, I was trying to find how to pass From RGB-D images parameter (screenshot below), but I could not find it in the available options. Could you let me know if this parameter is available in rtabmap-export and under what name it is? I need it in disabled state.

Thanks!

Screenshot from 2022-11-08 13-18-42

@mgow001
Copy link
Author

mgow001 commented Nov 18, 2022

Hello, just writing to follow-up on this. Is it possible to set From RGB-D images parameter using rtabmap-export tool? Thanks!

@matlabbe
Copy link
Member

Use --scan option

@mgow001
Copy link
Author

mgow001 commented Nov 28, 2022

That worked, thank you.

@mgow001 mgow001 closed this as completed Nov 28, 2022
@nirmalsnair
Copy link

Hi @matlabbe,

Is it possible to use a (.ini) config file with rtabmap-export?

I'm encountering an issue where exporting a textured (.obj) mesh via rtabmap-export results in a file without any faces. However, exporting through the GUI works correctly.

@matlabbe
Copy link
Member

The GUI dialog and rtabmap-export don't use the same code, so ini file is not supported with rtabmap-export (the options overlap, but I don't guarantee that all same options are in both). Make sure you use --mesh --texture options with rtabmap-export to create a textured mesh.

@nirmalsnair
Copy link

nirmalsnair commented May 26, 2024

Thanks @matlabbe, that explains the discrepancies between the GUI and CLI.

Running rtabmap-export --mesh --texture "new.db" results in a .obj file with no faces and no .mtl file.

GUI log
02:21:44 Clearing memory...
02:21:44 Clearing memory, done!
02:21:44 Connecting to database "C:/Users/centr/Documents/RTAB-Map GUI/new.db"...
02:21:44 Connecting to database "C:/Users/centr/Documents/RTAB-Map GUI/new.db", done!
02:21:44 Loading last nodes to WM...
02:21:44 Loading nodes to WM, done! (8 loaded)
02:21:44 Loading dictionary...
02:21:44 Loading dictionary, done! (1174 words)
02:21:44 Adding word references...
02:21:44 Adding word references, done! (2867)
02:21:47 Downloading the map (global=false ,optimized=true)...
02:21:47 Downloading the map... done.
02:21:47 poses = 8
02:21:47 constraints = 15
02:21:47 Inserting data in the cache (8 signatures downloaded)...
02:21:47 Inserted 8 new signatures.
02:21:47 Inserting data in the cache... done.
02:21:47 Updating the 3D map cloud...
02:21:47 Updated cloud 1 (1/8)
02:21:47 Updated cloud 2 (2/8)
02:21:47 Updated cloud 3 (3/8)
02:21:47 Updated cloud 4 (4/8)
02:21:47 Updated cloud 5 (5/8)
02:21:47 Updated cloud 6 (6/8)
02:21:47 Updated cloud 7 (7/8)
02:21:47 Updated cloud 8 (8/8)
02:21:47 Updating the 3D map cloud... done.
02:21:47 8 locations are updated to/inserted in the cache.

02:22:22 Copied cloud 1 from cache with 3072 points and 2382 indices (1/8).
02:22:22 Copied cloud 2 from cache with 3072 points and 2588 indices (2/8).
02:22:22 Copied cloud 3 from cache with 3072 points and 2597 indices (3/8).
02:22:22 Copied cloud 4 from cache with 3072 points and 2613 indices (4/8).
02:22:22 Copied cloud 5 from cache with 3072 points and 2518 indices (5/8).
02:22:22 Copied cloud 6 from cache with 3072 points and 2618 indices (6/8).
02:22:22 Copied cloud 7 from cache with 3072 points and 2446 indices (7/8).
02:22:22 Copied cloud 8 from cache with 3072 points and 2438 indices (8/8).
02:22:22 Assembling 8 clouds...
02:22:22 Assembled cloud 1, total=2382 (1/8).
02:22:22 Assembled cloud 2, total=4970 (2/8).
02:22:22 Assembled cloud 3, total=7567 (3/8).
02:22:22 Assembled cloud 4, total=10180 (4/8).
02:22:22 Assembled cloud 5, total=12698 (5/8).
02:22:22 Assembled cloud 6, total=15316 (6/8).
02:22:22 Assembled cloud 7, total=17762 (7/8).
02:22:22 Assembled cloud 8, total=20200 (8/8).
02:22:22 Voxelize cloud (20200 points, voxel size = 0.01 m)...
02:22:22 Voxelize cloud (20200 points, voxel size = 0.01 m)...done! (16083 points)
02:22:22 Poisson surface reconstruction...
02:22:22 Poisson depth resolution chosen is 7, map size (m) = 2x1x2
02:22:23 Mesh 0 created with 39812 polygons (1/1).
02:22:23 Transferring color from point cloud to mesh...
02:22:23 Texturing...
02:22:24 Computing visible faces per cam (30719 faces, 8 cams)
02:22:24 Processed camera 1/8: 1669 occluded and 177 spurious polygons out of 19827
02:22:24 Processed camera 2/8: 1784 occluded and 208 spurious polygons out of 19852
02:22:24 Processed camera 3/8: 1894 occluded and 234 spurious polygons out of 18152
02:22:24 Processed camera 4/8: 1928 occluded and 145 spurious polygons out of 17438
02:22:24 Processed camera 5/8: 1851 occluded and 152 spurious polygons out of 16466
02:22:24 Processed camera 6/8: 1462 occluded and 162 spurious polygons out of 14561
02:22:24 Processed camera 7/8: 1427 occluded and 117 spurious polygons out of 12866
02:22:24 Processed camera 8/8: 1848 occluded and 228 spurious polygons out of 14034
02:22:24 Texturing 30719 polygons...
02:22:24 Textured 9155/10000 of 30719 polygons
02:22:24 Textured 18073/20000 of 30719 polygons
02:22:24 Textured 27673/30000 of 30719 polygons
02:22:24 Cleaned texture mesh: 30719 -> 28291 polygons
02:22:24 TextureMesh 0 created [cameras=8] (1/1).
02:22:34 Saving the mesh (with 8 textures)...
02:22:34 Merging textures...
02:22:35 Merging textures... done.
02:22:36 Saving the mesh (with 1 textures)... done.
CLI log
PS C:\Users\centr> rtabmap-export --mesh --texture "C:\Users\centr\Documents\RTAB-Map CLI\new.db"

[W ..\torch\csrc\jit\codegen\cuda\interface.cpp:47] Warning: Loading nvfuser library failed with: error in LoadLibrary for nvfuser_codegen.dll. WinError 126: The specified module could not be found.
 (function LoadingNvfuserLibrary)
Loading database "C:\Users\centr\Documents\RTAB-Map CLI\new.db"...
Loading database "C:\Users\centr\Documents\RTAB-Map CLI\new.db"... done (0.058480s).
Optimizing the map...
Optimizing the map... done (0.005214s, poses=8).
Create and assemble the clouds...
Create and assemble the clouds... done (0.115425s, 20200 points).
Voxel grid filtering of the assembled cloud... (voxel=0.010000, 20200 points)
Voxel grid filtering of the assembled cloud.... done! (0.002228s, 16082 points)
Computing normals of the assembled cloud... (k=20, 16082 points)
Computing normals of the assembled cloud... done! (0.017429s, 16082 points)
Adjust normals to viewpoints of the assembled cloud... (16082 points)
Adjust normals to viewpoints of the assembled cloud... (0.009521s, 16082 points)
Mesh reconstruction... depth=7
Vertex pair not in list 2       [5] (9 16 5)
Mesh reconstruction... done (0.662250s, 40143 polygons).
Mesh color transfer (max polygons=300000, color radius=0.050000, clean=true)...
Failed to find match for field 'normal_x'.
Failed to find match for field 'normal_y'.
Failed to find match for field 'normal_z'.
Failed to find match for field 'rgb'.
Failed to find match for field 'curvature'.
Mesh color transfer... done (0.088507s).
Texturing 34549 polygons... robotPoses=8, cameraModels=8, cameraDepths=8
Computing visible faces per cam (34549 faces, 8 cams)
Processed camera 1/8: 2754 occluded and 295 spurious polygons out of 21881
Processed camera 2/8: 2914 occluded and 311 spurious polygons out of 21901
Processed camera 3/8: 3038 occluded and 346 spurious polygons out of 20181
Processed camera 4/8: 2986 occluded and 276 spurious polygons out of 19477
Processed camera 5/8: 3006 occluded and 240 spurious polygons out of 18293
Processed camera 6/8: 2581 occluded and 231 spurious polygons out of 16385
Processed camera 7/8: 2471 occluded and 162 spurious polygons out of 14869
Processed camera 8/8: 2943 occluded and 262 spurious polygons out of 15967
Texturing 34549 polygons...
Textured 8497/10000 of 34549 polygons
Textured 16734/20000 of 34549 polygons
Textured 25671/30000 of 34549 polygons
Texturing... done (0.505868s).
Cleanup mesh...
Cleanup mesh... done (0.053042s).
Merging 8 texture(s)... (1 max textures)
Merging to 1 texture(s)... done (0.859075s).
Saving texture to texture.jpg.
Saved texture.jpg.
Saving obj (20176 vertices) to C:\Users\centr\Documents\RTAB-Map CLI/new_mesh.obj.

The GUI and CLI input/output files are attached:
RTAB-Map GUI.zip [file redacted]
RTAB-Map CLI.zip [file redacted]

@matlabbe
Copy link
Member

It seems that the CLI is not done yet or crashed while writing the OBJ. The last log message should be:

Saved obj to C:\Users\centr\Documents\RTAB-Map CLI/new_mesh.obj!

We can see in the OBJ file that is was interrupted writing the last line:

vt 0.61655 0.88921
vt 0.61929 0.88837
vt 0.61884 0.89103
vt 0.61673 0.8

so the faces were not written yet, and even the MTL is missing (probably written after OBJ). I tried on my computer with rtabmap-export and the resulting mesh looks similar to your GUI one:
image

On your side, is rtabmap-export hanging at the end so you need to do ctrl-c? or just crash silently?

@nirmalsnair
Copy link

Thanks for testing the files.

On your side, is rtabmap-export hanging at the end so you need to do ctrl-c? or just crash silently?

No, rtabmap-export does not hang, it just returns to the prompt after
Saving obj (20176 vertices) to C:\Users\centr\Documents\RTAB-Map CLI/new_mesh.obj.

@nirmalsnair
Copy link

Your CLI output looks good, so it seems the issue might be with my installation or system specifications.

I tried RTAB-Map on the following two computers:

  1. Desktop running Windows 11 with RTX 2070 Super and RTABMap v0.21.4 CPU-only installer.
  2. Laptop running Windows 11 with RTX 4090 and RTABMap v0.21.4 (Tried on both CPU and CUDA installers)

Screenshot 2024-05-27 205331
Screenshot 2024-05-27 205314

Could you share the specifications of the system you are using and the version of RTAB-Map you have installed?

@matlabbe
Copy link
Member

matlabbe commented Jun 3, 2024

Thanks for testing the files.

On your side, is rtabmap-export hanging at the end so you need to do ctrl-c? or just crash silently?

No, rtabmap-export does not hang, it just returns to the prompt after Saving obj (20176 vertices) to C:\Users\centr\Documents\RTAB-Map CLI/new_mesh.obj.

So it is crashing silently... there could be an issue with PCL 1.14 on Windows (it is crashing inside a PCL function used to write OBJ). The machine specs should not matter. I tested on ubuntu 20.04.

Can you try version 0.21.0? It was built with PCL 1.13.

@nirmalsnair
Copy link

Thanks for your suggestion. I tried both RTABMap-0.21.0-win64-cuda11.7.exe and RTABMap-0.21.0-win64.exe, but unfortunately, exporting the 3D model does not work from either the CLI or the GUI. The face data is still not being fully written, resulting in the same incomplete output as before.

@matlabbe
Copy link
Member

matlabbe commented Jun 4, 2024

I reproduced your issue on Windows with these two versions. However, the 0.21.0 with old dependencies work: https://github.com/introlab/rtabmap/releases/download/0.21.0/RTABMap-0.21.0-win64-old_deps.zip, you may use this one till the bug is fixed (next release).

I'll open a new issue: #1296

@nirmalsnair
Copy link

Thank you very much! I tried the suggested file, and the mesh export is working fine for both the CLI and GUI.

Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
None yet
Projects
None yet
Development

No branches or pull requests

3 participants