What is liftJacobian?
The liftJacobian appears in OKVIS when computing Jacobians for a CostFunction in Ceres Solver. It computes the Jacobian of parameters in the minimal space relative to parameters in the naively overparameterized space. Recall that for optimization on manifolds, the scheme “lift-solve-retract” refers to the steps in solving the optimization problem:
- lift - mapping from the manifold to the minimal Euclidean space;
- solve - computing the correction in the Euclidean space;
- retract - applying the correction to the original manifold.
From this viewpoint, the “lift” in liftJacobian implies that the Jacobian is for the mapping from the overparameterized manifold to the tangent space.
Why is liftJacobian needed?
Ceres Solver supports the optimization of entities on manifolds with local parameterization for these entities. In computing derivatives of cost functions, Ceres Solver expects Jacobians of the CostFunction relative to parameters in the naively overparameterized space. In optimization, these Jacobians will be corrected to the minimal space by right multiplying with the LocalParameterizationJacobian (i.e., OplusJacobian), Jacobian of the naively parameterized space relative to the minimal space. And these corrected ones are what actually used in solving the optimization problem if a local parameterization is involved.
To compute Jacobians relative to the naive parameter space, we may use the automatic differentiation inside Ceres Solver. Ideally, these Jacobians can also be obtained by an analytic approach. But often times we only have analytic Jacobians relative to parameters in the minimal space. To convert them to the Jacobians required by Ceres Solver, they need to be right multiplied with the liftJacobian.
In essence, liftJacobian and OplusJacobian (i.e., ComputeJacobian() of a class inheriting ceres::LocalParameterization) are used in pair in Ceres Solver. As long as one of the two is the pseudo inverse of the other, the Ceres Solver should solve correctly.
How is liftJacobian computed?
Consequently, both can be set to the identity matrix (not necessarily square) to save computation in optimization. This technique is used in VINS-Mono.
Of course, they may be computed faithfully with their definitions as in OKVIS. For an entity on a manifold, $\mathbf{x}$, the perturbations in the tangent space and the overparameterized space, $\delta \mathbf{x}$ and $\Delta \mathbf{x}$, respectively, are roughly related by $\mathbf{x} \boxplus \delta \mathbf{x} := \mathbf{x} + \Delta \mathbf{x}$. The liftJacobian is defined as $\mathbf{J} = \frac{\partial \delta \mathbf{x}}{\partial \Delta \mathbf{x}}$.
Its counterpart ComputeJacobian().
The LocalParameterization class can be derived to represent the tangent space of an entity on a manifold. To achieve this, two virtual abstract functions, Plus() and ComputeJacobian(), should be defined. Behind the curtain, ComputeJacobian() of a LocalParameterization is used to compute the local_parameterization_jacobian_ of a ParameterBlock hooked with the LocalParameterization. The local_parameterization_jacobian_ is (accessed through LocalParameterizationJacobian()) used only by ResidualBlock::Evaluate() in obtaining the Jacobian of the CostFunction relative to the local parameterization, i.e., parameters in the minimal space.