After multiplying a lot of rotation matrices, the end result might not be a valid rotation matrix any more, due to rounding issues (de-orthogonalized)
One way to re-
I don't use Eigen and didn't bother to look up the API but here is a simple, computationally cheap and stable procedure to re-orthogonalize the rotation matrix. This orthogonalization procedure is taken from Direction Cosine Matrix IMU: Theory by William Premerlani and Paul Bizard; equations 19-21.
Let x
, y
and z
be the row vectors of the (slightly messed-up) rotation matrix. Let error=dot(x,y)
where dot()
is the dot product. If the matrix was orthogonal, the dot product of x
and y
, that is, the error
would be zero.
The error
is spread across x
and y
equally: x_ort=x-(error/2)*y
and y_ort=y-(error/2)*x
. The third row z_ort=cross(x_ort, y_ort)
, which is, by definition orthogonal to x_ort
and y_ort
.
Now, you still need to normalize x_ort
, y_ort
and z_ort
as these vectors are supposed to be unit vectors.
x_new = 0.5*(3-dot(x_ort,x_ort))*x_ort
y_new = 0.5*(3-dot(y_ort,y_ort))*y_ort
z_new = 0.5*(3-dot(z_ort,z_ort))*z_ort
That's all, were are done.
It should be pretty easy to implement this with the API provided by Eigen. You can easily come up with other orthoginalization procedures but I don't think it will make a noticable difference in practice. I used the above procedure in my motion tracking application and it worked beatifully; it's both stable and fast.