The manif package differentiates Jacobians with respect to a local perturbation on the tangent space. These Jacobians map tangent spaces, as described in this paper.
However, many non-linear solvers
(e.g. Ceres) expect functions to be differentiated with respect to the
underlying representation vector of the group element
(e.g. with respect to quaternion vector for SO3
).
For this reason manif is compliant with the
CppAD::AD<Scalar>
(forward/reverse) auto-differentiation type.
For reference of the size of the Jacobians returned when using CppAD::AD<Scalar>
,
manif implements rotations in the following way:
- SO(2) and SE(2): as a complex number with
real = cos(theta)
andimag = sin(theta)
values. - SO(3), SE(3) and SE_2(3): as a unit quaternion, using the underlying
Eigen::Quaternion
type.
Therefore, the respective Jacobian sizes using [autodiff::dual
][autodiff] are as follows:
- ℝ(n) : size n
- SO(2) : size 2
- SO(3) : size 4
- SE(2) : size 4
- SE(3) : size 7
- SE_2(3): size 10
Considering,
a group element (e.g. S3),
the vector tangent to the group at
,
an error function,
one is interested in expressing the Taylor series of the error function,
Therefore we have to compute the Jacobian
the Jacobian of with respect to a perturbation on the tangent space,
so that the state update happens on the manifold tangent space.
In some optimization frameworks, the computation of this Jacobian is decoupled in two folds as explained hereafter.
Using the CppAD library, evaluating a function and its Jacobians may be,
using Scalar = double;
using Ad = CppAD::AD<Scalar>;
using AdFun = CppAD::ADFun<Scalar>;
using VectorXs = Eigen::Matrix<Scalar, Eigen::Dynamic, 1>;
using VectorXad = Eigen::Matrix<Ad, Eigen::Dynamic, 1>;
using LieGroup = manif::SE3<Ad>;
using Tangent = typename LieGroup::Tangent;
// The variable block
VectorXad variables(LieGroup::RepSize + LieGroup::RepSize);
VectorXad variables_out(Tangent::RepSize);
... // Some initialization and such
// Map to manipulate variables as manif objects
Eigen::Map<LieGroup> xi(variables.data()), xj(variables.data()+LieGroup::RepSize);
Eigen::Map<Tangent> e(variables_out.data());
// declare independent variables and start taping
CppAD::Independent(variables);
// Call manif ominus
e = xi - xj;
// create f: xi, xj -> e and stop taping
AdFun ad_fun(variables, variables_out);
// Evaluate the Jacobians
VectorXs jacobians = ad_fun.Jacobian(variables.template cast<Scalar>());
// Map the Jacobian as a matrice
Eigen::Map<
Eigen::Matrix<Scalar, LieGroup::DoF, LieGroup::RepSize*2, Eigen::RowMajor>
> J_e_xixj(jacobians.data());
// With Jacobians as blocks
//
// J_e_xi = J_e_xixj.block(0, 0, LieGroup::DoF, LieGroup::RepSize)
// J_e_xj = J_e_xixj.block(0, LieGroup::RepSize, LieGroup::DoF, LieGroup::RepSize)
It produces Jacobians of the form,
We thus then need to compute the Jacobian that will map to the tangent space - often called local-parameterization. A convenience function is provided in manif to do so as follow:
Eigen::MatrixXd J_xi_lp = cppadLocalParameterizationJacobian(xi);
Eigen::MatrixXd J_xj_lp = cppadLocalParameterizationJacobian(xj);
This function computes the operation's
Jacobian evaluated for
thus providing the Jacobian,
Once both the cost function and local-parameterization's Jacobians are evaluated, they can be compose as,
Voila.
The intermediate Jacobians (2-3) that some solver requires are not available in manif
since the library provides directly the final Jacobian (1)
.
However, manif is compliant with CppAD::AD<Scalar>
auto-differentiation type to compute (2-3).