tum-vision / LDSO

DSO with SIM(3) pose graph optimization and loop closure
GNU General Public License v3.0
670 stars 236 forks source link

Problem with loop closing #60

Closed gauti1311 closed 2 years ago

gauti1311 commented 4 years ago

Hi @NikolausDemmel ,

  1. I am facing the issue with CorrectLoop function in LoopClosing.cc .In line 280 activepixels is defined but it is not being added to anywhere and then it is used at line 306 which is not working. and i found the inverse depth always equals to zero.

  2. one more clarification about the 3d and points used in solvePnPRansac are both calcualted with diferrent frames i.e 3d points using candidate frame and 2d points from current frame here and here.

thank you.

mgladkova commented 3 years ago

Hi @gauti1311 , maybe I can comment on these questions a bit, since I worked with the code before.

  1. activepixels vector is indeed not populated and the loop in line 306 should not run at all. If you would like a dilated depth map, you can add elements to the vector by inserting activePixels.push_back(Vec2(u, v)) into the line 297. If the inverse depth map entries are all zero, it can be that your matches vector is empty or it contains only outliers or invalid features.
  2. I am not sure about your question here, I can try to give you a general perspective and you see if it matches your understanding. The goal of solvePnPRansac function is to compute the relative transformation between a reference frame and a current frame. 3D points are expressed in the reference coordinate system, 2D points are local to the current image. When passing the feature vectors to the function, It is important that each 3D point from the reference frame has a corresponding 2D coordinate in the current frame.
gauti1311 commented 3 years ago

Hi @mgladkova , thanks for the reply, but when i don't have dilated depth map then i can't find the loop closure. Can you give me some hint if there is any other parameters which are too strict for loop closing.

mgladkova commented 3 years ago

The only parameter that comes to my mind is setting_pointSelection in ine 125 which should be 1 to enable the loop closure. You can also try to increase the number of extracted features (setting_desiredImmatureDensity parameter) in line 29.

Nevertheless, I would recommend to first visualize your candidate frames and get an insight if a loop closure candidate is good. Maybe it's worth querying more than 1 candidate in the database call here. If the candidates seem reasonable, look into the feature matches and check if there are many good ones.

Please note that both the loop candidate query and feature matching are done using Bag-of-Visual-Words representations. If you are using your own dataset (neither KITTI nor EuroC nor TUM Mono) it might be helpful to train your own vocabulary instead of using the provided orbvoc.dbow3.