Fix subset of [Eigen]QuaternionParameterization?

360 views
Skip to first unread message

Arne Jacobs

unread,
Jan 21, 2022, 11:30:13 AM1/21/22
to Ceres Solver
Hi!

I am using the EigenQuaternionParamerization to optimize for a rotation given some measurements. Now I have some cases where I want to restrict the rotation to be only around the Z axis. In the past I just used one single parameter (angle around the Z axis) for this, but it would be nice to keep the quaternion representation of the rotation and to reuse the code for the corresponding residual computation.

It is not possible currently to associate two LocalParameterization objects with a parameter block (apart maybe from combining them with ProductParameterization, but this serves a different purpose), is that correct?

I would think that it's possible to create a special LocalParameterization to constrain a quaternion parameter to a rotation around a given axis, but I don't understand the math behind it yet. But is it possible to have a class that combines two arbitrary LocalParameteration objects with sort-of an AND function? One use case could be to combine SubsetParameterization and QuaternionParameterization to have a quaternion AND keep qx and qy constant.

I would also be glad for any pointers to where I need to look to better understand the theory behind creating a new LocalParameterization class.

Thanks a lot!

Kind regards,
Jarne

Sameer Agarwal

unread,
Jan 21, 2022, 12:57:28 PM1/21/22
to ceres-...@googlegroups.com
Hi Arne,


On Fri, Jan 21, 2022 at 8:30 AM 'Arne Jacobs' via Ceres Solver <ceres-...@googlegroups.com> wrote:
Hi!

I am using the EigenQuaternionParamerization to optimize for a rotation given some measurements. Now I have some cases where I want to restrict the rotation to be only around the Z axis. In the past I just used one single parameter (angle around the Z axis) for this, but it would be nice to keep the quaternion representation of the rotation and to reuse the code for the corresponding residual computation.

It is not possible currently to associate two LocalParameterization objects with a parameter block (apart maybe from combining them with ProductParameterization, but this serves a different purpose), is that correct?

No this is not possible, because generally speaking it makes no mathematical sense to do that.
 
I would think that it's possible to create a special LocalParameterization to constrain a quaternion parameter to a rotation around a given axis, but I don't understand the math behind it yet. But is it possible to have a class that combines two arbitrary LocalParameteration objects with sort-of an AND function? One use case could be to combine SubsetParameterization and QuaternionParameterization to have a quaternion AND keep qx and qy constant.

There is no general way of doing this combination so Ceres does not support it. 

A single parameter that maps to a rotation around the z axis is straightforward to do. If you insist on using quaternions you can first construct a 3 vector [0,0,z] where z is the rotation around the z axis and then convert it into a quaternion using AngleAxisToQuaternion and apply it, which would roughly amount to constructing the quaternion:
q = [cos(z), 0, 0, sin(z)]

and then computing Plus(x, z) = QuaternionProduct(x, q)

I would also be glad for any pointers to where I need to look to better understand the theory behind creating a new LocalParameterization class.

Have a look at the documentation for LocalParameterization (or Manifolds going forward) and the code implementing it. Also Hartley & Zisserman's appendix 6 has a good discussion. Finally I recommend reading "Integrating Generic Sensor Fusion Algorithms with Sound State Representations through Encapsulation of Manifolds" By C. Hertzberg, R. Wagner, U. Frese and L. Schroder https://arxiv.org/pdf/1107.1119.pdf

Sameer
 

Thanks a lot!

Kind regards,
Jarne

--
You received this message because you are subscribed to the Google Groups "Ceres Solver" group.
To unsubscribe from this group and stop receiving emails from it, send an email to ceres-solver...@googlegroups.com.
To view this discussion on the web visit https://groups.google.com/d/msgid/ceres-solver/64d90705-a099-4a0a-9b13-2eb992066c39n%40googlegroups.com.

Arne Jacobs

unread,
Jan 21, 2022, 2:59:12 PM1/21/22
to Ceres Solver

Thanks for all the tips, Sameer!

There is no general way of doing this combination so Ceres does not support it. 

Pity, I was  hoping it'd be as easy as the product of two parameterizations.
Will have a look at your suggested reads!

With kind regards,
Jarne
Reply all
Reply to author
Forward
0 new messages