HKUST-Aerial-Robotics / VINS-Mono

A Robust and Versatile Monocular Visual-Inertial State Estimator
GNU General Public License v3.0
4.96k stars 2.09k forks source link

Memory leak problem fixed #383

Open KopiSoftware opened 3 years ago

KopiSoftware commented 3 years ago

A memory leak problem confused me when I fuse object detection into vins fusion. The memory usage of loop_fusion node is increaseing without limitation, while vins estimator is okay. When settle down the camera and keep still, the memory usage gradually increases util my PC crashes. I found vins mono has similar issues, such as #237 #254. They think the reason for memory leak is that some objects in estimator.cpp are not completely released, which is different from my situation. I try to follow their solutions, but they just not work. So I begin to read the source code to locate the problem. Finally I found that a image queue named "image_buf" is continue increasing when camera stays in place. This queue is to receive image from ros publisher, so I wonder if it needs so much memory. Then I removed all the pictures item beyond 60 frames, then the bug is fixed. Here is my solution:

in loop_fusion/sec/pose_graph_node.cpp:

void process(){
...
m_buf.lock();
while(image_buf.size()>60) image_buf.pop();
if(!image_buf.empty() && !point_buf.empty() && !pose_buf.empty())
...
}

The cause of this problem is an engineering problem, the vins framework is okay. I think, the reason why earlier developers thought that the pointer in the program was not released completely is that the estimator and loop fusion of vins mono were integrated together, so it was not clear which part of the memory increased. When I run vins fusion, estimator and fusion are two difference nodes, and I saw the usage of loop fusion is increasing. However, the information given by the author of issue #237 is not enough, so the conclusion above is only my personal inference.

The memory usage will continue to grow but slowly. This is acceptable, because vins framework has to record pose graph information and so on.

Other solutions: You can also solve this problem when images pushed in, this may save some computational resources. When you do so, you have to deal with queue structure carefully, because old images and new images are all needed in the loop closure procedure. You can't simply pop out the front of queue or try to delete the rear of the queue which is not safe. You also shouldn't simply abandon new images beyond the limitation, since these images are used in the loop closure too. Dequeues are inefficient, I think vector is fit for the job.

KopiSoftware commented 3 years ago

Note that mapping frameworks, such as dense surfel mapping, also has the same problem. Adding input size limitation at ros subscriber can fix it too. In surfel mapping, they are image_input, color_input and depth_input My test shows that vins+surfel takes less than 4GB ram when continue running for 10min.

chobitsfan commented 1 year ago

Hi @KopiSoftware Thank you very much for fixing. It helps me a lot

YU-HSIANG-LAI commented 3 weeks ago

Hi, @KopiSoftware .Thank you for fixing. But if this function affects the loop closure result due to the lack of images? while(image_buf.size()>60) image_buf.pop();