Open MGBzH opened 5 days ago
The default configuration uses METIS to compute the ordering used for elimination. The resulting orderings have the same asymptotic complexity as the Schur complement trick (linear in the number of 3D points in the problem), so it should be pretty fast and it'll scale as you expect with the numbers of poses and points, same as if you were explicitly using the Schur complement trick
For really big problems there are other tricks you can use and lots of linear solvers to choose from; the linear solver is a template parameter that you can change to any solver that implements the interface SymForce expects for linear solvers; for example, you can use any of Eigen's sparse linear solvers with the wrapper in eigen_sparse_solver.h, or you could plug in a solver from another library by implementing a similar adapter.
Thank you for your answer.
I am working on a relatively small BA problem (35 poses, 2300 points and around 19k edges).
To understand how code generation works I've generated a reprojection residual. I've modified the bundle_adjustment_in_the_large.py
example by creating a reprojection residual between a sf.Pose3
and a sf.V3
but using a pinhole camera model with sf.LinearCameraCal
. Those intrinsics are known and fixed so I did not include them in the which_args
parameter list of Codegen.
I have then built a graph with the generated factor, following the implementation of bundle_adjustment_in_the_large.cc
but using my own data and optimized using sym::Optimizerd with default params and fixed the first keyframe of the graph.
I did a similar approch but using g2o (with analytical jacobians and the Schur complement trick) and I get to the same optimum as with symforce.
However while symforce converges in fewer (6) iterations than g2o (10), the time per iteration of g2o is lower: around 0.02-0.04s against 0.1 for symforce, making the overall optimisation take 0.2s for g2o against 0.6 for symforce.
Have you been able to compare against g2o in your experiments and is this difference something you have observed? Or on the contrary have you seen that symforce was faster, suggesting an error on my side?
Thank you
It would help if you could post more detailed timing for what part of the iteration time is slower; there are very different reasons depending on that. SymForce should print a table on exit of timing for different parts of the optimization problem; I haven't used g2o much so I'm not sure what timing information they have available
Hi, first of all thanks for your amazing work!
I'm using symforce to solve classical bundle adjustment with 6 DoF poses, 3D points and projection factors. The optimization works as expected, however is the Schur Complement trick used automatically or do I need to do something to enable it to speed up the optimisation?
Thank you