Questions about Adjoint Matrix on SE(2) and SE(3)
Closed this issue · 3 comments
Hi! First of all, thank you for providing these invaluable materials. :)
I've studied these materials to fully understand invariant EKF, but there's a question about the Adjoint matrix in matrix_groups/odometry_propagation_se2.m
and matrix_groups/odometry_propagation_se3.m
.
In matrix_groups/odometry_propagation_se2.m
, adjoint matrix is defined as:
% SE(2) Adjoint
robot.Ad = @(X) [X(1:2,1:2), [X(2,3); -X(1,3)]; 0 0 1];
and in matrix_groups/odometry_propagation_se3.m
, the adjoint matrix is defined as:
% SE(3) Adjoint
robot.Ad = @(X) [X(1:3,1:3), skew(X(1:3,4))*X(1:3,1:3); zeros(3), X(1:3,1:3)];
The point is that the forms of adjoints are different from the one explained in Lecture 08, i.e. [R 0; P^R R].
(1:44:30 @ https://www.youtube.com/watch?v=k2miimTn6rk)
Could you explain why these adjoints have a different forms? Thank you in advance!
Oops, I found that SE(3) adjoint is transposed. But how about SE(2) adjoint? I still have no idea...:(
We can choose twist = vec(v, omega) or twist = vec(omega, v). The diagonal remains the same but the nonzero off-diagonal block changes sides to keep the result the same. In my note, I used twist = vec(omega, v) but in the code twist = vec(v, omega). It's good to see both notations because both are valid and you might come across both in the literature.
SE(2) is just a single plane rotation, i.e., R = Rz, and 2D translation, p = [x,y,0]. So it's a subgroup of SE(3) (rotation and translation in the 2d plane). To get the SE(2) adjoint you can do the following calculation in MATLAB (or using other symbolic packages in Python or Julia).
>> syms t x y wz v1 v2 real
>> p = [x; y; 0]; R = [cos(t) -sin(t) 0; sin(t) cos(t) 0; 0 0 1];
>> Adq = [R, zeros(3); skew(p)*R, R] * [0;0;wz; v1;v2;0] % Ad(q)
0
0
wz
wz*y + v1*cos(t) - v2*sin(t)
v2*cos(t) - wz*x + v1*sin(t)
0
Which you can verify is the same as
>> [1 0 0; y cos(t) -sin(t); -x cos(t) sin(t)] * [wz;v1;v2]
wz
wz*y + v1*cos(t) - v2*sin(t)
v1*cos(t) - wz*x + v2*sin(t)
We learn that the Adjoint of SE(2), if we choose twist = vec(omega_z, v1, v2), is Ad(X=(R,p)) = [ 1 0 0; y R_11 R_12; -x R_21 R_22] where R = [R_11 R_12; R_21 R_22] is the 2D rotation matrix.
You can verify that if we choose twist = vec(v1, v2, omega_z), then the correct Adjoint matrix is Ad(X=(R,p)) = [ R_11 R_12 y; R_21 R_22 -x; 0 0 1].
Sorry for the late reply, Ghaffari. I fully understand it. You're the GOAT!!!!! Thank you for your kind reply :)