raulmur / ORB_SLAM2

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

Understanding plane detection code in AR demo(not an issue) #1006

Open Pallav1299 opened 3 years ago

Pallav1299 commented 3 years ago

First of all, thanks for the great work. I've been trying to understand and modify the AR demo code (which is also used here), but couldn't find proper documentation for the same. It would be great if someone could share some reference for understanding its working. Specifically the following functions:

I want to achieve multiple plane detection on mobile devices(example repo). Is it viable to use sparse features from ORB-SLAM for multiple plane detection?

AlejandroSilvestri commented 3 years ago

Hi @Pallav1299

Many years ago I was wondering the same. Since I didn't write my thoughts then, I'll share here with you what I think is going on. Feel free to correct me if I wrong.

DetectPlane uses RANSAC to test planes based in random set of points, and keep that with the most inliers, hence the dominant plane. It construct a Plane object from them.

If you want to detect more planes, you can repeat DetectPlane omitting the points associated with the already detected plane, and you'll get the second dominant plane, and so on.

Recompute computes the plane pose from the inliers discovered in DetectPlane. Recompute will be executed many times on the same plane point cloud, because ORB-SLAM will erase some of them, refine the position of other, and change a lot on each loop closure.

Recompute uses o, the plane point cloud average, as the origin of its reference system; and SVD to find the perpendicular unit vector n to the plane: a,b,c is a perpendicular vector, n=nx,ny,nz is a normalized version. It chooses the sign so the vector is pointing up instead of down, taking the camera as the reference (uses camera y axis to tell what is "up").

As in PCA (principal component analysis) SVD gives you the three eigenvectors or principal components. The main two eigenvector belong to the plane. The third one, the weakest, is perpendicular to the plane.

So, up unit vector is (0,1,0), representing up in the plane reference system, meaning y axe is the perpendicular one, meanwhile x and z belong to the plane. n unit vector is up in the world reference system, so Rodrigues vector are build with the direction v (cross product between up and n), normalized as n/sa, and module ang (the angle of rotation between up and n).

I believe ExpSO3 is a function to get a rotation matrix from a Rodrigues vector. I believe it implement Rodrigues algorithm to do so. In mathematics, this conversion belong to the exponential map (an infinite serie) of the special orthogonal group ExpSO(3), and Rodrigues algorithm is a very good and practical approximation.

I hope it helps.

Pallav1299 commented 3 years ago

@AlejandroSilvestri, Sorry for the late reply. Your explanation is very helpful, thanks.

Although I am left with a general question:

AlejandroSilvestri commented 3 years ago

Hi @Pallav1299

If you want to detect more planes, you can repeat DetectPlane omitting the points associated with the already detected plane, and you'll get the second dominant plane, and so on.

I know there are some methods addressing this problem, although they don't run in real time. Here are two papers (without code), they aim 3d point cloud and aren't related to visual slam.

Plane Detection in Point Cloud Data, 2010

Plane Detection in 3D Point Cloud Using Octree-Balanced Density Down-sampling and Iterative Adaptive Plane Extraction, 2018 Looks for all planes in a 3d point cloud. image

I would like to know your findings.

Pallav1299 commented 3 years ago

@AlejandroSilvestri, thanks for the suggestion. The approach looks good. Can it be actually used on the sparse monocular 3D points from ORB SLAM 2? I am working with ORB SLAM 2 on a mobile device and wanted to confirm if the indexes in vKeys and vMPs actually have correspondance?

AlejandroSilvestri commented 3 years ago

@Pallav1299

ORB_SLAM2 on mobile? Very exciting! Please post some link to some video or demo!

vKeys and vMPs are paired: they have the same size and their elements under the same index correspond to each other.

Pallav1299 commented 3 years ago

Thanks @AlejandroSilvestri. Here's the link to an available github repo that I found.