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

large kitti data map(or LoopClosure) make rtabmap_ros and the whole ubuntu crash!

asked 2019-08-07 06:08:07 -0600

lixz123007 gravatar image

updated 2019-08-22 22:04:54 -0600

I successfuly run rtabmap_ros by kitti2rosbag(kitti_to_rosbag),if kitti data is not such large.(less than 2500 pictures) But i want do "Visual Odometry / SLAM Evaluation 2012".So i download odometry data set sequence 00 which is "2011_10_03_drive_0027 (17.6 GB) Length: 4550 frames (07:35 minutes)" ,make it to rosbag( it is 25.8G by kitti2rosbag,37G!!!!!by kitti_to_rosbag). And i run it by Mathieu ' code (thanks to him again and again and agin)

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" approx_sync:=true use_sim_time:=true frame_id:=base_link

it is normal in first 2000 pictures ,but when it comes to 2400.it just stocked! And my whole ubuntu system die ,sometime my mouse can move.But and keboard is useless.Even the numlock is useless! The light of numlock is not change ,if i press it .I try to wait ,but 3hours passed ,nothing changes . And ,i change some parameter of launch files like:

<!-- maximum features map size, default 2000 -->
<param name="OdomF2M/MaxSize" type="string" value="5000"/>

But it is useless too. And i use ORB2-slam as odom too.But both orb mode and rgbd_odom mode are useless.

----------------------------------------------------------sovled------------------------------------------------------------ new question : image description

----------------------------------------------------------sovled------------------------------------------------------------ -------------new questions:!!! I try to export the poses and compare with kitti ground truth(4541 frames).I find the poses i exported from rtabmap are key frames(454 frames).But mostly every tools need same frame number,when they compare the ground truth. So I try to change some settings : settings First i set the rate in picture to 10,and run it .The whole ubuntu system stocked again.(I have changed set the ROI ratios to "0.001 0.0 0.0 0.0")And i try to another way: uncheck "Show 3D clouds map" .It worked in some kind of way .But it seems not be LoopClosure optimization or something.It looks bad and has a some breakpoints .I think maybe uncheck "show 3D clouds map" will close loopclosure optimization. Next i try set the rate and buffer size in picutre to 0,and open the "Show 3D clouds map" and "Create intermediate nodes if odometry is faster than the detection rate.".In case the suddenly stock ,i use htop to watch the RAM .Guess what ? picture below is the last picture of ubuntu .It stock when i remain 10G free ram! I cannot understand why? last picture My teacher tells me ,it is unnecessary to make every frames because key frames,is it possible for rtabmap? If it can ,It is also unnecessary to know why system stocked.But if it cannot , i think i have to know how to avoid system stocked. Any suggestion about it is OK ! Thanks!

edit retag flag offensive close merge delete

2 Answers

Sort by ยป oldest newest most voted
2

answered 2019-08-13 14:38:24 -0600

matlabbe gravatar image

updated 2022-12-05 10:53:32 -0600

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 ... (more)

edit flag offensive delete link more

Comments

It works!Thanks you!!!!Again and Again But i still have a questions:will changing ROI ratios low down the quality of finial 3d point cloud?

lixz123007 gravatar image lixz123007  ( 2019-08-15 08:10:37 -0600 )edit

Another problem!!!I updated a new picture in question ,you can see they are not in same high level! Is it the problem of ORB odom(my odometry has changed to ORB_slam2 )?OR it is the problem of the whole rtabmap?

lixz123007 gravatar image lixz123007  ( 2019-08-15 09:16:09 -0600 )edit

For your first question, no the quality of the point cloud won't change, we only remove 1 line from the image. For the second question, it seems loop closures are not detected or rejected (red background under loop closure detection panel). There should be warnings on terminal telling that loop closures are rejected with some reasons, what are they ?

matlabbe gravatar image matlabbe  ( 2019-08-17 10:25:55 -0600 )edit

This time it was better,but it was still have two a little high level differences. But it run by rtabmap's odometry not orbslam2 . And it shown :

    Rtabmap.cpp:2912::process() Rejecting all added loop closures (1, first is 448 <-> 3) in this iteration because a wrong loop closure has been detected after graph optimization, resulting in a maximum graph error ratio of 8.306853 (edge 96->97, type=0, abs error=2.340500 m, stddev=0.281755). The maximum error ratio parameter "RGBD/OptimizeMaxError" is 3.000000 of std deviation.

[ WARN] (2019-08-18 22:16:02.473) Rtabmap.cpp:2946::process() Loop closure 448->3 rejected!

I will try orb_slam soon.

lixz123007 gravatar image lixz123007  ( 2019-08-18 09:24:20 -0600 )edit

For those datasets, there are rarely wrong loop closure detections, you may turn off graph deformation verification "--RGBD/OptimizeMaxError 0"

matlabbe gravatar image matlabbe  ( 2019-08-18 09:45:43 -0600 )edit

I just finished the orb_slam2 as odometry(just like in picture).It is very different.Orb_slam as odometry is worse than rtabmap as odometry.They get same error.And next i will try '--RGBD/OptimizeMaxError 0' in both two odometry. Emm!!!It just works !No different high level! But why??

lixz123007 gravatar image lixz123007  ( 2019-08-19 00:11:04 -0600 )edit

With --RGBD/OptimizeMaxError 0, all loop closures are accepted, so it is why you don't see two levels, the graph is correctly optimized. A wrong loop closure would create large deformations in the graph. This parameter is used to avoid wrong loop closures by checking how much the graph is deformed after optimization with the new constraint. We may not have exactly the same build and/or not all images are processed on your computer (do you have >= 10 Hz odometry?), so that constraints may have different covariances, making reject some loop closures.

matlabbe gravatar image matlabbe  ( 2019-08-19 09:03:17 -0600 )edit

Thanks,it can work anyway! Actually,i ran my rosbag as 10 times slower than normally speed (-r 0.1),or it will always lost in orbslam odometry mode !Maybe it was related. In short ,Thank you again!

lixz123007 gravatar image lixz123007  ( 2019-08-19 20:59:03 -0600 )edit
0

answered 2022-12-04 00:56:21 -0600

divi@04 gravatar image

Have you changed any individual parameters for visual odometry apart from odometry rate and image buffer? My odometry fails at around 35 seconds (right after first 2 turns). Can anyone help with it? I have different parameters. still I am not able to get any improvements, if someone has worked on this data with RTABMAP package, please let me know what specific parameters are you tuning to get the results.

Error Message:: [ WARN] (2022-12-04 01:49:15.282) OdometryF2M.cpp:557::computeTransform() Registration failed: "Not enough inliers 0/20 (matches=57) between -1 and 367"

edit flag offensive delete link more

Comments

1

Question Tools

2 followers

Stats

Asked: 2019-08-07 06:08:07 -0600

Seen: 1,079 times

Last updated: Dec 05 '22