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


gtsam
Author(s):
autogenerated on Sat May 8 2021 02:49:53