Skip to content

Commit

Permalink
fix bug on computation of SO(3) logmap
Browse files Browse the repository at this point in the history
when theta near 0 (or 2pi, 4pi...)
  • Loading branch information
tmcg0 authored Jun 1, 2021
1 parent d5dbaf7 commit 4ef4338
Showing 1 changed file with 2 additions and 1 deletion.
3 changes: 2 additions & 1 deletion gtsam/geometry/SO3.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -278,7 +278,8 @@ Vector3 SO3::Logmap(const SO3& Q, ChartJacobian H) {
} else {
// when theta near 0, +-2pi, +-4pi, etc. (trace near 3.0)
// use Taylor expansion: theta \approx 1/2-(t-3)/12 + O((t-3)^2)
magnitude = 0.5 - tr_3 * tr_3 / 12.0;
// see https://github.com/borglab/gtsam/issues/746 for details
magnitude = 0.5 - tr_3 / 12.0;
}
omega = magnitude * Vector3(R32 - R23, R13 - R31, R21 - R12);
}
Expand Down

0 comments on commit 4ef4338

Please sign in to comment.