databaseViewer and RAM management

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

databaseViewer and RAM management

Mikor
Hello Mathieu,

I have an issue when I am trying to export and/or view large maps from the databaseViewer. The thing is that the RAM gets full and the app is killed and I am trying to figure out how to cope with this because it seems the only way is to increase the voxel size or reduce the range of points that gets colored (I am using a lidar and cameras to paint the cloud), and this is not ideal because I can only export very small parts of the area I am trying to map.

Any idea how to cope with this?

Also, I would like to know where can I find some info about the database and how to use the data stored in there, for example, is it possible to change the tf data inside the database or can I export images from it ?

Thank you in advance !!
Reply | Threaded
Open this post in threaded view
|

Re: databaseViewer and RAM management

matlabbe
Administrator
Hi,

You may try rtabmap-export CLI instead to see if less RAM is used. It has also --xmin,--xmax,--ymin,--ymax,--zmin,--zmax options to limit the size of the export, so a script could be used to call multiple times rtabmap-export with different areas, creating multiple point clouds that could be assembled afterwards. Here an example splitting an area (200m x 200m) in four (100m x 100m):
rtabmap-export --xmin -50 --xmax 50 --ymin -50 --ymax 50 --output section1 map.db
rtabmap-export --xmin 50 --xmax 150 --ymin -50 --ymax 50 --output section2 map.db
rtabmap-export --xmin 50 --xmax 150 --ymin 50 --ymax 150 --output section3 map.db
rtabmap-export --xmin -50 --xmax 50 --ymin 50 --ymax 150 --output section4 map.db

Otherwise, we would have to debug which step in https://github.com/introlab/rtabmap/blob/master/tools/Export/main.cpp uses too much RAM (maybe there are optimizations that could be done to avoid duplicated data in RAM).

Without adding more physical RAM to the computer, the SWAP could be increased.

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

Re: databaseViewer and RAM management

Mikor
Hi Mathieu,

sorry to bother you again, the thing is that when I try to export from the terminal it seems to fail to save the cloud because it contains 0 points

rtabmap-export --xmin -10 --xmax 10 --ymin -10 --ymax 10 --zmin -10 --zmax 10 --output section1 ~/.ros/peiramatozwo_rtabmap.db
Loading database "/home/antonis/.ros/peiramatozwo_rtabmap.db"...
Loading database "/home/antonis/.ros/peiramatozwo_rtabmap.db"... done (1.634707s).
Optimizing the map...
Optimizing the map... done (0.645100s, poses=240).
Filtering poses (range: x=-10.000000<->10.000000, y=-10.000000<->10.000000, z=-10.000000<->10.000000, map size=440.422638 x 139.740219 x 385.405853)...
Filtering poses... done! 8/240 remaining (new map size=2.018154 x 2.547761 x 7.832434).
Create and assemble the clouds...
Create and assemble the clouds... done (0.848917s, 0 points).
Export failed! The cloud is empty.

 but when I try to export from the GUI for the same area there are 8 nodes and their points.

Any idea why is this happening ? Also I attach the database, you can also paint the points from the cameras (I am still experimenting on the calibration techniques and this is why I was asking if I can change the TF information in order to check new calibration results without redoing the mapping).
Reply | Threaded
Open this post in threaded view
|

Re: databaseViewer and RAM management

matlabbe
Administrator
This post was updated on .
Hi,

The option --scan is missing, so no clouds were created because there are no depth images. I added a log in the console to remember to use --scan with laser scans.

I also optimized the RAM usage for camera projection. With your database, rtabmap-export should now use around 2GB instead of more than 10 GB.

Commit: https://github.com/introlab/rtabmap/commit/67710ef94ce0bfcd1478cd1490ad3c7690cfe6da

EDIT: for TF between base link and camera links, there is no easy way to do this by modifying the database's Data->calibration field. For example, the calibration field is deserialized like this from the sql BLOB. Serializing function of a single camera model is here. What you would want to do is to modify the local_transform part of the BLOB for each camera.

To debug scan/camera registration, you may use rtabmap_ros/pointcloud_to_depthimage node, then recreate the RGB-D cloud with point_cloud_xyzrgb node and visualize it in RVIZ.

cheers,
Mathieu