Bundle Adjustment: Axis-Angle vs Quaternions

582 views
Skip to first unread message

Vivek Bagaria

unread,
Mar 2, 2021, 12:00:05 AM3/2/21
to ceres-...@googlegroups.com
Rotation in quaternion representation involves only cheap addition and multiplication operation, whereas rotation in axis-angle space additionally involves expensive cos/sin operations. Therefore for bundle adjustment, the residual and jacobian evaluation for quaternion should be much faster than axis-angle representation and hence theoretically using quaternionin bundle_adjuster.cc should be faster

I have attached summary reports comparing axis-angle to quaternion (with and without local parameterization) and I didnt find any difference in running time. Is it because sin/cos are implemented via a lookup table?

For problem-39-18060-pre.txt from here, these were the running times
  1. Axis angle - 740ms
  2. Quaternion - 807ms
  3. Quaternion with local parameterization - 790ms

quaternion
quaternion_local_parameterization
axis_angle

Sameer Agarwal

unread,
Mar 2, 2021, 10:06:49 AM3/2/21
to ceres-...@googlegroups.com
On Mon, Mar 1, 2021 at 9:00 PM Vivek Bagaria <vi...@matician.com> wrote:
Rotation in quaternion representation involves only cheap addition and multiplication operation, whereas rotation in axis-angle space additionally involves expensive cos/sin operations. Therefore for bundle adjustment, the residual and jacobian evaluation for quaternion should be much faster than axis-angle representation and hence theoretically using quaternionin bundle_adjuster.cc should be faster

Not quite. Because how cheap/expensive these operations are needs to also be considered w.r.t the increased dimension size of the quaternion. In any case the jacobian evaluation times are a small fraction of the total time to solve, so I suspect you are not going to see much time difference.
Sameer

 

I have attached summary reports comparing axis-angle to quaternion (with and without local parameterization) and I didnt find any difference in running time. Is it because sin/cos are implemented via a lookup table?

For problem-39-18060-pre.txt from here, these were the running times
  1. Axis angle - 740ms
  2. Quaternion - 807ms
  3. Quaternion with local parameterization - 790ms

--
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/CA%2BA0BBr9PbUHnHvoROfT_-1y6NhR1RPOGu6kRR3rwC3fNMDHFA%40mail.gmail.com.

Dmitriy Korchemkin

unread,
Mar 2, 2021, 10:55:35 AM3/2/21
to Ceres Solver
I think that your results are more or less explainable.

Using quaternions without local parameterizations:
a. Results into larger dimensionality of tangent space (than in the case of axis-angle) => larger linear solver problems => linear solver time increases [to 0.28 from 0.23]
b. Computing jacobians involves (in the case of bundle adjustment example you're using) automatic differentiation for larger parameter block sizes, thus jacobian evaluation times are slightly higher (compared to axis-angle) [0.314 vs 0.308]
c. Computing residuals becomes cheaper (no trigonometry) [0.042 vs 0.049]

Using quaternions with local parameterizations:
a. Results into the same dimensionality of tangent space (as in the case of axis-angle) => similar size linear solver problems => linear solver time is almost equal [0.227 vs 0.229]
b. Computing jacobians involves automatic differentiation and additional operations for obtaining gradient in tangent space / parameter space => jacobian evaluation times are the highest
c. Computing residuals becomes cheaper (no trigonometry involved) [0.042 vs 0.049]


Note that only quaternions with local parameterizations will guarantee that rotation does not stay constant for non-zero perturbations in every point from parameter space.


If your performance is limited by residual/jacobian evaluation - you might be interested in pre-computing camera-specific jacobian parts (and transformations from the world to camera as matrices) in evaluation callback and computing only point-specific jacobian parts in the cost function evaluation routine; especially if per-point computations are rather simple, for example in the case of calibrated cameras.

Vivek Bagaria

unread,
Mar 2, 2021, 4:11:09 PM3/2/21
to Ceres Solver

Thanks for the quick response Sameer and Dmitriy :)
From your responses, I gather that there are two opposing forces when moving from AxisAngle to Quaternion:
  1. The computation cost increase because of increase in dimension
  2. The computations cost decrease because Quaternion uses cheaper operations.
I thought the second factor should dominate for the following reasons:
  1. The #3d point parameters is much larger than #camera parameters, so the first effect should be small for the linear solver.
  2. For a residual block, the number of parameters increase from 12 to 13 (=8%), however the increase in linear solver time is 22% whereas increase in jacobian calculation is 2%. Is this as expected or am I reading too much into these numbers?
  3. Trig computations are much more expensive than add/mul and I was expecting 2-3x improvement in speed. Am I wrong in this making assumption?

@Dmitry: Thanks for detailed explanation. It makes so much sense :). As per your comments and general discussion in this group, we should do the following to get the best performance (per iteration):
  1. Use optimized analytical jacobian since calculating them takes most of the time. Since bundle adjustment is so widly used, is there any existing implementation of analytical jacobian? Any resources would be great!
  2. Optimize the residual computation (harder to do this)
  3. Use the "right parameters" ceres::Options to improve performance of the linear solver.
Cheers,
--Vivek

Sameer Agarwal

unread,
Mar 3, 2021, 7:13:50 PM3/3/21
to ceres-...@googlegroups.com
Derivative computation is vectorized so there isn't a simple map from more or less computations.

sympy is a good place to start for analytical jacobians, though doing it by hand is perhaps simpler because it allows you to deal with common sub expressions yourself, which is key to an efficient implementation.
Sameer


Vivek Bagaria

unread,
Mar 3, 2021, 7:18:32 PM3/3/21
to ceres-...@googlegroups.com
On Wed, Mar 3, 2021 at 4:13 PM 'Sameer Agarwal' via Ceres Solver <ceres-...@googlegroups.com> wrote:
Derivative computation is vectorized so there isn't a simple map from more or less computations.
Ah..got it!

sympy is a good place to start for analytical jacobians, though doing it by hand is perhaps simpler because it allows you to deal with common sub expressions yourself, which is key to an efficient implementation.
Will look into this :)
You received this message because you are subscribed to a topic in the Google Groups "Ceres Solver" group.
To unsubscribe from this topic, visit https://groups.google.com/d/topic/ceres-solver/Yba35NrvG6Q/unsubscribe.
To unsubscribe from this group and all its topics, send an email to ceres-solver...@googlegroups.com.
To view this discussion on the web visit https://groups.google.com/d/msgid/ceres-solver/CABqdRUCXSur7yyfUDM2KB1AdUwSso8K_m6WizVi0WWKQU_Wu4w%40mail.gmail.com.
Reply all
Reply to author
Forward
0 new messages