1 // Copyright (c) 2018, ETH Zurich and UNC Chapel Hill.
2 // All rights reserved.
3 //
4 // Redistribution and use in source and binary forms, with or without
5 // modification, are permitted provided that the following conditions are met:
6 //
7 // * Redistributions of source code must retain the above copyright
8 // notice, this list of conditions and the following disclaimer.
9 //
10 // * Redistributions in binary form must reproduce the above copyright
11 // notice, this list of conditions and the following disclaimer in the
12 // documentation and/or other materials provided with the distribution.
13 //
14 // * Neither the name of ETH Zurich and UNC Chapel Hill nor the names of
15 // its contributors may be used to endorse or promote products derived
16 // from this software without specific prior written permission.
17 //
18 // THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
19 // AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
20 // IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
21 // ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDERS OR CONTRIBUTORS BE
22 // LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
23 // CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
24 // SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
25 // INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
26 // CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
27 // ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
28 // POSSIBILITY OF SUCH DAMAGE.
29 //
30 // Author: Johannes L. Schoenberger (jsch-at-demuc-dot-de)
31
32 #include "estimators/generalized_absolute_pose.h"
33
34 #include <array>
35
36 #include "base/polynomial.h"
37 #include "base/projection.h"
38 #include "estimators/generalized_absolute_pose_coeffs.h"
39 #include "util/logging.h"
40
41 namespace colmap {
42 namespace {
43
44 // Check whether the rays are close to parallel.
CheckParallelRays(const Eigen::Vector3d & ray1,const Eigen::Vector3d & ray2,const Eigen::Vector3d & ray3)45 bool CheckParallelRays(const Eigen::Vector3d& ray1, const Eigen::Vector3d& ray2,
46 const Eigen::Vector3d& ray3) {
47 const double kParallelThreshold = 1e-5;
48 return ray1.cross(ray2).isApproxToConstant(0, kParallelThreshold) &&
49 ray1.cross(ray3).isApproxToConstant(0, kParallelThreshold);
50 }
51
52 // Check whether the points are close to collinear.
CheckCollinearPoints(const Eigen::Vector3d & X1,const Eigen::Vector3d & X2,const Eigen::Vector3d & X3)53 bool CheckCollinearPoints(const Eigen::Vector3d& X1, const Eigen::Vector3d& X2,
54 const Eigen::Vector3d& X3) {
55 const double kMinNonCollinearity = 1e-5;
56 const Eigen::Vector3d X12 = X2 - X1;
57 const double non_collinearity_measure =
58 X12.cross(X1 - X3).squaredNorm() / X12.squaredNorm();
59 return non_collinearity_measure < kMinNonCollinearity;
60 }
61
ComposePlueckerLine(const Eigen::Matrix3x4d & rel_tform,const Eigen::Vector2d & point2D)62 Eigen::Vector6d ComposePlueckerLine(const Eigen::Matrix3x4d& rel_tform,
63 const Eigen::Vector2d& point2D) {
64 const Eigen::Matrix3x4d inv_proj_matrix = InvertProjectionMatrix(rel_tform);
65 const Eigen::Vector3d bearing =
66 inv_proj_matrix.leftCols<3>() * point2D.homogeneous();
67 const Eigen::Vector3d proj_center = inv_proj_matrix.rightCols<1>();
68 const Eigen::Vector3d bearing_normalized = bearing.normalized();
69 Eigen::Vector6d pluecker;
70 pluecker << bearing_normalized, proj_center.cross(bearing_normalized);
71 return pluecker;
72 }
73
PointFromPlueckerLineAndDepth(const Eigen::Vector6d & pluecker,const double depth)74 Eigen::Vector3d PointFromPlueckerLineAndDepth(const Eigen::Vector6d& pluecker,
75 const double depth) {
76 return pluecker.head<3>().cross(pluecker.tail<3>()) +
77 depth * pluecker.head<3>();
78 }
79
80 // Compute the coefficients from the system of 3 equations, nonlinear in the
81 // depth of the points. Inputs are three Pluecker lines and the locations of
82 // their corresponding points in 3D. The system of equations comes from the
83 // distance constraints between 3D points:
84 //
85 // || f_i - f_j ||^2 = || (q_i x q_i' + lambda_i * q_i) -
86 // (q_j x q_j' + lambda_j * q_j) ||^2
87 //
88 // where [q_i; q_i'] is the Pluecker coordinate of bearing i and f_i is the
89 // coordinate of the corresponding 3D point in the global coordinate system. A
90 // 3D point in the local camera coordinate system along this line is
91 // parameterized through the depth scalar lambda_i as:
92 //
93 // B_fi = q_i x q_i' + lambda_i * q_i.
94 //
ComputePolynomialCoefficients(const std::vector<Eigen::Vector6d> & plueckers,const std::vector<Eigen::Vector3d> & points3D)95 Eigen::Matrix<double, 3, 6> ComputePolynomialCoefficients(
96 const std::vector<Eigen::Vector6d>& plueckers,
97 const std::vector<Eigen::Vector3d>& points3D) {
98 CHECK_EQ(plueckers.size(), 3);
99 CHECK_EQ(points3D.size(), 3);
100
101 Eigen::Matrix<double, 3, 6> K;
102 const std::array<int, 3> is = {{0, 0, 1}};
103 const std::array<int, 3> js = {{1, 2, 2}};
104
105 for (int k = 0; k < 3; ++k) {
106 const int i = is[k];
107 const int j = js[k];
108 const Eigen::Vector3d moment_difference =
109 plueckers[i].head<3>().cross(plueckers[i].tail<3>()) -
110 plueckers[j].head<3>().cross(plueckers[j].tail<3>());
111 K(k, 0) = 1;
112 K(k, 1) = -2 * plueckers[i].head<3>().dot(plueckers[j].head<3>());
113 K(k, 2) = 2 * moment_difference.dot(plueckers[i].head<3>());
114 K(k, 3) = 1;
115 K(k, 4) = -2 * moment_difference.dot(plueckers[j].head<3>());
116 K(k, 5) = moment_difference.squaredNorm() -
117 (points3D[i] - points3D[j]).squaredNorm();
118 }
119
120 return K;
121 }
122
123 // Solve quadratics of the form: x^2 + bx + c = 0.
SolveQuadratic(const double b,const double c,double * roots)124 int SolveQuadratic(const double b, const double c, double* roots) {
125 const double delta = b * b - 4 * c;
126 // Do not allow complex solutions.
127 if (delta >= 0) {
128 const double sqrt_delta = std::sqrt(delta);
129 roots[0] = -0.5 * (b + sqrt_delta);
130 roots[1] = -0.5 * (b - sqrt_delta);
131 return 2;
132 } else {
133 return 0;
134 }
135 }
136
137 // Given lambda_j, return the values for lambda_i, where:
138 // k1 lambda_i^2 + (k2 lambda_j + k3) lambda_i
139 // + k4 lambda_j^2 + k5 lambda_j + k6 = 0.
ComputeLambdaValues(const Eigen::Matrix<double,3,6>::ConstRowXpr & k,const double lambda_j,std::vector<double> * lambdas_i)140 void ComputeLambdaValues(const Eigen::Matrix<double, 3, 6>::ConstRowXpr& k,
141 const double lambda_j,
142 std::vector<double>* lambdas_i) {
143 // Note that we solve x^2 + bx + c = 0, since k(0) is one.
144 double roots[2];
145 const int num_solutions =
146 SolveQuadratic(k(1) * lambda_j + k(2),
147 lambda_j * (k(3) * lambda_j + k(4)) + k(5), roots);
148 for (int i = 0; i < num_solutions; ++i) {
149 if (roots[i] > 0) {
150 lambdas_i->push_back(roots[i]);
151 }
152 }
153 }
154
155 // Given the coefficients of the polynomial system return the depths of the
156 // points along the Pluecker lines. Use Sylvester resultant to get and 8th
157 // degree polynomial for lambda_3 and back-substite in the original equations.
ComputeDepthsSylvester(const Eigen::Matrix<double,3,6> & K)158 std::vector<Eigen::Vector3d> ComputeDepthsSylvester(
159 const Eigen::Matrix<double, 3, 6>& K) {
160 const Eigen::Matrix<double, 9, 1> coeffs = ComputeDepthsSylvesterCoeffs(K);
161
162 Eigen::VectorXd roots_real;
163 Eigen::VectorXd roots_imag;
164 if (!FindPolynomialRootsCompanionMatrix(coeffs, &roots_real, &roots_imag)) {
165 return std::vector<Eigen::Vector3d>();
166 }
167
168 // Back-substitute every lambda_3 to the system of equations.
169 std::vector<Eigen::Vector3d> depths;
170 depths.reserve(roots_real.size());
171 for (Eigen::VectorXd::Index i = 0; i < roots_real.size(); ++i) {
172 const double kMaxRootImagRatio = 1e-3;
173 if (std::abs(roots_imag(i)) > kMaxRootImagRatio * std::abs(roots_real(i))) {
174 continue;
175 }
176
177 const double lambda_3 = roots_real(i);
178 if (lambda_3 <= 0) {
179 continue;
180 }
181
182 std::vector<double> lambdas_2;
183 ComputeLambdaValues(K.row(2), lambda_3, &lambdas_2);
184
185 // Now we have two depths, lambda_2 and lambda_3. From the two remaining
186 // equations, we must get the same lambda_1, otherwise the solution is
187 // invalid.
188 for (const double lambda_2 : lambdas_2) {
189 std::vector<double> lambdas_1_1;
190 ComputeLambdaValues(K.row(0), lambda_2, &lambdas_1_1);
191 std::vector<double> lambdas_1_2;
192 ComputeLambdaValues(K.row(1), lambda_3, &lambdas_1_2);
193 for (const double lambda_1_1 : lambdas_1_1) {
194 for (const double lambda_1_2 : lambdas_1_2) {
195 const double kMaxLambdaRatio = 1e-2;
196 if (std::abs(lambda_1_1 - lambda_1_2) <
197 kMaxLambdaRatio * std::max(lambda_1_1, lambda_1_2)) {
198 const double lambda_1 = (lambda_1_1 + lambda_1_2) / 2;
199 depths.emplace_back(lambda_1, lambda_2, lambda_3);
200 }
201 }
202 }
203 }
204 }
205
206 return depths;
207 }
208
209 } // namespace
210
Estimate(const std::vector<X_t> & points2D,const std::vector<Y_t> & points3D)211 std::vector<GP3PEstimator::M_t> GP3PEstimator::Estimate(
212 const std::vector<X_t>& points2D, const std::vector<Y_t>& points3D) {
213 CHECK_EQ(points2D.size(), 3);
214 CHECK_EQ(points3D.size(), 3);
215
216 if (CheckCollinearPoints(points3D[0], points3D[1], points3D[2])) {
217 return std::vector<GP3PEstimator::M_t>({});
218 }
219
220 // Transform 2D points into compact Pluecker line representation.
221 std::vector<Eigen::Vector6d> plueckers(3);
222 for (size_t i = 0; i < 3; ++i) {
223 plueckers[i] = ComposePlueckerLine(points2D[i].rel_tform, points2D[i].xy);
224 }
225
226 if (CheckParallelRays(plueckers[0].head<3>(), plueckers[1].head<3>(),
227 plueckers[2].head<3>())) {
228 return std::vector<GP3PEstimator::M_t>({});
229 }
230
231 // Compute the coefficients k1, k2, k3 using Eq. 4.
232 const Eigen::Matrix<double, 3, 6> K =
233 ComputePolynomialCoefficients(plueckers, points3D);
234
235 // Compute the depths along the Pluecker lines of the observations.
236 const std::vector<Eigen::Vector3d> depths = ComputeDepthsSylvester(K);
237 if (depths.empty()) {
238 return std::vector<GP3PEstimator::M_t>({});
239 }
240
241 // For all valid depth values, compute the transformation between points in
242 // the camera and the world frame. This uses Umeyama's method rather than the
243 // algorithm proposed in the paper, since Umeyama's method is numerically more
244 // stable and this part is not a bottleneck.
245
246 Eigen::Matrix3d points3D_world;
247 for (size_t i = 0; i < 3; ++i) {
248 points3D_world.col(i) = points3D[i];
249 }
250
251 std::vector<M_t> models(depths.size());
252 for (size_t i = 0; i < depths.size(); ++i) {
253 Eigen::Matrix3d points3D_camera;
254 for (size_t j = 0; j < 3; ++j) {
255 points3D_camera.col(j) =
256 PointFromPlueckerLineAndDepth(plueckers[j], depths[i][j]);
257 }
258
259 const Eigen::Matrix4d transform =
260 Eigen::umeyama(points3D_world, points3D_camera, false);
261 models[i] = transform.topLeftCorner<3, 4>();
262 }
263
264 return models;
265 }
266
Residuals(const std::vector<X_t> & points2D,const std::vector<Y_t> & points3D,const M_t & proj_matrix,std::vector<double> * residuals)267 void GP3PEstimator::Residuals(const std::vector<X_t>& points2D,
268 const std::vector<Y_t>& points3D,
269 const M_t& proj_matrix,
270 std::vector<double>* residuals) {
271 CHECK_EQ(points2D.size(), points3D.size());
272
273 residuals->resize(points2D.size(), 0);
274
275 // Note that this code might not be as nice as Eigen expressions,
276 // but it is significantly faster in various tests.
277
278 const double P_00 = proj_matrix(0, 0);
279 const double P_01 = proj_matrix(0, 1);
280 const double P_02 = proj_matrix(0, 2);
281 const double P_03 = proj_matrix(0, 3);
282 const double P_10 = proj_matrix(1, 0);
283 const double P_11 = proj_matrix(1, 1);
284 const double P_12 = proj_matrix(1, 2);
285 const double P_13 = proj_matrix(1, 3);
286 const double P_20 = proj_matrix(2, 0);
287 const double P_21 = proj_matrix(2, 1);
288 const double P_22 = proj_matrix(2, 2);
289 const double P_23 = proj_matrix(2, 3);
290
291 for (size_t i = 0; i < points2D.size(); ++i) {
292 const Eigen::Matrix3x4d& rel_tform = points2D[i].rel_tform;
293 const double X_0 = points3D[i](0);
294 const double X_1 = points3D[i](1);
295 const double X_2 = points3D[i](2);
296
297 // Project 3D point from world to generalized camera.
298 const double pgx_0 = P_00 * X_0 + P_01 * X_1 + P_02 * X_2 + P_03;
299 const double pgx_1 = P_10 * X_0 + P_11 * X_1 + P_12 * X_2 + P_13;
300 const double pgx_2 = P_20 * X_0 + P_21 * X_1 + P_22 * X_2 + P_23;
301
302 // Projection 3D point from generalized camera to camera of the observation.
303 const double pcx_2 = rel_tform(2, 0) * pgx_0 + rel_tform(2, 1) * pgx_1 +
304 rel_tform(2, 2) * pgx_2 + rel_tform(2, 3);
305
306 // Check if 3D point is in front of camera.
307 if (pcx_2 > std::numeric_limits<double>::epsilon()) {
308 const double pcx_0 = rel_tform(0, 0) * pgx_0 + rel_tform(0, 1) * pgx_1 +
309 rel_tform(0, 2) * pgx_2 + rel_tform(0, 3);
310 const double pcx_1 = rel_tform(1, 0) * pgx_0 + rel_tform(1, 1) * pgx_1 +
311 rel_tform(1, 2) * pgx_2 + rel_tform(1, 3);
312 const double inv_pcx_norm =
313 1 / std::sqrt(pcx_0 * pcx_0 + pcx_1 * pcx_1 + pcx_2 * pcx_2);
314
315 const double x_0 = points2D[i].xy(0);
316 const double x_1 = points2D[i].xy(1);
317 const double inv_x_norm = 1 / std::sqrt(x_0 * x_0 + x_1 * x_1 + 1);
318
319 const double cosine_dist =
320 1 - inv_pcx_norm * inv_x_norm * (pcx_0 * x_0 + pcx_1 * x_1 + pcx_2);
321 (*residuals)[i] = cosine_dist * cosine_dist;
322
323 } else {
324 (*residuals)[i] = std::numeric_limits<double>::max();
325 }
326 }
327 }
328
329 } // namespace colmap
330