forked from UZ-SLAMLab/ORB_SLAM3
-
Notifications
You must be signed in to change notification settings - Fork 1
/
Copy pathGeometricTools.cc
68 lines (52 loc) · 2.48 KB
/
GeometricTools.cc
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
/**
* This file is part of ORB-SLAM3
*
* Copyright (C) 2017-2021 Carlos Campos, Richard Elvira, Juan J. Gómez Rodríguez, José M.M. Montiel and Juan D. Tardós, University of Zaragoza.
* Copyright (C) 2014-2016 Raúl Mur-Artal, José M.M. Montiel and Juan D. Tardós, University of Zaragoza.
*
* ORB-SLAM3 is free software: you can redistribute it and/or modify it under the terms of the GNU General Public
* License as published by the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* ORB-SLAM3 is distributed in the hope that it will be useful, but WITHOUT ANY WARRANTY; without even
* the implied warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License along with ORB-SLAM3.
* If not, see <http://www.gnu.org/licenses/>.
*/
#include "GeometricTools.h"
#include "KeyFrame.h"
namespace ORB_SLAM3
{
Eigen::Matrix3f GeometricTools::ComputeF12(KeyFrame* &pKF1, KeyFrame* &pKF2)
{
Sophus::SE3<float> Tc1w = pKF1->GetPose();
Sophus::Matrix3<float> Rc1w = Tc1w.rotationMatrix();
Sophus::SE3<float>::TranslationMember tc1w = Tc1w.translation();
Sophus::SE3<float> Tc2w = pKF2->GetPose();
Sophus::Matrix3<float> Rc2w = Tc2w.rotationMatrix();
Sophus::SE3<float>::TranslationMember tc2w = Tc2w.translation();
Sophus::Matrix3<float> Rc1c2 = Rc1w * Rc2w.transpose();
Eigen::Vector3f tc1c2 = -Rc1c2 * tc2w + tc1w;
Eigen::Matrix3f tc1c2x = Sophus::SO3f::hat(tc1c2);
const Eigen::Matrix3f K1 = pKF1->mpCamera->toK_();
const Eigen::Matrix3f K2 = pKF2->mpCamera->toK_();
return K1.transpose().inverse() * tc1c2x * Rc1c2 * K2.inverse();
}
bool GeometricTools::Triangulate(Eigen::Vector3f &x_c1, Eigen::Vector3f &x_c2,Eigen::Matrix<float,3,4> &Tc1w ,Eigen::Matrix<float,3,4> &Tc2w , Eigen::Vector3f &x3D)
{
Eigen::Matrix4f A;
A.block<1,4>(0,0) = x_c1(0) * Tc1w.block<1,4>(2,0) - Tc1w.block<1,4>(0,0);
A.block<1,4>(1,0) = x_c1(1) * Tc1w.block<1,4>(2,0) - Tc1w.block<1,4>(1,0);
A.block<1,4>(2,0) = x_c2(0) * Tc2w.block<1,4>(2,0) - Tc2w.block<1,4>(0,0);
A.block<1,4>(3,0) = x_c2(1) * Tc2w.block<1,4>(2,0) - Tc2w.block<1,4>(1,0);
Eigen::JacobiSVD<Eigen::Matrix4f> svd(A, Eigen::ComputeFullV);
Eigen::Vector4f x3Dh = svd.matrixV().col(3);
if(x3Dh(3)==0)
return false;
// Euclidean coordinates
x3D = x3Dh.head(3)/x3Dh(3);
return true;
}
} //namespace ORB_SLAM