Replies: 3 comments 6 replies
-
Franck, it is less about accuracy and more about consistency and convergence. With consistency, I mean how well the actual error matches with the estimated uncertainty. Thus, you can trust a consistent estimate that the provided covariance reflects well the belief about the error. Guaranteed convergence is important for large initial deviations or if strong noise is present. With the Lie algebra / group formulation, one can show that consistency and global convergence are guaranteed under certain assumptions. This is the power of this approach. Nevertheless, it can have an impact on accuracy as well. |
Beta Was this translation helpful? Give feedback.
-
Hi Franck. Thanks for this question. Good answers to your question may vary a lot. They can go beyond what Stefan explains above. For example, there is the conceptual benefits of having a theory that abstracts the mechanisms of many different mathematical objects. So you can use the same concepts in unit quaternions, rotaiton matrices in 2 and 3 dims, unit complex numbers, transforms in 2 and 3 dims (the SE(n) groups), the similarity groups, the Galilean group (useful for IMU systems), and many more. Without the unifying framework of Lie theory, you can come up with perfectly accurate solutions for all of these systems, but you have to engineer them explicitly each time. Lie theory allows you to understand all these things at once, then work confidently on each one of them, using the same principles, with the assurance that you are doing things properly. The idea of conceptualizing and abstracting is interesting per se, and has practical outcome when it comes to implementing software. In manif, we have abstracted all the common concepts, and you can find generic code for interpolating, that you can use in SO2, SO3, SE2 and SE3. At the end, it is a bit like saying: I can add number 7 eight times to obtain 56. Why do I need multiplication if just summing gives the same exacdt result? Well, multiplication is a tool that allows you do do much more than just add number 7 eight times. Lie theory is the same thing when compared to 3x3 rotation matrices. It allows you to apply the concepts to other domains, and still be sure that you are doing it fine. Another practical advantage is this. Imagine you are in SE3. You have a pose
this is fine but it is not accurate. In fact, you are rotating at the same time as translating, proceeding in an arc-shaped trajectory, and therefore the equation What you want is to make sure that at each moment you have accumulated the exact rotation so that your velocity is pointed at all times to the right direction, making an arc. This you achieve with the exponential map of SE(3), like so:
Now you can see that the update expression for T is different than before, and that the exponential map of SE(3) gives you a more accurate solution than just translating and rotating in the R3 and SO(3) groups separately. The matrix V(dtheta) captures the fact that the trajectory is an arc and not a straight line. The compact form of writing this update using the exponential of SE(3), which is absolutely equivalent to the above, is:
where
or what you would do using unit quaternions
or even what you do in pure translations in R^3
since in R3 you have the trivial exponential map I hope this all makes sense to you. |
Beta Was this translation helpful? Give feedback.
-
A few quick facts for you to ground some concepts: Rotation matrices are what SO(3) is about, with and without Lie theory. In the context of Lie theory, you apply composition to two matrices. In SO(3), composition is achieved through matrix product. Therefore, composing rotations "using Lie theory" is exactly the same as multiplying rotation matrices. Therefore, the result is the same exactly. In Eigen, rotation composition is done with matrix multiplication. So there is nothing to add to what it has been said in the paragraph above. Internally, however, Eigen uses quaternions sometimes. Composing quaternions is done through quaternion product, again irrespectively of if you want to call it "Lie theory" or not. Also, quaternions can be exactly converted to rotation matrices, and the product of quaternions becoms exactly equivalent to the product of rotation matrices. Again, it does not matter what you do, you always obtain the same exact result. Now on to covariances and Jacobians. In 3x3 rot matrtices, you have 9 parameters. If you go the naive way, the covariance of such matrix is a 9x9 matrix. This is an awful approach. People used to use quaternions, which have 4 parameters. Then, the naive covariance of a quaternion is a 4x4 matrix. This is better than 9x9, but still wrong, since one dimension is blocked. What you want is a 3x3 covariance matrix. Lie theory gives you the framework to properly define 3x3 covariance matrices for rotations. It does so by defining the uncertainty in the tangent space, which is 3-dimensional. To do so, all Jacobians in Lie theory transform from tangent space to tangent space, and they have minimal dimension. Out of Lie theory, all these issues are really messy, and most of the times only approximately accurate. |
Beta Was this translation helpful? Give feedback.
-
Why are Lie algebra / group useful in practice?
I read about Lie algebra / group: basically, I understand that:
OK, that for the theory: using Lie theory allows to get exact result (up to numerical precision)... But in practice, in robotics daily life, why would I care? In all I read, there is never an example that could explain why (i.e. compare with the naive approach and see the benefits).
Could someone give an pragmatic concrete daily-life example? In robotics for example, what example can I use to conclude "if I would have done this naively, I would have ended-up with this big error, but, as I use Lie algebra / group my final error is epsilon machine"?
Is multiplying rotation matrices such an example? Not sure as AFAIU, if I multiply for instance a rotation matrix of 45 degrees over the x-axis with itself I get exactly a rotation matrix of 90 degrees over the x-axis, right? There is no approximation or error here: the Lie theory will not help to get better result. Iterative Closest Point has rotation matrix backed deep in the algorithm, it goes the naive way but doesn't use Lie theory AFAIK and everything seems fine. I am not sure to understand why and when using the Lie theory make a difference.
My question is: what kind of practical example (in robotics for instance) can show the benefit of using Lie theory and illustrate that if I go the naive-way I get an incorrect result (that would have been correct using Lie theory)?
In other words, in which kind of problems must I use Lie theory to avoid errors?
Beta Was this translation helpful? Give feedback.
All reactions