testRotateFactor.cpp
Go to the documentation of this file.
1 /*
2  * @file testRotateFactor.cpp
3  * @brief Test RotateFactor class
4  * @author Frank Dellaert
5  * @date December 17, 2013
6  */
7 
9 #include <gtsam/base/Testable.h>
14 
15 #include <boost/bind.hpp>
16 #include <boost/assign/std/vector.hpp>
17 #include <vector>
18 
19 using namespace std;
20 using namespace boost::assign;
21 using namespace gtsam;
22 
23 static const double kDegree = M_PI / 180;
24 
25 //*************************************************************************
26 // Create some test data
27 // Let's assume IMU is aligned with aero (X-forward,Z down)
28 // And camera is looking forward.
29 static const Point3 cameraX(0, 1, 0), cameraY(0, 0, 1), cameraZ(1, 0, 0);
30 static const Rot3 iRc(cameraX, cameraY, cameraZ);
31 
32 // Now, let's create some rotations around IMU frame
33 static const Unit3 p1(1, 0, 0), p2(0, 1, 0), p3(0, 0, 1);
34 static const Rot3 i1Ri2 = Rot3::AxisAngle(p1, 1), //
35 i2Ri3 = Rot3::AxisAngle(p2, 1), //
36 i3Ri4 = Rot3::AxisAngle(p3, 1);
37 
38 // The corresponding rotations in the camera frame
39 static const Rot3 c1Zc2 = iRc.inverse() * i1Ri2 * iRc, //
40 c2Zc3 = iRc.inverse() * i2Ri3 * iRc, //
41 c3Zc4 = iRc.inverse() * i3Ri4 * iRc;
42 
43 // The corresponding rotated directions in the camera frame
44 static const Unit3 z1 = iRc.inverse() * p1, //
45 z2 = iRc.inverse() * p2, //
46 z3 = iRc.inverse() * p3;
47 
49 
50 //*************************************************************************
51 TEST (RotateFactor, checkMath) {
52  EXPECT(assert_equal(c1Zc2, Rot3::AxisAngle(z1, 1)));
53  EXPECT(assert_equal(c2Zc3, Rot3::AxisAngle(z2, 1)));
54  EXPECT(assert_equal(c3Zc4, Rot3::AxisAngle(z3, 1)));
55 }
56 
57 //*************************************************************************
59  Model model = noiseModel::Isotropic::Sigma(3, 0.01);
60  RotateFactor f(1, i1Ri2, c1Zc2, model);
61  EXPECT(assert_equal(Z_3x1, f.evaluateError(iRc), 1e-8));
62 
63  Rot3 R = iRc.retract(Vector3(0.1, 0.2, 0.1));
64 #if defined(GTSAM_ROT3_EXPMAP) || defined(GTSAM_USE_QUATERNIONS)
65  Vector expectedE = Vector3(-0.0248752, 0.202981, -0.0890529);
66 #else
67  Vector expectedE = Vector3(-0.0246305, 0.20197, -0.08867);
68 #endif
69  EXPECT( assert_equal(expectedE, f.evaluateError(R), 1e-5));
70 
71  Matrix actual, expected;
72  // Use numerical derivatives to calculate the expected Jacobian
73  {
74  expected = numericalDerivative11<Vector3,Rot3>(
75  boost::bind(&RotateFactor::evaluateError, &f, _1, boost::none), iRc);
76  f.evaluateError(iRc, actual);
77  EXPECT(assert_equal(expected, actual, 1e-9));
78  }
79  {
80  expected = numericalDerivative11<Vector3,Rot3>(
81  boost::bind(&RotateFactor::evaluateError, &f, _1, boost::none), R);
82  f.evaluateError(R, actual);
83  EXPECT(assert_equal(expected, actual, 1e-9));
84  }
85 }
86 
87 //*************************************************************************
88 TEST (RotateFactor, minimization) {
89  // Let's try to recover the correct iRc by minimizing
91  Model model = noiseModel::Isotropic::Sigma(3, 0.01);
95 
96  // Check error at ground truth
97  Values truth;
98  truth.insert(1, iRc);
99  EXPECT_DOUBLES_EQUAL(0, graph.error(truth), 1e-8);
100 
101  // Check error at initial estimate
102  Values initial;
103  Rot3 initialE = iRc.retract(kDegree * Vector3(20, -20, 20));
104  initial.insert(1, initialE);
105 
106 #if defined(GTSAM_ROT3_EXPMAP) || defined(GTSAM_USE_QUATERNIONS)
107  EXPECT_DOUBLES_EQUAL(3545.40, graph.error(initial), 1);
108 #else
109  EXPECT_DOUBLES_EQUAL(3349, graph.error(initial), 1);
110 #endif
111 
112  // Optimize
114  //parameters.setVerbosity("ERROR");
115  LevenbergMarquardtOptimizer optimizer(graph, initial, parameters);
116  Values result = optimizer.optimize();
117 
118  // Check result
119  Rot3 actual = result.at<Rot3>(1);
120  EXPECT(assert_equal(iRc, actual,1e-1));
121 
122  // Check error at result
123  EXPECT_DOUBLES_EQUAL(0, graph.error(result), 1e-4);
124 }
125 
126 //*************************************************************************
128  Model model = noiseModel::Isotropic::Sigma(2, 0.01);
129  RotateDirectionsFactor f(1, p1, z1, model);
130  EXPECT(assert_equal(Z_2x1, f.evaluateError(iRc), 1e-8));
131 
132  Rot3 R = iRc.retract(Vector3(0.1, 0.2, 0.1));
133 
134 #if defined(GTSAM_ROT3_EXPMAP) || defined(GTSAM_USE_QUATERNIONS)
135  Vector expectedE = Vector2(-0.0890529, -0.202981);
136 #else
137  Vector expectedE = Vector2(-0.08867, -0.20197);
138 #endif
139 
140  EXPECT( assert_equal(expectedE, f.evaluateError(R), 1e-5));
141 
142  Matrix actual, expected;
143  // Use numerical derivatives to calculate the expected Jacobian
144  {
145  expected = numericalDerivative11<Vector,Rot3>(
146  boost::bind(&RotateDirectionsFactor::evaluateError, &f, _1,
147  boost::none), iRc);
148  f.evaluateError(iRc, actual);
149  EXPECT(assert_equal(expected, actual, 1e-9));
150  }
151  {
152  expected = numericalDerivative11<Vector,Rot3>(
153  boost::bind(&RotateDirectionsFactor::evaluateError, &f, _1,
154  boost::none), R);
155  f.evaluateError(R, actual);
156  EXPECT(assert_equal(expected, actual, 1e-9));
157  }
158 }
159 
160 //*************************************************************************
161 TEST (RotateDirectionsFactor, minimization) {
162  // Let's try to recover the correct iRc by minimizing
164  Model model = noiseModel::Isotropic::Sigma(2, 0.01);
168 
169  // Check error at ground truth
170  Values truth;
171  truth.insert(1, iRc);
172  EXPECT_DOUBLES_EQUAL(0, graph.error(truth), 1e-8);
173 
174  // Check error at initial estimate
175  Values initial;
176  Rot3 initialE = iRc.retract(kDegree * Vector3(20, -20, 20));
177  initial.insert(1, initialE);
178 
179 #if defined(GTSAM_ROT3_EXPMAP) || defined(GTSAM_USE_QUATERNIONS)
180  EXPECT_DOUBLES_EQUAL(3335.9, graph.error(initial), 1);
181 #else
182  EXPECT_DOUBLES_EQUAL(3162, graph.error(initial), 1);
183 #endif
184 
185  // Optimize
187  LevenbergMarquardtOptimizer optimizer(graph, initial, parameters);
188  Values result = optimizer.optimize();
189 
190  // Check result
191  Rot3 actual = result.at<Rot3>(1);
192  EXPECT(assert_equal(iRc, actual,1e-1));
193 
194  // Check error at result
195  EXPECT_DOUBLES_EQUAL(0, graph.error(result), 1e-4);
196 }
197 
198 //*************************************************************************
199 TEST(RotateDirectionsFactor, Initialization) {
200  // Create a gravity vector in a nav frame that has Z up
201  const Point3 n_gravity(0, 0, -10);
202  const Unit3 n_p(-n_gravity);
203 
204  // NOTE(frank): avoid singularities by using 85/275 instead of 90/270
205  std::vector<double> angles = {0, 45, 85, 135, 180, 225, 275, 315};
206  for (double yaw : angles) {
207  const Rot3 nRy = Rot3::Yaw(yaw * kDegree);
208  for (double pitch : angles) {
209  const Rot3 yRp = Rot3::Pitch(pitch * kDegree);
210  for (double roll : angles) {
211  const Rot3 pRb = Rot3::Roll(roll * kDegree);
212 
213  // Rotation from body to nav frame:
214  const Rot3 nRb = nRy * yRp * pRb;
215  const Vector3 rpy = nRb.rpy() / kDegree;
216 
217  // Simulate measurement of IMU in body frame:
218  const Point3 b_acc = nRb.unrotate(-n_gravity);
219  const Unit3 b_z(b_acc);
220 
221  // Check initialization
222  const Rot3 actual_nRb = RotateDirectionsFactor::Initialize(n_p, b_z);
223  const Vector3 actual_rpy = actual_nRb.rpy() / kDegree;
224  EXPECT_DOUBLES_EQUAL(rpy.x(), actual_rpy.x(), 1e-5);
225  EXPECT_DOUBLES_EQUAL(rpy.y(), actual_rpy.y(), 1e-5);
226  }
227  }
228  }
229 }
230 
231 /* ************************************************************************* */
232 int main() {
233  TestResult tr;
234  return TestRegistry::runAllTests(tr);
235 }
236 /* ************************************************************************* */
237 
static const Unit3 p2(0, 1, 0)
static const double kDegree
static const Rot3 i3Ri4
static const Rot3 i2Ri3
static const Eigen::MatrixBase< Vector3 >::ConstantReturnType Z_3x1
Definition: Vector.h:46
virtual const Values & optimize()
Concept check for values that can be used in unit tests.
static const Unit3 z2
static int runAllTests(TestResult &result)
Eigen::Vector3d Vector3
Definition: Vector.h:43
TEST(RotateFactor, checkMath)
Factor Graph consisting of non-linear factors.
static const Rot3 i1Ri2
static const Unit3 p3(0, 0, 1)
static const Rot3 c3Zc4
static const Unit3 z1
noiseModel::Diagonal::shared_ptr model
void insert(Key j, const Value &val)
Definition: Values.cpp:140
Matrix expected
Definition: testMatrix.cpp:974
Vector evaluateError(const Rot3 &R, boost::optional< Matrix & > H=boost::none) const override
vector of errors returns 2D vector
Definition: RotateFactor.h:53
Definition: test.py:1
static const Rot3 iRc(cameraX, cameraY, cameraZ)
Eigen::MatrixXd Matrix
Definition: base/Matrix.h:43
#define M_PI
Definition: main.h:78
Rot2 R(Rot2::fromAngle(0.1))
Point3 unrotate(const Point3 &p, OptionalJacobian< 3, 3 > H1=boost::none, OptionalJacobian< 3, 3 > H2=boost::none) const
rotate point from world to rotated frame
Definition: Rot3.cpp:136
static const Point3 cameraZ(1, 0, 0)
Values initial
static const Rot3 c1Zc2
noiseModel::Isotropic::shared_ptr Model
Definition: Half.h:150
Some functions to compute numerical derivatives.
NonlinearFactorGraph graph
static const Point3 cameraY(0, 0, 1)
#define EXPECT_DOUBLES_EQUAL(expected, actual, threshold)
Definition: Test.h:162
Rot3 inverse() const
inverse of a rotation
Definition: Rot3.h:311
Represents a 3D point on a unit sphere.
Definition: Unit3.h:42
IsDerived< DERIVEDFACTOR > emplace_shared(Args &&...args)
Emplace a shared pointer to factor of given type.
Definition: FactorGraph.h:172
static const Unit3 z3
Eigen::VectorXd Vector
Definition: Vector.h:38
Values result
const ValueType at(Key j) const
Definition: Values-inl.h:342
#define EXPECT(condition)
Definition: Test.h:151
Point2(* f)(const Point3 &, OptionalJacobian< 2, 3 >)
A nonlinear optimizer that uses the Levenberg-Marquardt trust-region scheme.
Array< double, 1, 3 > e(1./3., 0.5, 2.)
Vector evaluateError(const Rot3 &iRc, boost::optional< Matrix & > H=boost::none) const override
vector of errors returns 2D vector
Definition: RotateFactor.h:105
static ConjugateGradientParameters parameters
static const Unit3 p1(1, 0, 0)
static const Point3 cameraX(0, 1, 0)
traits
Definition: chartTesting.h:28
bool assert_equal(const Matrix &expected, const Matrix &actual, double tol)
Definition: Matrix.cpp:42
Class retract(const TangentVector &v) const
retract as required by manifold concept: applies v at *this
Definition: Lie.h:130
Eigen::Vector2d Vector2
Definition: Vector.h:42
static const Rot3 c2Zc3
boost::shared_ptr< Isotropic > shared_ptr
Definition: NoiseModel.h:541
Vector3 rpy(OptionalJacobian< 3, 3 > H=boost::none) const
Definition: Rot3.cpp:192
Vector3 Point3
Definition: Point3.h:35
double error(const Values &values) const
Rot3 nRb
static const Eigen::MatrixBase< Vector2 >::ConstantReturnType Z_2x1
Definition: Vector.h:45
int main()


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