The SL4
class represents an element of the Special Linear Group SL(4), which is the group of all 4x4 real matrices with a determinant of 1. This group is fundamental in projective geometry, where it can represent transformations like 3D homographies.
Unlike Pose3
, which represents rigid-body motions in Euclidean space (the group SE(3)), SL4
transformations can include shearing and non-uniform scaling, and they do not necessarily preserve distances, angles, or parallelism. It is a 15-parameter Lie group. For users familiar with computer vision, this is the group of 3D projective transformations, a.k.a. homographies.
import gtsam
from gtsam import SL4
import numpy as np
Initialization and Properties¶
An SL4
element can be initialized in several ways:
With no arguments to create an identity transform (a 4x4 identity matrix).
From a 4x4
numpy
matrix. GTSAM will automatically normalize the matrix to ensure its determinant is 1. This is done by dividing the matrix by . Note that the determinant must be positive.
# Identity transform
s_identity = gtsam.SL4()
print(f"Identity:\n{s_identity.matrix()}\n")
# Create from a numpy matrix
# Note that det(M) = 16. SL4 will normalize this.
M = 2 * np.eye(4)
print(f"Original Matrix (det=16):\n{M}\n")
S1 = SL4(M / np.power(np.linalg.det(M), 1.0/4.0))
print(f"S1 Matrix (normalized, det={np.linalg.det(S1.matrix()):.1f}):\n{np.round(S1.matrix(), 3)}\n")
Identity:
[[1. 0. 0. 0.]
[0. 1. 0. 0.]
[0. 0. 1. 0.]
[0. 0. 0. 1.]]
Original Matrix (det=16):
[[2. 0. 0. 0.]
[0. 2. 0. 0.]
[0. 0. 2. 0.]
[0. 0. 0. 2.]]
S1 Matrix (normalized, det=1.0):
[[1. 0. 0. 0.]
[0. 1. 0. 0.]
[0. 0. 1. 0.]
[0. 0. 0. 1.]]
Group Operations¶
SL4
implements the standard Lie group operations: Identity
, inverse
, and compose
(via the *
operator).
# Create a second transform
S2_matrix = np.array([
[1, -0.5, 0, 1],
[0.5, 0.866, 0, 1],
[0, 0, 1, 0],
[0, 0, 0, 1]
])
S2 = SL4(S2_matrix / np.power(np.linalg.det(S2_matrix), 1.0/4.0))
print(f"S2:\n{np.round(S2.matrix(), 3)}\n")
# Inverse
s_inv = S1.inverse()
print(f"S1.inverse():\n{np.round(s_inv.matrix(), 3)}\n")
# Composition (group product)
s_composed = S1 * S2
print(f"S1 * S2:\n{np.round(s_composed.matrix(), 3)}\n")
S2:
[[ 0.973 -0.486 0. 0.973]
[ 0.486 0.843 0. 0.973]
[ 0. 0. 0.973 0. ]
[ 0. 0. 0. 0.973]]
S1.inverse():
[[ 1. -0. 0. -0.]
[-0. 1. -0. 0.]
[ 0. -0. 1. -0.]
[-0. 0. -0. 1.]]
S1 * S2:
[[ 0.973 -0.486 0. 0.973]
[ 0.486 0.843 0. 0.973]
[ 0. 0. 0.973 0. ]
[ 0. 0. 0. 0.973]]
Lie Algebra¶
The Lie algebra of SL(4), denoted sl(4)
, is the tangent space at the identity. It is represented by a 15-dimensional vector xi
. This vector can be mapped to a 4x4 matrix in the Lie algebra using the Hat
operator; these algebra matrices are characterized by having a trace of zero. The Expmap
and Logmap
functions convert between the 15-D Lie algebra vector and the Lie group SL4
.
# Logarithm map: from group to Lie algebra
xi_log = SL4.Logmap(S1)
print(f"Logmap(S1) = {np.round(xi_log, 3)}\n")
# Exponential map: from Lie algebra to group
S_exp = SL4.Expmap(xi_log)
print(f"Expmap(xi):\n{np.round(S_exp.matrix(), 3)}\n")
Logmap(S1) = [ 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -0.]
Expmap(xi):
[[1. 0. 0. 0.]
[0. 1. 0. 0.]
[0. 0. 1. 0.]
[0. 0. 0. 1.]]
The Hat
and Vee
operators convert between the 15-dimensional vector xi
and the 4x4 matrix representation of the Lie algebra sl(4)
.
# Hat: from 15D vector to 4x4 Lie algebra matrix
X_hat = SL4.Hat(xi_log)
print(f"Hat(xi):\n{np.round(X_hat, 3)}\n")
# Vee: from 4x4 Lie algebra matrix to 15D vector
xi_vee = SL4.Vee(X_hat)
print(f"Vee(X): {np.round(xi_vee, 3)}\n")
Hat(xi):
[[ 0. 0. 0. 0.]
[ 0. 0. 0. 0.]
[ 0. 0. -0. 0.]
[ 0. 0. 0. 0.]]
Vee(X): [ 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. -0.]