a question about GPSFactor

488 views
Skip to first unread message

huanhexiao

unread,
Sep 22, 2020, 7:56:03 AM9/22/20
to gtsam users
Hey there,
I have some questions about the GPSFactor.

1. The "evaluateError()" is :
Vector GPSFactor::evaluateError(const Pose3p,
boost::optional<Matrix&> H) const {
return p.translation(H) -nT_;
}
and the "p.translation(H)" is:
const Point3Pose3::translation(OptionalJacobian<3, 6> H) const {
if (H) *H << Z_3x3, rotation().matrix();
return t_;
}
which means the derivatives of t(p.translation) with respect to R and t is 0_3×3 and R, right?
I mean intuitively the derivative of t(p.translation) w.r.t t should be identity I_3×3. in the "evaluateError()" of GPS factor.

So, How to deduce the derivatives?

2. As we return p.translation(H) -nT_ , the GPSFactor measurement "nT_" must be transformed to the measurement center, e.g., the IMU center, with the translation parameter between GPS antenna and the body center, which is also known as LeverArm. 
If we take the leverarm t_ig as a constant and treat the GPS as 3D(actually 1D) body with the same axes of the IMU, we can define the the transform parameter as T_ig = [Eye(3)  t_ig], just as we do in the VIO system.

How to deduce the derivatives with T_ig?

Thanks in advance!

Dellaert, Frank

unread,
Sep 22, 2020, 8:39:10 AM9/22/20
to huanhexiao, gtsam users
Derivatives can sometimes be weird in GTSAM as they are return tangent vectors in  the local coordinate frame. Take a look at math.pdf to learn more. This is why unit tests are absolutely crucial when creating new functions + derivatives: our intuition is often wrong.

If you have doubts about any derivative, prove to yourself that it is correct with a unit test, or prove to us that it’s wrong with a unit test that fails :-)  helping us find and correct bugs is one of the most valuable contributions to GTSAM !

Frank

From: gtsam...@googlegroups.com <gtsam...@googlegroups.com> on behalf of huanhexiao <huanh...@gmail.com>
Sent: Tuesday, September 22, 2020 7:56:03 AM
To: gtsam users <gtsam...@googlegroups.com>
Subject: [GTSAM] a question about GPSFactor
 
--
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 on the web visit https://groups.google.com/d/msgid/gtsam-users/a844fe98-3f43-4b77-832f-324c3cfa6fb4n%40googlegroups.com.

huanhexiao

unread,
Sep 22, 2020, 9:11:17 PM9/22/20
to gtsam users
Thank u very much for your reply, Frank!
I have learned more about the math.pdf and the unit test, and worked it out. 
Thanks again!

afdasf...@gmail.com

unread,
Oct 2, 2020, 9:10:22 AM10/2/20
to gtsam users

About question 1, I found the weird  derivative is caused by the retract function in struct LieGroup which composes the current pose to the delta pose. And I think this step is used to convert the local delta to global frame. But in the 2D GPS factor example in the Tutorials, the H matrix is I_2X2. This confused me and can you tell me the what causes this difference?

huanhexiao

unread,
Nov 25, 2020, 7:42:52 AM11/25/20
to gtsam users
Have u read math.pdf? There are math derivatives for Pose represented on Lie Group/Algebra.  Some work may be needed for this.
Reply all
Reply to author
Forward
0 new messages