testSO3.cpp
Go to the documentation of this file.
1 /* ----------------------------------------------------------------------------
2 
3  * GTSAM Copyright 2010, Georgia Tech Research Corporation,
4  * Atlanta, Georgia 30332-0415
5  * All Rights Reserved
6  * Authors: Frank Dellaert, et al. (see THANKS for the full author list)
7 
8  * See LICENSE for the license information
9 
10  * -------------------------------------------------------------------------- */
11 
19 #include <gtsam/base/Testable.h>
20 #include <gtsam/base/testLie.h>
21 #include <gtsam/geometry/SO3.h>
22 
23 using namespace std::placeholders;
24 using namespace std;
25 using namespace gtsam;
26 
27 //******************************************************************************
28 TEST(SO3, Identity) {
29  const SO3 R;
30  EXPECT_LONGS_EQUAL(3, R.rows());
31  EXPECT_LONGS_EQUAL(3, SO3::dimension);
32  EXPECT_LONGS_EQUAL(3, SO3::Dim());
33  EXPECT_LONGS_EQUAL(3, R.dim());
35 }
36 
37 //******************************************************************************
38 TEST(SO3, Concept) {
40  GTSAM_CONCEPT_ASSERT(IsManifold<SO3>);
42 }
43 
44 //******************************************************************************
45 TEST(SO3, Constructors) {
46  const Vector3 axis(0, 0, 1);
47  const double angle = 2.5;
48  SO3 Q(Eigen::AngleAxisd(angle, axis));
49  SO3 R = SO3::AxisAngle(axis, angle);
50  EXPECT(assert_equal(Q, R));
51 }
52 
53 /* ************************************************************************* */
54 TEST(SO3, ClosestTo) {
55  Matrix3 M;
56  M << 0.79067393, 0.6051136, -0.0930814, //
57  0.4155925, -0.64214347, -0.64324489, //
58  -0.44948549, 0.47046326, -0.75917576;
59 
60  Matrix expected(3, 3);
61  expected << 0.790687, 0.605096, -0.0931312, //
62  0.415746, -0.642355, -0.643844, //
63  -0.449411, 0.47036, -0.759468;
64 
65  auto actual = SO3::ClosestTo(3 * M);
66  EXPECT(assert_equal(expected, actual.matrix(), 1e-6));
67 }
68 
69 //******************************************************************************
70 namespace {
71 SO3 id;
72 Vector3 z_axis(0, 0, 1), v2(1, 2, 0), v3(1, 2, 3);
73 SO3 R1(Eigen::AngleAxisd(0.1, z_axis));
74 SO3 R2(Eigen::AngleAxisd(0.2, z_axis));
75 } // namespace
76 
77 /* ************************************************************************* */
78 TEST(SO3, ChordalMean) {
79  std::vector<SO3> rotations = {R1, R1.inverse()};
80  EXPECT(assert_equal(SO3(), SO3::ChordalMean(rotations)));
81 }
82 
83 //******************************************************************************
84 // Check that Hat specialization is equal to dynamic version
85 TEST(SO3, Hat) {
86  EXPECT(assert_equal(SO3::Hat(z_axis), SOn::Hat(z_axis)));
87  EXPECT(assert_equal(SO3::Hat(v2), SOn::Hat(v2)));
88  EXPECT(assert_equal(SO3::Hat(v3), SOn::Hat(v3)));
89 }
90 
91 //******************************************************************************
92 // Check that Hat specialization is equal to dynamic version
93 TEST(SO3, Vee) {
94  auto X1 = SOn::Hat(z_axis), X2 = SOn::Hat(v2), X3 = SOn::Hat(v3);
95  EXPECT(assert_equal(SO3::Vee(X1), SOn::Vee(X1)));
96  EXPECT(assert_equal(SO3::Vee(X2), SOn::Vee(X2)));
97  EXPECT(assert_equal(SO3::Vee(X3), SOn::Vee(X3)));
98 }
99 
100 //******************************************************************************
101 TEST(SO3, Local) {
102  Vector3 expected(0, 0, 0.1);
103  Vector3 actual = traits<SO3>::Local(R1, R2);
104  EXPECT(assert_equal((Vector)expected, actual));
105 }
106 
107 //******************************************************************************
108 TEST(SO3, Retract) {
109  Vector3 v(0, 0, 0.1);
110  SO3 actual = traits<SO3>::Retract(R1, v);
111  EXPECT(assert_equal(R2, actual));
112 }
113 
114 //******************************************************************************
115 TEST(SO3, Logmap) {
116  Vector3 expected(0, 0, 0.1);
117  Vector3 actual = SO3::Logmap(R1.between(R2));
118  EXPECT(assert_equal((Vector)expected, actual));
119 }
120 
121 //******************************************************************************
123  Vector3 v(0, 0, 0.1);
124  SO3 actual = R1 * SO3::Expmap(v);
125  EXPECT(assert_equal(R2, actual));
126 }
127 
128 //******************************************************************************
129 TEST(SO3, Invariants) {
130  EXPECT(check_group_invariants(id, id));
131  EXPECT(check_group_invariants(id, R1));
132  EXPECT(check_group_invariants(R2, id));
133  EXPECT(check_group_invariants(R2, R1));
134 
135  EXPECT(check_manifold_invariants(id, id));
136  EXPECT(check_manifold_invariants(id, R1));
137  EXPECT(check_manifold_invariants(R2, id));
138  EXPECT(check_manifold_invariants(R2, R1));
139 }
140 
141 //******************************************************************************
142 TEST(SO3, LieGroupDerivatives) {
147 }
148 
149 //******************************************************************************
150 TEST(SO3, ChartDerivatives) {
151  CHECK_CHART_DERIVATIVES(id, id);
155 }
156 
157 /* ************************************************************************* */
158 TEST(SO3, ExpmapFunctor) {
159  Vector axis = Vector3(0., 1., 0.); // rotation around Y
160  double angle = 3.14 / 4.0;
161  Matrix expected(3,3);
162  expected << 0.707388, 0, 0.706825, 0, 1, 0, -0.706825, 0, 0.707388;
163 
164  // axis angle version
165  so3::ExpmapFunctor f1(axis, angle);
166  SO3 actual1 = f1.expmap();
167  CHECK(assert_equal(expected, actual1.matrix(), 1e-5));
168 
169  // axis angle version, negative angle
170  so3::ExpmapFunctor f2(axis, angle - 2*M_PI);
171  SO3 actual2 = f2.expmap();
172  CHECK(assert_equal(expected, actual2.matrix(), 1e-5));
173 
174  // omega version
175  so3::ExpmapFunctor f3(axis * angle);
176  SO3 actual3 = f3.expmap();
177  CHECK(assert_equal(expected, actual3.matrix(), 1e-5));
178 
179  // omega version, negative angle
180  so3::ExpmapFunctor f4(axis * (angle - 2*M_PI));
181  SO3 actual4 = f4.expmap();
182  CHECK(assert_equal(expected, actual4.matrix(), 1e-5));
183 }
184 
185 /* ************************************************************************* */
186 namespace exmap_derivative {
187 static const Vector3 w(0.1, 0.27, -0.2);
188 }
189 // Left trivialized Derivative of exp(w) wrpt w:
190 // How does exp(w) change when w changes?
191 // We find a y such that: exp(w) exp(y) = exp(w + dw) for dw --> 0
192 // => y = log (exp(-w) * exp(w+dw))
194  using exmap_derivative::w;
195  return SO3::Logmap(SO3::Expmap(-w) * SO3::Expmap(w + dw));
196 }
197 
198 TEST(SO3, ExpmapDerivative) {
199  using exmap_derivative::w;
200  const Matrix actualDexpL = SO3::ExpmapDerivative(w);
201  const Matrix expectedDexpL =
202  numericalDerivative11<Vector3, Vector3>(testDexpL, Vector3::Zero(), 1e-2);
203  EXPECT(assert_equal(expectedDexpL, actualDexpL, 1e-7));
204 
205  const Matrix actualDexpInvL = SO3::LogmapDerivative(w);
206  EXPECT(assert_equal(expectedDexpL.inverse(), actualDexpInvL, 1e-7));
207 }
208 
209 //******************************************************************************
210 TEST(SO3, ExpmapDerivative2) {
211  const Vector3 theta(0.1, 0, 0.1);
212  const Matrix Jexpected = numericalDerivative11<SO3, Vector3>(
213  std::bind(&SO3::Expmap, std::placeholders::_1, nullptr), theta);
214 
215  CHECK(assert_equal(Jexpected, SO3::ExpmapDerivative(theta)));
216  CHECK(assert_equal(Matrix3(Jexpected.transpose()),
217  SO3::ExpmapDerivative(-theta)));
218 }
219 
220 //******************************************************************************
221 TEST(SO3, ExpmapDerivative3) {
222  const Vector3 theta(10, 20, 30);
223  const Matrix Jexpected = numericalDerivative11<SO3, Vector3>(
224  std::bind(&SO3::Expmap, std::placeholders::_1, nullptr), theta);
225 
226  CHECK(assert_equal(Jexpected, SO3::ExpmapDerivative(theta)));
227  CHECK(assert_equal(Matrix3(Jexpected.transpose()),
228  SO3::ExpmapDerivative(-theta)));
229 }
230 
231 //******************************************************************************
232 TEST(SO3, ExpmapDerivative4) {
233  // Iserles05an (Lie-group Methods) says:
234  // scalar is easy: d exp(a(t)) / dt = exp(a(t)) a'(t)
235  // matrix is hard: d exp(A(t)) / dt = exp(A(t)) dexp[-A(t)] A'(t)
236  // where A(t): R -> so(3) is a trajectory in the tangent space of SO(3)
237  // and dexp[A] is a linear map from 3*3 to 3*3 derivatives of se(3)
238  // Hence, the above matrix equation is typed: 3*3 = SO(3) * linear_map(3*3)
239 
240  // In GTSAM, we don't work with the skew-symmetric matrices A directly, but
241  // with 3-vectors.
242  // omega is easy: d Expmap(w(t)) / dt = ExmapDerivative[w(t)] * w'(t)
243 
244  // Let's verify the above formula.
245 
246  auto w = [](double t) { return Vector3(2 * t, sin(t), 4 * t * t); };
247  auto w_dot = [](double t) { return Vector3(2, cos(t), 8 * t); };
248 
249  // We define a function R
250  auto R = [w](double t) { return SO3::Expmap(w(t)); };
251 
252  for (double t = -2.0; t < 2.0; t += 0.3) {
253  const Matrix expected = numericalDerivative11<SO3, double>(R, t);
254  const Matrix actual = SO3::ExpmapDerivative(w(t)) * w_dot(t);
255  CHECK(assert_equal(expected, actual, 1e-7));
256  }
257 }
258 
259 //******************************************************************************
260 TEST(SO3, ExpmapDerivative5) {
261  auto w = [](double t) { return Vector3(2 * t, sin(t), 4 * t * t); };
262  auto w_dot = [](double t) { return Vector3(2, cos(t), 8 * t); };
263 
264  // Now define R as mapping local coordinates to neighborhood around R0.
265  const SO3 R0 = SO3::Expmap(Vector3(0.1, 0.4, 0.2));
266  auto R = [R0, w](double t) { return R0.expmap(w(t)); };
267 
268  for (double t = -2.0; t < 2.0; t += 0.3) {
269  const Matrix expected = numericalDerivative11<SO3, double>(R, t);
270  const Matrix actual = SO3::ExpmapDerivative(w(t)) * w_dot(t);
271  CHECK(assert_equal(expected, actual, 1e-7));
272  }
273 }
274 
275 //******************************************************************************
276 TEST(SO3, ExpmapDerivative6) {
277  const Vector3 thetahat(0.1, 0, 0.1);
278  const Matrix Jexpected = numericalDerivative11<SO3, Vector3>(
279  std::bind(&SO3::Expmap, std::placeholders::_1, nullptr), thetahat);
280  Matrix3 Jactual;
281  SO3::Expmap(thetahat, Jactual);
282  EXPECT(assert_equal(Jexpected, Jactual));
283 }
284 
285 //******************************************************************************
286 TEST(SO3, LogmapDerivative) {
287  const Vector3 thetahat(0.1, 0, 0.1);
288  const SO3 R = SO3::Expmap(thetahat); // some rotation
289  const Matrix Jexpected = numericalDerivative11<Vector, SO3>(
290  std::bind(&SO3::Logmap, std::placeholders::_1, nullptr), R);
291  const Matrix3 Jactual = SO3::LogmapDerivative(thetahat);
292  EXPECT(assert_equal(Jexpected, Jactual));
293 }
294 
295 //******************************************************************************
296 TEST(SO3, JacobianLogmap) {
297  const Vector3 thetahat(0.1, 0, 0.1);
298  const SO3 R = SO3::Expmap(thetahat); // some rotation
299  const Matrix Jexpected = numericalDerivative11<Vector, SO3>(
300  std::bind(&SO3::Logmap, std::placeholders::_1, nullptr), R);
301  Matrix3 Jactual;
302  SO3::Logmap(R, Jactual);
303  EXPECT(assert_equal(Jexpected, Jactual));
304 }
305 
306 //******************************************************************************
307 TEST(SO3, ApplyDexp) {
308  Matrix aH1, aH2;
309  for (bool nearZeroApprox : {true, false}) {
310  std::function<Vector3(const Vector3&, const Vector3&)> f =
311  [=](const Vector3& omega, const Vector3& v) {
312  return so3::DexpFunctor(omega, nearZeroApprox).applyDexp(v);
313  };
314  for (Vector3 omega : {Vector3(0, 0, 0), Vector3(1, 0, 0), Vector3(0, 1, 0),
315  Vector3(0, 0, 1), Vector3(0.1, 0.2, 0.3)}) {
316  so3::DexpFunctor local(omega, nearZeroApprox);
317  for (Vector3 v : {Vector3(1, 0, 0), Vector3(0, 1, 0), Vector3(0, 0, 1),
318  Vector3(0.4, 0.3, 0.2)}) {
319  EXPECT(assert_equal(Vector3(local.dexp() * v),
320  local.applyDexp(v, aH1, aH2)));
321  EXPECT(assert_equal(numericalDerivative21(f, omega, v), aH1));
322  EXPECT(assert_equal(numericalDerivative22(f, omega, v), aH2));
323  EXPECT(assert_equal(local.dexp(), aH2));
324  }
325  }
326  }
327 }
328 
329 //******************************************************************************
330 TEST(SO3, ApplyInvDexp) {
331  Matrix aH1, aH2;
332  for (bool nearZeroApprox : {true, false}) {
333  std::function<Vector3(const Vector3&, const Vector3&)> f =
334  [=](const Vector3& omega, const Vector3& v) {
335  return so3::DexpFunctor(omega, nearZeroApprox).applyInvDexp(v);
336  };
337  for (Vector3 omega : {Vector3(0, 0, 0), Vector3(1, 0, 0), Vector3(0, 1, 0),
338  Vector3(0, 0, 1), Vector3(0.1, 0.2, 0.3)}) {
339  so3::DexpFunctor local(omega, nearZeroApprox);
340  Matrix invDexp = local.dexp().inverse();
341  for (Vector3 v : {Vector3(1, 0, 0), Vector3(0, 1, 0), Vector3(0, 0, 1),
342  Vector3(0.4, 0.3, 0.2)}) {
343  EXPECT(assert_equal(Vector3(invDexp * v),
344  local.applyInvDexp(v, aH1, aH2)));
345  EXPECT(assert_equal(numericalDerivative21(f, omega, v), aH1));
346  EXPECT(assert_equal(numericalDerivative22(f, omega, v), aH2));
347  EXPECT(assert_equal(invDexp, aH2));
348  }
349  }
350  }
351 }
352 
353 //******************************************************************************
354 TEST(SO3, vec) {
355  const Vector9 expected = Eigen::Map<const Vector9>(R2.matrix().data());
356  Matrix actualH;
357  const Vector9 actual = R2.vec(actualH);
358  CHECK(assert_equal(expected, actual));
359  std::function<Vector9(const SO3&)> f = [](const SO3& Q) { return Q.vec(); };
360  const Matrix numericalH = numericalDerivative11(f, R2, 1e-5);
361  CHECK(assert_equal(numericalH, actualH));
362 }
363 
364 //******************************************************************************
366  Matrix3 M;
367  M << 1, 2, 3, 4, 5, 6, 7, 8, 9;
368  SO3 R = SO3::Expmap(Vector3(1, 2, 3));
369  const Matrix3 expected = M * R.matrix();
370  Matrix actualH;
371  const Matrix3 actual = so3::compose(M, R, actualH);
372  CHECK(assert_equal(expected, actual));
373  std::function<Matrix3(const Matrix3&)> f = [R](const Matrix3& M) {
374  return so3::compose(M, R);
375  };
376  Matrix numericalH = numericalDerivative11(f, M, 1e-2);
377  CHECK(assert_equal(numericalH, actualH));
378 }
379 
380 //******************************************************************************
381 int main() {
382  TestResult tr;
383  return TestRegistry::runAllTests(tr);
384 }
385 //******************************************************************************
#define CHECK(condition)
Definition: Test.h:108
Matrix< RealScalar, Dynamic, Dynamic > M
Definition: bench_gemm.cpp:51
Jet< T, N > cos(const Jet< T, N > &f)
Definition: jet.h:426
Quaternion Q
#define GTSAM_CONCEPT_ASSERT(concept)
Definition: base/concepts.h:22
Vector v2
Concept check for values that can be used in unit tests.
static int runAllTests(TestResult &result)
Eigen::Vector3d Vector3
Definition: Vector.h:43
SO inverse() const
inverse of a rotation = transpose
Definition: SOn.h:195
EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const Scalar * data() const
EIGEN_DEVICE_FUNC const VectorBlock< const Coefficients, 3 > vec() const
Matrix expected
Definition: testMatrix.cpp:971
A matrix or vector expression mapping an existing array of data.
Definition: Map.h:94
Vector3 testDexpL(const Vector3 &dw)
Definition: testSO3.cpp:193
bool assert_equal(const Matrix &expected, const Matrix &actual, double tol)
Definition: Matrix.cpp:40
Eigen::MatrixXd Matrix
Definition: base/Matrix.h:39
#define M_PI
Definition: main.h:106
TEST(SO3, Identity)
Definition: testSO3.cpp:28
Rot2 R(Rot2::fromAngle(0.1))
Jet< T, N > sin(const Jet< T, N > &f)
Definition: jet.h:439
Pose2_ Expmap(const Vector3_ &xi)
Definition: BFloat16.h:88
double f2(const Vector2 &x)
3*3 matrix representation of SO(3)
static const Similarity3 id
internal::FixedSizeMatrix< Y, X >::type numericalDerivative11(std::function< Y(const X &)> h, const X &x, double delta=1e-5)
New-style numerical derivatives using manifold_traits.
T compose(const T &t1, const T &t2)
Definition: lieProxies.h:39
internal::FixedSizeMatrix< Y, X1 >::type numericalDerivative21(const std::function< Y(const X1 &, const X2 &)> &h, const X1 &x1, const X2 &x2, double delta=1e-5)
#define CHECK_LIE_GROUP_DERIVATIVES(t1, t2)
Definition: testLie.h:82
static const Vector3 w(0.1, 0.27, -0.2)
SO< 3 > SO3
Definition: SO3.h:34
Vector v3
Eigen::VectorXd Vector
Definition: Vector.h:38
const MatrixNN & matrix() const
Return matrix.
Definition: SOn.h:157
#define EXPECT(condition)
Definition: Test.h:150
Array< int, Dynamic, 1 > v
Point2(* f)(const Point3 &, OptionalJacobian< 2, 3 >)
Vector::Scalar omega(const Vector &t, const Vector &s, RealScalar angle)
Definition: IDRS.h:36
Array< double, 1, 3 > e(1./3., 0.5, 2.)
size_t dim() const
Definition: SOn.h:216
traits
Definition: chartTesting.h:28
#define EXPECT_LONGS_EQUAL(expected, actual)
Definition: Test.h:154
int main()
Definition: testSO3.cpp:381
The quaternion class used to represent 3D orientations and rotations.
Point2 f1(const Point3 &p, OptionalJacobian< 2, 3 > H)
double f4(double x, double y, double z)
Class between(const Class &g) const
Definition: Lie.h:52
#define CHECK_CHART_DERIVATIVES(t1, t2)
Definition: testLie.h:85
double f3(double x1, double x2)
internal::FixedSizeMatrix< Y, X2 >::type numericalDerivative22(std::function< Y(const X1 &, const X2 &)> h, const X1 &x1, const X2 &x2, double delta=1e-5)
size_t rows() const
Definition: SOn.h:159
Class expmap(const TangentVector &v) const
Definition: Lie.h:78
static Rot3 R0
Represents a 3D rotation as a rotation angle around an arbitrary 3D axis.
Point2 t(10, 10)
VectorN2 vec(OptionalJacobian< internal::NSquaredSO(N), dimension > H={}) const
Definition: SOn-inl.h:88


gtsam
Author(s):
autogenerated on Tue Jul 4 2023 02:39:41