ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | ros @ Robotics Stack Exchange
Ask Your Question

Revision history [back]

click to hide/show revision 1
initial version

Hi,

It seems to be a RAM problem. I tried on my computer with default parameters, and the memory used by rtabmapviz increases very fast! The problem is that the image size is 1241x376. Normally a decimation of the image is done before creating the dense point clouds (to not use so much memory for visualization). In this case the decimation cannot be done (1241 cannot be divided by 4, or 2, or 8), so the full point cloud is created for each node for visualization. This requires a lot of memory. Your computer may crash (or not respond) if the RAM and swap memory are full. The solution is to disable the point cloud rendering in rtabmapviz (uncheck "Show 3D clouds" in Preferences->3D Rendering) or set the ROI ratios under Map and Odom columns to "0.001 0.0 0.0 0.0" so that images are cropped to 1240x376 before creating the clouds (so that decimation is applied). Maximum depth under Map column can be set to 30 meters for a cleaner point cloud map. image description

Also the default grid parameters are tuned for indoor size maps, for such large maps they should be tuned, otherwise disable the occupancy grid by setting RGBD/CreateOccupancyGrid=false:

roslaunch rtabmap_ros rtabmap.launch stereo:="true" left_image_topic:=/kitti/camera_color_left/image_raw right_image_topic:=/kitti/camera_color_right/image_raw left_camera_info_topic:=/kitti/camera_color_left/camera_info right_camera_info_topic:=/kitti/camera_color_right/camera_info rtabmap_args:="--delete_db_on_start --RGBD/CreateOccupancyGrid false" approx_sync:=true use_sim_time:=true frame_id:=base_link

Then with the parameters above for rtabmapviz, I can get 1.6 GB RAM used at the end of the bag, instead of >>10 GB. rtabmap node should take around 675 MB. image description image description

Hi,

It seems to be a RAM problem. I tried on my computer with default parameters, and the memory used by rtabmapviz increases very fast! The problem is that the image size is 1241x376. Normally a decimation of the image is done before creating the dense point clouds (to not use so much memory for visualization). In this case the decimation cannot be done (1241 cannot be divided by 4, or 2, or 8), so the full point cloud is created for each node for visualization. This requires a lot of memory. Your computer may crash (or not respond) if the RAM and swap memory are full. The solution is to disable the point cloud rendering in rtabmapviz (uncheck "Show 3D clouds" in Preferences->3D Rendering) or set the ROI ratios under Map and Odom columns to "0.001 0.0 0.0 0.0" so that images are cropped to 1240x376 before creating the clouds (so that decimation is applied). Maximum depth under Map column can be set to 30 meters for a cleaner point cloud map. image description

Also the default grid parameters are tuned for indoor size maps, for such large maps they should be tuned, otherwise disable the occupancy grid by setting RGBD/CreateOccupancyGrid=false:

roslaunch rtabmap_ros rtabmap.launch stereo:="true" left_image_topic:=/kitti/camera_color_left/image_raw right_image_topic:=/kitti/camera_color_right/image_raw left_camera_info_topic:=/kitti/camera_color_left/camera_info right_camera_info_topic:=/kitti/camera_color_right/camera_info rtabmap_args:="--delete_db_on_start --RGBD/CreateOccupancyGrid false" approx_sync:=true use_sim_time:=true frame_id:=base_link

Then with the parameters above for rtabmapviz, I can get 1.6 GB RAM used at the end of the bag, instead of >>10 GB. rtabmap node should take around 675 MB. image description image description

EDIT To process all images, you should create the bag with exact stamps for both left and right images (copy image_00/timestamps.txt to image_01/timestamps.txt and image_02/timestamps.txt to image_03/timestamps.txt). Without the exact timestamps, we have to use approx_sync:=true and some images may be skipped. I tried and some images are still skipped. It is because rtabmap node is dropping images in the ROS sync queue if rtabmap takes more time than odometry update time. If you want to have exactly the same number of nodes in the graph than the number of images, we would have to launch the rosbag at 1/10 real-time or even less. This is quite inconvenient, so I suggest to use the offline rtabmap-kitti_dataset evaluation tool (which works with only odometry dataset though). The resulting database can be opened in rtabmap-databaseViewer to extract all poses.

Here is an example with the bag (not all images are processed, so the resulting graph is smaller).

roslaunch rtabmap_ros rtabmap.launch stereo:="true" left_image_topic:=/kitti/camera_color_left/image_raw right_image_topic:=/kitti/camera_color_right/image_raw left_camera_info_topic:=/kitti/camera_color_left/camera_info right_camera_info_topic:=/kitti/camera_color_right/camera_info rtabmap_args:="--delete_db_on_start --RGBD/CreateOccupancyGrid false --Rtabmap/ImageBufferSize 0 --Odom/ImageBufferSize 0 --Rtabmap/CreateIntermediateNodes true" approx_sync:=false use_sim_time:=true frame_id:=base_link queue_size:=100

For the memory problem, I have set "0.001 0.0 0.0 0.0" and decimation to 8, here is the final memory usage (with top, my computer has 32GB RAM to convert the pourcentage): image description

To fix rtabmap sync queue problem, we would have to create a different thread for rtabmap algorithm than the ros thread for managing callbacks, then buffering data in parallel to rtabmap thread (unless there is already a way to do that with the current ROS synchronization API -> buffering all reveived topics). Another approach is to launch rtabmap data_recorder.launch, record all data in rtabmap's database format, then reprocess it offline with rtabmap standalone app.

Hi,

It seems to be a RAM problem. I tried on my computer with default parameters, and the memory used by rtabmapviz increases very fast! The problem is that the image size is 1241x376. Normally a decimation of the image is done before creating the dense point clouds (to not use so much memory for visualization). In this case the decimation cannot be done (1241 cannot be divided by 4, or 2, or 8), so the full point cloud is created for each node for visualization. This requires a lot of memory. Your computer may crash (or not respond) if the RAM and swap memory are full. The solution is to disable the point cloud rendering in rtabmapviz (uncheck "Show 3D clouds" in Preferences->3D Rendering) or set the ROI ratios under Map and Odom columns to "0.001 0.0 0.0 0.0" so that images are cropped to 1240x376 before creating the clouds (so that decimation is applied). Maximum depth under Map column can be set to 30 meters for a cleaner point cloud map. image description

Also the default grid parameters are tuned for indoor size maps, for such large maps they should be tuned, otherwise disable the occupancy grid by setting RGBD/CreateOccupancyGrid=false:

roslaunch rtabmap_ros rtabmap.launch stereo:="true" left_image_topic:=/kitti/camera_color_left/image_raw right_image_topic:=/kitti/camera_color_right/image_raw left_camera_info_topic:=/kitti/camera_color_left/camera_info right_camera_info_topic:=/kitti/camera_color_right/camera_info rtabmap_args:="--delete_db_on_start --RGBD/CreateOccupancyGrid false" approx_sync:=true use_sim_time:=true frame_id:=base_link

Then with the parameters above for rtabmapviz, I can get 1.6 GB RAM used at the end of the bag, instead of >>10 GB. rtabmap node should take around 675 MB. image description image description

EDIT To process all images, you should create the bag with exact stamps for both left and right images (copy image_00/timestamps.txt to image_01/timestamps.txt and image_02/timestamps.txt to image_03/timestamps.txt). Without the exact timestamps, we have to use approx_sync:=true and some images may be skipped. I tried and some images are still skipped. It is because rtabmap node is dropping images in the ROS sync queue if rtabmap takes more time than odometry update time. If you want to have exactly the same number of nodes in the graph than the number of images, we would have to launch the rosbag at 1/10 real-time or even less. This is quite inconvenient, so I suggest to use the offline rtabmap-kitti_dataset evaluation tool (which works with only odometry dataset though). The resulting database can be opened in rtabmap-databaseViewer to extract all poses.

Here is an example with the bag created with kitti2bag (not all images are processed, so the resulting graph is smaller).

roslaunch rtabmap_ros rtabmap.launch stereo:="true" left_image_topic:=/kitti/camera_color_left/image_raw right_image_topic:=/kitti/camera_color_right/image_raw left_camera_info_topic:=/kitti/camera_color_left/camera_info right_camera_info_topic:=/kitti/camera_color_right/camera_info rtabmap_args:="--delete_db_on_start --RGBD/CreateOccupancyGrid false --Rtabmap/ImageBufferSize 0 --Odom/ImageBufferSize 0 --Rtabmap/CreateIntermediateNodes true" approx_sync:=false use_sim_time:=true frame_id:=base_link queue_size:=100

For the memory problem, I have set "0.001 0.0 0.0 0.0" and decimation to 8, here is the final memory usage (with top, my computer has 32GB RAM to convert the pourcentage): image description

To fix rtabmap sync queue problem, we would have to create a different thread for rtabmap algorithm than the ros thread for managing callbacks, then buffering data in parallel to rtabmap thread (unless there is already a way to do that with the current ROS synchronization API -> buffering all reveived topics). Another approach is to launch rtabmap data_recorder.launch, record all data in rtabmap's database format, then reprocess it offline with rtabmap standalone app.

Hi,

UPDATE 2022: See also a summary of all instructions below here.

It seems to be a RAM problem. I tried on my computer with default parameters, and the memory used by rtabmapviz increases very fast! The problem is that the image size is 1241x376. Normally a decimation of the image is done before creating the dense point clouds (to not use so much memory for visualization). In this case the decimation cannot be done (1241 cannot be divided by 4, or 2, or 8), so the full point cloud is created for each node for visualization. This requires a lot of memory. Your computer may crash (or not respond) if the RAM and swap memory are full. The solution is to disable the point cloud rendering in rtabmapviz (uncheck "Show 3D clouds" in Preferences->3D Rendering) or set the ROI ratios under Map and Odom columns to "0.001 0.0 0.0 0.0" so that images are cropped to 1240x376 before creating the clouds (so that decimation is applied). Maximum depth under Map column can be set to 30 meters for a cleaner point cloud map. image description

Also the default grid parameters are tuned for indoor size maps, for such large maps they should be tuned, otherwise disable the occupancy grid by setting RGBD/CreateOccupancyGrid=false:

roslaunch rtabmap_ros rtabmap.launch stereo:="true" left_image_topic:=/kitti/camera_color_left/image_raw right_image_topic:=/kitti/camera_color_right/image_raw left_camera_info_topic:=/kitti/camera_color_left/camera_info right_camera_info_topic:=/kitti/camera_color_right/camera_info rtabmap_args:="--delete_db_on_start --RGBD/CreateOccupancyGrid false" approx_sync:=true use_sim_time:=true frame_id:=base_link

Then with the parameters above for rtabmapviz, I can get 1.6 GB RAM used at the end of the bag, instead of >>10 GB. rtabmap node should take around 675 MB. image description image description

EDIT To process all images, you should create the bag with exact stamps for both left and right images (copy image_00/timestamps.txt to image_01/timestamps.txt and image_02/timestamps.txt to image_03/timestamps.txt). Without the exact timestamps, we have to use approx_sync:=true and some images may be skipped. I tried and some images are still skipped. It is because rtabmap node is dropping images in the ROS sync queue if rtabmap takes more time than odometry update time. If you want to have exactly the same number of nodes in the graph than the number of images, we would have to launch the rosbag at 1/10 real-time or even less. This is quite inconvenient, so I suggest to use the offline rtabmap-kitti_dataset evaluation tool (which works with only odometry dataset though). The resulting database can be opened in rtabmap-databaseViewer to extract all poses.

Here is an example with the bag created with kitti2bag (not all images are processed, so the resulting graph is smaller).

roslaunch rtabmap_ros rtabmap.launch stereo:="true" left_image_topic:=/kitti/camera_color_left/image_raw right_image_topic:=/kitti/camera_color_right/image_raw left_camera_info_topic:=/kitti/camera_color_left/camera_info right_camera_info_topic:=/kitti/camera_color_right/camera_info rtabmap_args:="--delete_db_on_start --RGBD/CreateOccupancyGrid false --Rtabmap/ImageBufferSize 0 --Odom/ImageBufferSize 0 --Rtabmap/CreateIntermediateNodes true" approx_sync:=false use_sim_time:=true frame_id:=base_link queue_size:=100

For the memory problem, I have set "0.001 0.0 0.0 0.0" and decimation to 8, here is the final memory usage (with top, my computer has 32GB RAM to convert the pourcentage): image description

To fix rtabmap sync queue problem, we would have to create a different thread for rtabmap algorithm than the ros thread for managing callbacks, then buffering data in parallel to rtabmap thread (unless there is already a way to do that with the current ROS synchronization API -> buffering all reveived topics). Another approach is to launch rtabmap data_recorder.launch, record all data in rtabmap's database format, then reprocess it offline with rtabmap standalone app.