Optimal parameter blocks for Bundle Adjustment

474 views
Skip to first unread message

dr.a.k...@gmail.com

unread,
Jan 7, 2021, 4:25:18 AM1/7/21
to Ceres Solver
I have typically been optimising using several parameter blocks...eg a quaternion, a 3-vector etc

I thought this was optimal because I can then tell Ceres to use QuaternionParametisation which presumably helps.

However, I notice the BA example just throws a 9-vector of the camera - Rodrigues, translation, camera params - in one 'lump'. Ceres will have no idea which numbers represent a rotation, or a translation etc.

Which is the correct way to do this ? Intuitively surely Ceres is better off knowing that a certain small block represents a rotation vector ? 
Yet it seems from this forum that if all variables will always be needed per-cost-function, then we should just send them as one big anonymous block.

I'm probably missing something....

Sameer Agarwal

unread,
Jan 7, 2021, 12:42:25 PM1/7/21
to ceres-...@googlegroups.com
There are two different issues here. 

1. Using a local parameterization when instead of a four vector, we have say a 7-vector (or more containing more parameters of the camera).
2. What is the right parameter block size.

I will address both, but first let me say that from a mathematical/correctness perspective the size of the parameter block does not matter as long as you are using them correctly in your cost functions.

Ceres treats each parameter block as living on a manifold described by its local parameterization. If there is no local parameterization, then the manifold is just R^k. Other than that it makes no assumptions.

Now if you have a parameter block which is the product of multiple manifolds, say the pose of a camera, which is the product of R^3 and Quaternion. Then use a product local parameterization to indicate that to ceres.

As for the right parameter block size. This is primarily a matter of efficiency.

Ceres treats the jacobian of a cost function w.r.t a parameter block to be structurally dense, even if the entries in it are zero. So if you have a parameter block that contains a bunch of sub components that are not used by most cost functions that depend on that parameter block, then you will have an overly dense Jacobian which in turn would decrease the performance of the sparse linear algebra algorithms.

The flip side of this is, if you split a parameter block too finely, you will get perhaps minimal sparsity but you will increase some of the accounting and indexing that needs to be done to keep track of parameter blocks, and how much that is really depends on your problem.

For bundle_adjuster.cc there is only one cost function which uses all the parameters of a camera so there is no reason to split it into separate parameter blocks.

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/d683083e-f7e2-448f-89e1-c682aed802a4n%40googlegroups.com.

dr.a.k...@gmail.com

unread,
Jan 8, 2021, 4:08:33 AM1/8/21
to Ceres Solver
Thanks Sameer - very helpful and prompt as always.

Just so I'm clear (as I've never used ProductParametrization)

Currently I do the following for bundle adjustment. The cost blocks are:
4 - Eigen Quaternion
3 - Translation
15 - Camera intrinsics and distortion coefficients
3 - the 3d point

 CostFunction* reprojection_cost =
                new AutoDiffCostFunction<Camera_Reprojection_Cost, 2, 4, 3, 15, 3>(
                    new Camera_Reprojection_Cost(left_image_points[j]));

I add each block to fitting_cost_function and then I do :

 EigenQuaternionParameterization* quaternion_parameterisation = new EigenQuaternionParameterization;
    fitting_cost_function.SetParameterization(&camera_rotation[i][0],
        quaternion_parameterisation);

(where i is the ith camera)

I think what you are saying is that I either
i) Combine the 4-block and 3-block into a 7-block (or even a 22-block with the camera coefficients). This has the advantage of being simple, but Ceres loses the information that the 4-block was a quaternion, and so the solution is less constrained, presumably, because it might create quaternions that don't exist.

ii) Use ProductParameterization. In which case I don't know how to locally parameterize the 3-block translation. The docs give the example:

            ProductParameterization product_param(new QuaterionionParameterization(), new IdentityParameterization(3));  

But I need a 'plain' R^3 for the second term. Is there such a thing? Could you advise as to how I'd produce a ProductParameterization of a quaternion and a 3-vector ?

Finally, even with the simple way I'm currently using (small blocks and no ProductParameterization), do I understand correctly that the runtime might be slower but the final result should be just as good? Or is there a risk of poorer convergence?

Many thanks

Sameer Agarwal

unread,
Jan 8, 2021, 1:10:28 PM1/8/21
to ceres-...@googlegroups.com
On Fri, Jan 8, 2021 at 1:08 AM dr.a.k...@gmail.com <dr.a.k...@gmail.com> wrote:
Thanks Sameer - very helpful and prompt as always.

Just so I'm clear (as I've never used ProductParametrization)

Currently I do the following for bundle adjustment. The cost blocks are:
4 - Eigen Quaternion
3 - Translation
15 - Camera intrinsics and distortion coefficients
3 - the 3d point

 CostFunction* reprojection_cost =
                new AutoDiffCostFunction<Camera_Reprojection_Cost, 2, 4, 3, 15, 3>(
                    new Camera_Reprojection_Cost(left_image_points[j]));

I add each block to fitting_cost_function and then I do :

 EigenQuaternionParameterization* quaternion_parameterisation = new EigenQuaternionParameterization;
    fitting_cost_function.SetParameterization(&camera_rotation[i][0],
        quaternion_parameterisation);

(where i is the ith camera)

I think what you are saying is that I either
i) Combine the 4-block and 3-block into a 7-block (or even a 22-block with the camera coefficients). This has the advantage of being simple, but Ceres loses the information that the 4-block was a quaternion, and so the solution is less constrained, presumably, because it might create quaternions that don't exist.

ii) Use ProductParameterization. In which case I don't know how to locally parameterize the 3-block translation. The docs give the example:

            ProductParameterization product_param(new QuaterionionParameterization(), new IdentityParameterization(3));  

But I need a 'plain' R^3 for the second term. Is there such a thing? Could you advise as to how I'd produce a ProductParameterization of a quaternion and a 3-vector ?

IdentityParameterization IS the plain R^k parameterization.
 
Finally, even with the simple way I'm currently using (small blocks and no ProductParameterization), do I understand correctly that the runtime might be slower but the final result should be just as good? Or is there a risk of poorer convergence?

Yes the result should be the same modulo some floating point reordering.
Sameer

 

dr.a.k...@gmail.com

unread,
Jan 20, 2021, 5:14:17 AM1/20/21
to Ceres Solver
OK I understand.

The docs are not 100% clear on implementation. Is this correct (where I have a vector<Eigen::Quaterniond> and vector<Eigen::Vector3d> for rotations and translations)?
I feel like I should be adding product_param to the fitting_cost_function somehow,  but I don't know where to point it to)

for (int i = 0; i < n_scans; ++i)
    {
        EigenQuaternionParameterization* quaternion_parameterisation = new EigenQuaternionParameterization;
        fitting_cost_function.SetParameterization(rotations[i].coeffs().data(),
            quaternion_parameterisation);

IdentityParameterization* id_param = new IdentityParameterization(3);
fitting_cost_function.SetParameterization(translations[i].data(),
id_param);

ProductParameterization product_param(quaternion_parameterisation, id_param);

    }

Sameer Agarwal

unread,
Jan 20, 2021, 12:04:47 PM1/20/21
to ceres-...@googlegroups.com
On Wed, Jan 20, 2021 at 2:14 AM dr.a.k...@gmail.com <dr.a.k...@gmail.com> wrote:
OK I understand.

The docs are not 100% clear on implementation. Is this correct (where I have a vector<Eigen::Quaterniond> and vector<Eigen::Vector3d> for rotations and translations)?
I feel like I should be adding product_param to the fitting_cost_function somehow,  but I don't know where to point it to)

for (int i = 0; i < n_scans; ++i)
    {
        EigenQuaternionParameterization* quaternion_parameterisation = new EigenQuaternionParameterization;
        fitting_cost_function.SetParameterization(rotations[i].coeffs().data(),
            quaternion_parameterisation);

IdentityParameterization* id_param = new IdentityParameterization(3);
fitting_cost_function.SetParameterization(translations[i].data(),
id_param);

ProductParameterization product_param(quaternion_parameterisation, id_param);

There is no need for this, you have already attached a parameterization with each of your parameter block. Notice after creating the ProductParameterization you are not doing anything with it.

Sameer
 
Reply all
Reply to author
Forward
0 new messages