raulmur / ORB_SLAM2

Real-Time SLAM for Monocular, Stereo and RGB-D Cameras, with Loop Detection and Relocalization Capabilities
Other
9.35k stars 4.69k forks source link

Increasing uncertainty influences correspondence between pose and map-points? #858

Open flo981 opened 4 years ago

flo981 commented 4 years ago

Hey,

I extract the current visible map-points and current robot position to estimate an actuation angle (roll, pitch, yaw) from the robot pose towards a map-point (map-density region) based on the two functions below:

map points: std::vector<ORB_SLAM2::MapPoint*> points = mpSLAM->GetTrackedMapPoints();

pose: cv::Mat position = mpSLAM->TrackStereo(imLeft,imRight,cv_ptrLeft>header.stamp.toSec());

My question: Does a increasing pose uncertainty influence the geometrical correspondence between the pose and the map points? Thus is my angle estimation error increases with the robot pose uncertainty/error?

If yes, why? Thanks a lot!

AlejandroSilvestri commented 4 years ago

@flo981

ORB-SLAM2 doesn't have such thing like pose uncertainty or pose error. I believe your angle estimation error comes from drifting. If so, closing loops reduce the drifting.

flo981 commented 4 years ago

@raulmur

Yes okay. So in case we have somehow a big drift, then the relation between a new created map point to the current pose is not correct in perspective to the real robot pose and the real map point?

Thus, If I have a big drift, this big drift also influences the position/correctness of new created map points? So If I move the camera to the densest map point region while having a big drift (this is what I want to do in order to increase the SLAM robustness), I could guide the camera towards a e.g. feature-less region and tracking is lost (in the worst case). Since the current map point coordinates are always in relation to the map points coordinates created in the first frame/keyframe. And if the drift increases the incorrectness of the map point coordinates increases. Correct?

(I hope you understand what I am trying the say)

AlejandroSilvestri commented 4 years ago

@flo981

Yes, it is correct. While mapping, It is always better to let orb-slam2 create as much new point as it can. Sometimes less speed helps: when your hardware is not powerful enough to map new points, you stop moving and let the system triangulate points before resuming.

Avoiding rotation only movements are wise, because they quickly lead to new unmapped scenes and lose tracking. New points triangulation needs translation: can't triangulate from pure rotations.

About map points coordinates. Yes, they are expressed in the World reference, where the first keyframe is the origin. But new mappoint coordinates are determined in reference to the neighborhood (aka local map), so they can have little error in local map, while accumulating big error in the whole map.

Only loop closing reduce the overall error, not in the whole map but at least in the loop. Thus, big loops are desirables.