Conversion of GTSAM state uncertainty to global Position, Velocity and Euler Angle attitude.

57 views
Skip to first unread message

Mike

unread,
Jan 29, 2026, 1:00:57 PM (8 days ago) Jan 29
to gtsam users
Hello 

GTSAM is working out very well for our prototype application, I am confused about something though - if we want to extract the current estimated state and then convert to a global parametrization using Euler Angles how would we do this? I understand the marginals function call and in my understanding it returns the uncertainty at the local parametrization, I'm wondering how we would convert this to Euler Angles and maintain cross correlation? 

Thanks

Varun Agrawal

unread,
Jan 29, 2026, 1:31:54 PM (8 days ago) Jan 29
to Mike, gtsam users
I want to make sure I understand the question: you're looking for the approach to take the MAP estimate after optimization and convert it to global frame, specifically using Euler Angles?

Your state estimate in the resultant Values object after optimization will be available in the frame you defined it. If it's a Pose, you can get the rotation and then call an additional method to get the Euler angles.

Regards,
Varun Agrawal.


--
You received this message because you are subscribed to the Google Groups "gtsam users" group.
To unsubscribe from this group and stop receiving emails from it, send an email to gtsam-users...@googlegroups.com.
To view this discussion visit https://groups.google.com/d/msgid/gtsam-users/10c103be-099c-4967-b0db-0971b9226ddcn%40googlegroups.com.

Mike

unread,
Jan 30, 2026, 1:43:21 AM (7 days ago) Jan 30
to gtsam users
Apologies, something happened to my first message.

I will try to clarify, we are possibly interested in converting the GTSAM covariances into a global parameterization of the form position, velocity and RPY. I believe I understand how to get the estimated values but I'm wondering how to transform the marginal covariance output to correctly give cross covariances of the position, velocity and RPY states(or if there is a function currently to do this).

Thank you.

Dellaert, Frank

unread,
Jan 30, 2026, 10:29:52 AM (7 days ago) Jan 30
to Mike, gtsam users
Hi Mike,

Marginal covariances on Euler angles are easy. The xyz (and rpy) methods have an optional Jacobian argument, see https://github.com/borglab/gtsam/blob/aed1715546aaa033b96b8c946cf8d1b68ab4ef48/gtsam/geometry/Rot3.cpp#L162

You can do P’ = HPH^T where P is your marginal on rotation ( just 3x3 matrix in top-right).

To get covariances on translation and velocity you can use a similar scheme: both of those methods have Jacobian, but now you use the full 6x6 pose P, or 9x9 NavState P. If speed is an issue, you can inspect the structure of the Jacobians to optimize.

To get *covariance* between rpy and translation and/or velocity is another matter. Might need new Jacobians.

Best!
Frank 

Frank

From: gtsam...@googlegroups.com <gtsam...@googlegroups.com> on behalf of Mike <lowel...@gmail.com>
Sent: Friday, January 30, 2026 1:43:21 AM
To: gtsam users <gtsam...@googlegroups.com>
Subject: Re: [GTSAM] Conversion of GTSAM state uncertainty to global Position, Velocity and Euler Angle attitude.
 
Reply all
Reply to author
Forward
0 new messages