Replies: 5 comments
-
Hi @w-hc, tldr As the update tends to infinitely small, these representations tend to be the same. It is only as the update grows away from zero that the difference shows. @joansola may have a better explanation and most importantly I remember a drawing of several circles for different |
Beta Was this translation helpful? Give feedback.
-
Hi @w-hc This is the drawing @artivis is referring to: They all represent motion integration of a body in the plane, following linear velocity The left sketch is what you do in SE(2). You can see that the black arc is a "simultaneous translation and rotation as a continuum". If
and the whole arc can be computed in just one step, no matter how large In the other sketches, the blue trajectories correspond to integrating motion in R2xSO(2) for different values of
that is, the The red trajectories are not relevant here -- they are just a way to produce "chained translation and rotation" that respects the continuous trajectory at the evaluation points. But this is NOT what happens in plain R2xSO(2). In 3D it's the same idea, just one has to consider the magnitude In almost all practical cases, R3xSO(3) does just fine. However, if you want to use the Lie math for Invariant filtering, that is, if you want to pull from some interesting properties of Lie groups that allow you to build EKF's that act as if they were linear, then you have no more choice and you need to select your group carefully. Read Bonnabel and Barrau papers on these matters is you are interested. |
Beta Was this translation helpful? Give feedback.
-
@joansola, thanks for the concise explanation! Is the figure from an article that is publicly available? I would like to dig a little more into the "integration" part. |
Beta Was this translation helpful? Give feedback.
-
You can consult Section 2.3.4. of this document . However, the document does not deal with Lie theory, just with good old plain motion integration. It happens that the drawing serves well the purpose of this issue. |
Beta Was this translation helpful? Give feedback.
-
Beta Was this translation helpful? Give feedback.
-
On Page 11 of micro lie theory, Section "Example 7: SE(n) vs T(n) x SO(n)", there's a discussion on the difference between these two ways of parameterizing rigid body poses: "simultaneously as a continuum" vs "chained translation+rotation".
I wonder if empirically there is a significant difference for these two approaches, since SE3 does involve more complicated expressions for right Jacobians.
In a similar vein, what would be the practical benefit of Sim3 vs simple rotation + translation + scaling?
I have seen for example that the tutorial by Blanco uses pseudo-exp and pseudo-log for SE3, whereas sophus and lietorch implement full Sim3 support.
Thanks a lot for the help.
Beta Was this translation helpful? Give feedback.
All reactions