Code Monkey home page Code Monkey logo

Comments (14)

raulmur avatar raulmur commented on August 27, 2024

Your question is very interesting. Let me explain what is happening.

Camera pose can experience a jump, if the MapPoints that are used for tracking the camera, suffer a significant correction. When a loop is closed two optimizations are performed:

  1. Essential Graph Optimization: This is a pose graph optimization that distributes the error in the relative pose between the current KeyFrame and a loop closing KeyFrame (an old KeyFrame in your map). In this optimization, the loop closing KeyFrame is fixed, and the rest of KeyFrames are corrected. After the optimization, the MapPoints are corrected according to the corrections of their reference KeyFrames. That means that MapPoints seen by current KeyFrame (and very likely seen by your current camera) will be corrected, as the current KeyFrame pose will be corrected. A way to avoid a jump on the camera, is to fix the current KeyFrame instead of the loop closing KeyFrame. You can change this in line: https://github.com/raulmur/ORB_SLAM2/blob/master/src/Optimizer.cc#L834-L835 , so that the surroundings of the current KeyFrame are not moved by the optimization.

  2. Global bundle adjustment corrects all KeyFrames and all MapPoints fixing the initial KeyFrame (the KeyFrame with id 0). Again to avoid a change in the surroundings of your current KeyFrame, fix the current KeyFrame instead of the initial KeyFrame: https://github.com/raulmur/ORB_SLAM2/blob/master/src/Optimizer.cc#L79 . To do this, you will need to add an argument to the Bundle Adjustment function to tell which KeyFrame has to be fixed.

EDIT: You already know with which KF the loop was detecteded. nLoopKF in BundleAdjustment function.

from orb_slam2.

antithing avatar antithing commented on August 27, 2024

Thank you! That makes sense. So I need to store the current keyframe, and then for the Essential Graph Optimization:

if(pKF==currentKeyframe)
VSim3->setFixed(true);

and for the Global:

vSE3->setFixed(currentKeyframe);

Is this correct?

Is there a function existing to find the current camera keyframe? Or is it the last entry in the keyframes list?

Thank you again, very much appreciated.

from orb_slam2.

raulmur avatar raulmur commented on August 27, 2024

You already know which is the keyframe for which you detect the loop. This is the keyframe with index nLoopKF in BundleAdjustment function. However as the Global BA can take a significant time you will be fixing a keyframe that is far away from your current camera an therefore the camera can still experience a jump. You have two options here:

from orb_slam2.

antithing avatar antithing commented on August 27, 2024

Awesome. Thank you yet again for your help!

from orb_slam2.

antithing avatar antithing commented on August 27, 2024

Hi, sorry to keep bothering you... I have made the edits you suggested (without disabling BA) and slam is running great. Thank you! When i measure the tracked distance against a real world ground truth though, the accuracy is quite far off. A movement in Z or X of 1 meter reads as 1.15 meters in the slam system. What could i look at to improve the accuracy of the distance measured? (I am using a Zed stereo camera, with the factory calibrated settings for intrinsics and baseline)

thank you yet again.

from orb_slam2.

raulmur avatar raulmur commented on August 27, 2024

You need to rectify the stereo images

from orb_slam2.

antithing avatar antithing commented on August 27, 2024

Hi, and thanks again for your time. The images are synchronised,
rectified and undistorted already. What else could be my problem?
On 10 Mar 2016 08:50, "Raul Mur-Artal" [email protected] wrote:

You need to rectify the stereo images


Reply to this email directly or view it on GitHub
#33 (comment).

from orb_slam2.

raulmur avatar raulmur commented on August 27, 2024

Make sure you are providing correctly the calibration, especially bf parameter (baseline*fx).
At which distance is the camera with respect the scene?

from orb_slam2.

antithing avatar antithing commented on August 27, 2024

The camera is around 3 meters from a desk, with a wall behind it. I have tried a few different locations around the room and see pretty much the same error. I am using the camera rigs on board self calibration values, so will maybe try a new manual opencv stereocalibrate instead to get the baseline exact.
Thank you yet again!

from orb_slam2.

durn2000 avatar durn2000 commented on August 27, 2024

antithing, I am looking at running Orb-SLAM2 with a ZED stereo camera as well and wondering if possibly you could help me this as you may have run through the same issues. Did you perform the opencv stereo calibration? Are you running your camera through ROS and if so which package are you using? Any help you could give me would be appreciated. Perhaps you could email me (my address is in my profile) since this really doesn't belong in this thread.

from orb_slam2.

antithing avatar antithing commented on August 27, 2024

Happy to help. stand by for email.

from orb_slam2.

M1234Thomas avatar M1234Thomas commented on August 27, 2024

hi @antithing @durn2000 ,
I am also working with the ZED stereo camera trying to run live SLAM. But the reconstructions do not look alike the scene. Also the tracking and loop closing are not robust either. I have double checked the settings file and everything seems to be correct. Did you experience something similar in the beginning. Do you mind sharing the rectification code if you have done any and config files as well? Any help is really appreciated. Thanks in advance.

from orb_slam2.

 avatar commented on August 27, 2024

Sounds like you are using incorrect camera calibration.

from orb_slam2.

sharma-arjun avatar sharma-arjun commented on August 27, 2024

@antithing Could you share the changes you had to make to LoopClosing.cc and Tracking.cc to compute the correction for the current reference key frame and transforming all corrections such that the current reference key frame pose does not change (as suggested by raulmur). I am facing the same issue of camera jumping during global bundle adjustment. Thanks

from orb_slam2.

Related Issues (20)

Recommend Projects

  • React photo React

    A declarative, efficient, and flexible JavaScript library for building user interfaces.

  • Vue.js photo Vue.js

    🖖 Vue.js is a progressive, incrementally-adoptable JavaScript framework for building UI on the web.

  • Typescript photo Typescript

    TypeScript is a superset of JavaScript that compiles to clean JavaScript output.

  • TensorFlow photo TensorFlow

    An Open Source Machine Learning Framework for Everyone

  • Django photo Django

    The Web framework for perfectionists with deadlines.

  • D3 photo D3

    Bring data to life with SVG, Canvas and HTML. 📊📈🎉

Recommend Topics

  • javascript

    JavaScript (JS) is a lightweight interpreted programming language with first-class functions.

  • web

    Some thing interesting about web. New door for the world.

  • server

    A server is a program made to process requests and deliver data to clients.

  • Machine learning

    Machine learning is a way of modeling and interpreting data that allows a piece of software to respond intelligently.

  • Game

    Some thing interesting about game, make everyone happy.

Recommend Org

  • Facebook photo Facebook

    We are working to build community through open source technology. NB: members must have two-factor auth.

  • Microsoft photo Microsoft

    Open source projects and samples from Microsoft.

  • Google photo Google

    Google ❤️ Open Source for everyone.

  • D3 photo D3

    Data-Driven Documents codes.