introlab / rtabmap_ros

RTAB-Map's ROS package.
http://wiki.ros.org/rtabmap_ros
BSD 3-Clause "New" or "Revised" License
986 stars 555 forks source link

How to extract the images and odometry for the rtabmap reconstructed point cloud ? #389

Closed szx0112 closed 4 years ago

szx0112 commented 4 years ago

Hi @matlabbe ,

Thanks for your help. I have successfully create a 3D point cloud map of the sensing environment using multiple rgbd cameras with RTABMAP. I record the source images in a rosbag, and replay them to create the map.

Now, I am interesting to know if I can extract the color/depth images or the rgbd point cloud from the reconstructed map. That is, understand which frames are actually utilized in VO and mapping, and where those frames are located in the map. These allow me to do some object recognization tasks after the mapping, so I can also locate those recognized objects.

Currently, I am thinking to use the time stamp of VO and the raw rgbd images to link their connection, but haven't really work on it yet. Any comment would be really appreciate!

matlabbe commented 4 years ago

In rtabmap or rtabmap-databaseViewer, there are options in the File menu called Export images... or Extract images..., and Export poses....

Those are frames in the map. The frames of odometry are not saved (well some are saved in the map indirectly). Note that some exported poses format have a timestamp in it, other have ids.

szx0112 commented 4 years ago

@matlabbe Thanks for the reply.

Is it possible to get those image and the matched poses under ROS?

If current rtabmap_ros does not support such strategy, any suggestion I can modify it?

matlabbe commented 4 years ago

rtabmap_ros publishes /rtabmap/mapGraph topic, which contains all poses of the nodes in the map (those corresponding to each frame we can extract).

If you need all corresponding frames along with the poses, this can be done by calling the service /rtabmap/get_map_data with global=true, optimized=true and graphOnly=false.

For each NodeData, the RGB image is contained in this compressed array: https://github.com/introlab/rtabmap_ros/blob/master/msg/NodeData.msg#L19, it can be decoded using opencv image decoding function (same for depth image).

The local transform between base frame and the camera frame is contained here: https://github.com/introlab/rtabmap_ros/blob/7418cae8d3ef7fc44980b33e67eb0c0e3affc481/msg/NodeData.msg#L34

The corresponding optimized poses are there: https://github.com/introlab/rtabmap_ros/blob/7418cae8d3ef7fc44980b33e67eb0c0e3affc481/msg/MapData.msg#L7

cheers, Mathieu

szx0112 commented 4 years ago

Got you @matlabbe

I am able to successfully extract the color/depth images and poses from rtabmap GUI. However, even though they have exact same number, the images are named as IDs while the Poses are named as time-stamps I guess. I have tried all the available options (raw format, RGBD-SLAM format, KITTI format, ...) for pose extraction, but none of them can exported IDs.

It is fine if they are pairwisely matchable, I can just loop through them and pair them one by one. Please let me know if there is a better solution.

Overall, thank you very much for the help!

And I am going to close this issue now.

szx0112 commented 4 years ago

Hi @matlabbe,

I have a follow-up question related to the node (pose and saved images) extraction. I'd like to control the number/density of nodes (poses and correspondent images) collected in the graph. Actually I'd like to have a denser nodes (pose-image correspondence) collected from the map, such that I can do more image-processing stuff.

My RGBD images are collected at high frame rate (30HZ) and the vehicle is moved in low speed (~1m/s). There are thoudsands of frames collected from the camera but the map only stored around 500 nodes. This is actually pretty good for online processing, but our focus is the post-processing (i.e. collected in rosbag and replay in a workstation) and pose-image correspondences collection.

I have read your paper 'long-term online multi-session graph-based splam with memory management'. I understand that the number of nodes (based on ID) created is controlled by the STM. And the paper mentioned that whether the newly created node should be merged with the previous one in the map is determined by 'whether the ratio of corresponding visual words between the nodes is specified by threhold Y' and 'if the robot is moving ('odometry pose are the same')'. Would you clarify which parameters in ROS actually control these effects?

In addiiton, in order to make rtabmap successfully process our rosbag (30-50GB with RGB-D images collected at 30FPS), we have to reduce the rate of rosbag play from 1/10 to 1/30 (e.g. 'rosbag play --clock -r 0.1 my.bag'). Play are normal speed will easily cause the odometry loss tracks. I believe internally either ROS or Rtabmap skip some frames due the processing or hard-disk constraints. I have played with some parameters in Rtabmap, such as DetectionRate, STM size, change odom and loop closure featureType, but none of them help. Any suggestion would be really appreciated~!

matlabbe commented 4 years ago

If you want to save all frames processed at the framerate of the odometry, set Rtabmap/DetectionRate to 0. Even doing so, all images will be saved to database but not all in the graph. To get them all in the graph, set RGBD/LinearUpdate to 0. If we don't move, the graph will still be growing.

What is the actual frame rate of odometry you can get on your computer? $ rostopic hz /rtabmap/odom

Unless you have a powerful computer, it is unlikely that rtabmap's odometry (with default parameters) will run at 30Hz. For example, if you set Odom/Strategy to 1 with Vis/CorType to 1, odometry will be computed faster, but less accurate.

Decreasing rosbag frame rate is a way to process all frames, it is more like an offline way to process images. When running in real-time, odometry tries to process images as fast as it could, otherwise frames are dropped.

If the camera is shaking fast at some point where multiple frames in a short period of time are needed to correctly track the features, of some important frames are dropped, the odometry will indeed be lost if it cannot track the features with less temporally close frames.

cheers, Mathieu

szx0112 commented 4 years ago

Thank you @matlabbe. I managed to get proper number of nodes by setting Rtabmap/DetectionRate to 0, as well as RGBD/LinearUpdate nad RGBD/AngularUpdate to half of the default value.

I tested the rosbag at regular rate, the rtabmap/odom is processed at ~8 HZ. The CPU usage is nearly 50%. If this is the hardware constraint, we may expect the frame drop (i.e. only 8 of 30 frames are processed by rtabmap).

When rosbag is played at 1/10 or 3/10, the 30HZ raw data becomes the 3HZ or 9HZ during the post-processing (close to the 8HZ limit). I believe this is the reason the rosbag have to performed in the reduced rate. Because some regions can cause occlusions and also contain textureless surface, skip frames at those regions may cause the lost tracking.

The F2F is expected to be faster as it only tracks/matches two images, but F2M (which uses SBA based on my understanding) is preferred in the project for accuracy priority.

I believe I am OK with current configuration so I am going to close this issue. However, I am still open for any better solutions/suggestions.

szx0112 commented 4 years ago

Hi @matlabbe , Just a quick question. It seems that the depth images exported by the rtabmapviz are normalized to the image format (0~255). Is it possible to directly export the real depth values from the rtabmap? If not, I am going to write by myself. Thanks.

matlabbe commented 4 years ago

Do you mean when you right-click on the view, or when doing File->Export Images...?

szx0112 commented 4 years ago

Got it. I mistakenly convert the image to uint8. Thanks.