Skip to article frontmatterSkip to article content

Jacobians via Kernels...

...and their connection with Fréchet Derivatives

Frank Dellaert, August 2025

Part 1 - SO(3) kernels

This note shows how to compute Jacobians for SO(3) - and later for semidirect products like SE(3), SE₂(3), and Gal(3) - using a compact kernel representation. The key is that many SO(3) operators are polynomials in (\Omega=[\omega]_\times): [ K(\omega) ;=; a,I ; \pm ; b(\theta),\Omega ; + ; c(\theta),\Omega^2,\qquad \theta=|\omega|. ] We call this the kernel. Once we can apply (K(\omega)) and its closed-form derivative with respect to (\omega), we can reuse it everywhere.

SO(3) essentials

Let (\Omega = [\omega]_\times), (\theta=|\omega|). Define (Rodrigues/Eade) [ A=\frac{\sin\theta}{\theta},\qquad B=\frac{1-\cos\theta}{\theta^2},\qquad C=\frac{1-A}{\theta^2},\qquad G=\frac{1-2B}{2\theta^2}. ] Small-angle series: (A=1-\theta^2/6+\cdots), (B=1/2-\theta^2/24+\cdots), (C=1/6-\theta^2/120+\cdots), (G=1/24-\theta^2/720+\cdots).

Three important kernels:

Applying a kernel: y = K(ω) v

For any (v\in\mathbb R^3), we can either explicitly calculate the 3×33\times 3 matrix K(ω)K(\omega) and multiply, [ \boxed{;k(\omega,v) ;=; K(\omega) v ,=, a v + b,(\Omega v) + c,(\Omega^2 v).;} ] or make use of the fact that (\Omega v = \omega\times v) and (\Omega^2 v = \omega\times(\omega\times v)= (\omega\cdot v),\omega - |\omega|^2 v) and write [ k(\omega, v) = a v + b (\omega \times v) + c \big((\omega \cdot v),\omega - |\omega|^2 v\big). ]

Closed-form derivatives of K(ω) v

Denote the radial derivatives (d_b = b’(\theta)/\theta), (d_c = c’(\theta)/\theta). Then the Jacobians of k(.,)k(.,) in its two arguments are: [ \boxed{;\frac{\partial y}{\partial \omega} = (d_b,\Omega v + d_c,\Omega^2 v),\omega^\top; -,b,[v]_\times ;+; c\big(,\omega v^\top + (\omega!\cdot! v),I - 2 v,\omega^\top\big) ;} ] [ \boxed{;\frac{\partial y}{\partial v} = a I + b,\Omega + c,\Omega^2;\equiv; K(\omega).;} ]

GTSAM Kernel API

The GTSAM implementation is centered around two concepts in the gtsam::so3 namespace: ExpmapFunctor and DexpFunctor.

The so3::ExpmapFunctor class is a context object, constructed for a specific rotation vector omega. It efficiently caches geometric quantities like (\theta), (\Omega=[\omega]_\times), and (\Omega^2), and provides the rotation matrix (R(\omega)) via expmap().

The so3::DexpFunctor class builds on ExpmapFunctor by lazily computing the coefficients (A, B, C, \dots) and their derivatives when needed. It provides the kernels for various SO(3) operations:

The so3::Kernel struct, produced by DexpFunctor, holds the (a, b, c) coefficients and their radial derivatives. It provides the core functionality for applying kernels and computing their derivatives.

struct GTSAM_EXPORT Kernel {
  // ... fields a, b, c, db, dc ...

  Matrix3 left() const;   // a I + b W + c WW
  Matrix3 right() const;  // a I - b W + c WW

  Vector3 applyLeft(const Vector3& v, OptionalJacobian<3, 3> Hw = {},
                    OptionalJacobian<3, 3> Hv = {}) const;
  Vector3 applyRight(const Vector3& v, OptionalJacobian<3, 3> Hw = {},
                     OptionalJacobian<3, 3> Hv = {}) const;
};

Using the kernels in Other groups: SE(3) example

In SE(3), we reuse the SO(3) kernels. The kernel viewpoint emphasizes that the off-diagonal block is just the derivative (dK(\omega)/d\omega) from Part 1 applied to the translation vector. In the API, this is exactly what the apply() method returns in its Jacobian H1.

The right Jacobian has the block form: [ J_r^{SE(3)}(\omega,\rho) = \begin{pmatrix} J_r(\omega) & 0\[4pt] Q_r(\omega,\rho) & J_r(\omega) \end{pmatrix}. ] The off-diagonal block (Q_r) is obtained by applying the SO(3) kernel (J_r) to the translation vector and taking the derivative with respect to (\omega). In the API, this corresponds to calling apply() on the kernel, with the Jacobian H1 capturing the derivative for the off-diagonal block. This approach leverages the closed-form kernel derivatives developed in Part 1, requiring no additional series or integrals.

Additionally, constructing an SE(3) object from a rotation matrix and a translation introduces another (R^\top). This leads to the following expression for the (Q_r) block: [ Q_r(\omega, \rho) = R^\top \cdot \mathcal{L}{J_r}(\Omega)[-[\rho]\times], ] where (Q_r) is expressed in the body frame, and (R^T = \exp(-\Omega)) ensures the correct frame transformation.

Part 2 - A Cookbook for Group Jacobians

With the theoretical foundation from Part 1 in place, we now have a powerful recipe. We know that for semidirect products, the Jacobians are block-triangular, and the off-diagonal blocks are given by the Fréchet derivative of the corresponding SO(3)SO(3) kernel. This allows us to construct Jacobians for complex groups using our simple kernel building blocks.

This section provides a practical “cookbook” for several common groups. For each group, we will:

  1. Define the tangent vector ξ\xi and the exponential map exp(ξ)\exp(\xi).

  2. Show the resulting block structure of the right Jacobian Jr(ξ)J_r(\xi).

  3. Provide the formulas for each block.

SE(3)\text{SE}(3) - Special Euclidean Group

The group of rigid body motions. This section uses the convention adopted by GTSAM for its Pose3 class, which is physically motivated by integrating body-centric velocities.

SE2(3)\text{SE}_2(3) - The NavState

The NavState class in GTSAM implements a specific, influential definition of the SE2(3)SE_2(3) Lie group from the robotics literature (e.g., Barrau, 2012).

This group models a state with three components—rotation, position, and velocity—that evolve in parallel, swept along by the rotation.

Gal(3)\text{Gal}(3) - The Galilean group

The Gal3 class implements Galilean relativity, adding time to SE2(3)SE_2(3). Its Jacobian, as implemented and tested in GTSAM, is the result of formal Lie-theoretic derivations.

Sim(3)Sim(3) - The Similarity Group (GTSAM Convention)

The Similarity3 class in GTSAM models transformations involving rotation, translation, and uniform scaling. Its exponential map is defined by a specialized, scale-aware kernel, implemented in the VFunctor. This functor dynamically creates an kernel adapted to the specific rotation ω\omega and log-scale λ\lambda.

API

Mainly for unit-testing, the ABCKernel API also defines:


  /// Fréchet derivative of left-kernel K(ω) in the direction X ∈ so(3)
  /// L_M(Ω)[X] = b X + c (Ω X + X Ω) + s (db Ω + dc Ω²), with s = -½ tr(Ω X)
  Matrix3 frechet(const Matrix3& X) const;

  /// Apply Fréchet derivative to vector (left specialization)
  Matrix3 applyFrechet(const Vector3& v) const;

A call to applyFrechet should match the H1 derivative of Jacobian().left().apply().

References