Bundle Adjustment of Ground Truth Data

91 views
Skip to first unread message

Ron S.

unread,
Feb 13, 2022, 4:12:46 AM2/13/22
to Ceres Solver
Hello,

I am trying to test bundle adjustment on synthetic data. I am using the bundle_adjuster example in Ceres. 

I added a ground truth error metric. For the cameras, the average ground truth error is the distance between the correct camera position and the camera position after optimization. This applies to all cameras and is divided by the number of cameras. And for points, the average ground truth error is the distance between the correct point position and the point position after optimization. This applies to all points and is divided by the number of points.

First, I ran bundle_adjuster without adding any error to the scene.

The initial cost (reprojection error) is: 2.510083e-16

It is close to zero, so all is normal, since the scene is perfect at this point. The ground truth error for cameras and points is also close to zero.

Next, in bundle_adjuster.cc, I added perturbations to the problem 
bal_problem.Normalize();
bal_problem.Perturb(0.05, 0.05, 0.05);


After these perturbations, I calculated the initial ground truth error as:
GROUND TRUTH INITIAL AVG CAMERA ERROR: 0.08
GROUND TRUTH INITIAL AVG POINT ERROR: 0.08

Then, I ran the command:
bin/bundle_adjuster --input=synthetic-data.txt  --num_iterations=5

I get the output:

iter      cost      cost_change  |gradient|   |step|    tr_ratio  tr_radius  ls_iter  iter_time  total_time
   0 1.344274e+03    0.00e+00    4.60e+02   0.00e+00   0.00e+00  1.00e+04        0    4.52e-01   6.85e-01
   1 2.519456e+01    1.32e+03    6.74e+01   1.52e+02   9.82e-01  3.00e+04        3    6.68e-01   1.35e+00
   2 2.795099e-01    2.49e+01    6.63e+00   5.91e+01   9.91e-01  9.00e+04        7    7.28e-01   2.08e+00
   3 3.181261e-03    2.76e-01    4.94e-01   3.25e+01   9.92e-01  2.70e+05       38    1.36e+00  3.44e+00
   4 1.178155e-05    3.17e-03    4.45e-02   1.55e+01   9.98e-01  8.10e+05       95    2.53e+00   5.97e+00
   5 5.716298e-09    1.18e-05    5.42e-04   1.72e+00   1.00e+00  2.43e+06      134    3.33e+00   9.30e+00

Solver Summary (v 2.0.0-eigen-(3.3.7)-no_lapack-eigensparse-no_openmp)

                                     Original                  Reduced
Parameter blocks                        23616                    23616
Parameters                              74304                    74304
Residual blocks                        338882                   338882
Residuals                              677764                   677764

Minimizer                        TRUST_REGION
Trust region strategy     LEVENBERG_MARQUARDT

                                        Given                     Used
Linear solver                 ITERATIVE_SCHUR          ITERATIVE_SCHUR
Preconditioner                         JACOBI                   JACOBI
Threads                                     1                        1
Linear solver ordering              23040,576                23040,576
Schur structure                         2,3,9                    2,3,9

Cost:
Initial                          1.344274e+03
Final                            5.716298e-09
Change                           1.344274e+03

Minimizer iterations                        6
Successful steps                            6
Unsuccessful steps                          0

Time (in seconds):
Preprocessor                         0.233319

  Residual only evaluation           0.231133 (5)
  Jacobian & residual evaluation     2.385698 (6)
  Linear solver                      6.186789 (5)
Minimizer                            9.065083

Postprocessor                        0.019331
Total                                9.317733

Termination:                   NO_CONVERGENCE (Maximum number of iterations reached. Number of iterations: 5.)



The reprojection error is minimized to a low value. However, my ground truth error is: 

GROUND TRUTH AVG CAMERA ERROR: 1.70
GROUND TRUTH AVG POINT ERROR: 0.47

So the ground truth error became worse after optimization. Is this normal behavior? Is there some option in Ceres I can tune so that the problem optimizes closer to the ground truth? 



1262871536

unread,
Feb 13, 2022, 4:12:57 AM2/13/22
to Ron S.
这是来自QQ邮箱的假期自动回复邮件。

您好,我最近正在休假中,无法亲自回复您的邮件。我将在假期结束后,尽快给您回复。

Sameer Agarwal

unread,
Feb 13, 2022, 9:47:58 AM2/13/22
to ceres-...@googlegroups.com
Ron,
You are trying to optimize a function of the form

f(x) + g(x)

where f is the back projection error in bundle adjustment and g is the control point/ground truth error. The optimization algorithm tries the minimize the sum, so if it can find a lower minimum by trading some error in g for a much lower error in f it will. If you think error in g is more important then you should increase the weight/scale of the terms in g and optimize

f(x) + s g(x)

the value of s depends on how confident you are in the measurements of ground truth data compared to the image data.

Sameer


--
You received this message because you are subscribed to the Google Groups "Ceres Solver" group.
To unsubscribe from this group and stop receiving emails from it, send an email to ceres-solver...@googlegroups.com.
To view this discussion on the web visit https://groups.google.com/d/msgid/ceres-solver/7c98ac03-4670-4f05-af50-b900450001c5n%40googlegroups.com.

Ron S.

unread,
Feb 13, 2022, 1:32:30 PM2/13/22
to Ceres Solver
Hi Sameer,
Actually, I am not trying incorporate the ground truth data into the optimization problem. What I meant was I am trying to see how close bundle adjustment can get to the "real solution", which is why I am using synthetic data (with added noise). I run the bundle adjustment as normal using only reprojection error and afterwards, I see how well the results line up with ground truth. I thought maybe there was some option I could tune in Ceres that would allow it to converge to a "better" solution. Would you say that not being able to converge to the real solution is simply a limitation of bundle adjustment/reprojection error?

1262871536

unread,
Feb 13, 2022, 1:33:06 PM2/13/22
to Ron S.

Sameer Agarwal

unread,
Feb 13, 2022, 6:22:28 PM2/13/22
to ceres-...@googlegroups.com
On Sun, Feb 13, 2022 at 10:32 AM Ron S. <ron4...@gmail.com> wrote:
Hi Sameer,
Actually, I am not trying incorporate the ground truth data into the optimization problem. What I meant was I am trying to see how close bundle adjustment can get to the "real solution", which is why I am using synthetic data (with added noise). I run the bundle adjustment as normal using only reprojection error and afterwards, I see how well the results line up with ground truth. I thought maybe there was some option I could tune in Ceres that would allow it to converge to a "better" solution. Would you say that not being able to converge to the real solution is simply a limitation of bundle adjustment/reprojection error?

Sorry I totally screwed up my reply. A couple of things.

1. Are your accounting for the fact that you can scale, translate and rotate your reconstruction without changing the reprojection error? 
2. If your synthetic data has noise, then depending on how sensitive your reconstruction is, it is possible that there is another reconstruction with lower reconstruction error. In fact if your reconstruction is a critical configuration then there may exist an infinite number of such reconstructions. 
3.  The second problem is the limitation of nonlinear nonconvex optimization itself, where the solution you get depends on your starting point. So it is possible that you do not recover the ground truth simply because the optimizer is stuck in a local minimum.

I would first check for (1) before looking into (2) and (3).
Sameer



 
Reply all
Reply to author
Forward
0 new messages