testAHRSFactor.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 
22 #include <gtsam/inference/Symbol.h>
25 #include <gtsam/base/debug.h>
27 
28 #include <boost/bind.hpp>
29 #include <list>
30 
31 using namespace std;
32 using namespace gtsam;
33 
34 // Convenience for named keys
38 
40 
41 // Define covariance matrices
42 double accNoiseVar = 0.01;
43 const Matrix3 kMeasuredAccCovariance = accNoiseVar * I_3x3;
44 
45 //******************************************************************************
46 namespace {
47 Vector callEvaluateError(const AHRSFactor& factor, const Rot3 rot_i,
48  const Rot3 rot_j, const Vector3& bias) {
49  return factor.evaluateError(rot_i, rot_j, bias);
50 }
51 
52 Rot3 evaluateRotationError(const AHRSFactor& factor, const Rot3 rot_i,
53  const Rot3 rot_j, const Vector3& bias) {
54  return Rot3::Expmap(factor.evaluateError(rot_i, rot_j, bias).tail(3));
55 }
56 
57 AHRSFactor::PreintegratedMeasurements evaluatePreintegratedMeasurements(
58  const Vector3& bias, const list<Vector3>& measuredOmegas,
59  const list<double>& deltaTs,
60  const Vector3& initialRotationRate = Vector3::Zero()) {
62 
63  list<Vector3>::const_iterator itOmega = measuredOmegas.begin();
64  list<double>::const_iterator itDeltaT = deltaTs.begin();
65  for (; itOmega != measuredOmegas.end(); ++itOmega, ++itDeltaT) {
66  result.integrateMeasurement(*itOmega, *itDeltaT);
67  }
68 
69  return result;
70 }
71 
72 Rot3 evaluatePreintegratedMeasurementsRotation(
73  const Vector3& bias, const list<Vector3>& measuredOmegas,
74  const list<double>& deltaTs,
75  const Vector3& initialRotationRate = Vector3::Zero()) {
76  return Rot3(
77  evaluatePreintegratedMeasurements(bias, measuredOmegas, deltaTs,
78  initialRotationRate).deltaRij());
79 }
80 
81 Rot3 evaluateRotation(const Vector3 measuredOmega, const Vector3 biasOmega,
82  const double deltaT) {
83  return Rot3::Expmap((measuredOmega - biasOmega) * deltaT);
84 }
85 
86 Vector3 evaluateLogRotation(const Vector3 thetahat, const Vector3 deltatheta) {
87  return Rot3::Logmap(Rot3::Expmap(thetahat).compose(Rot3::Expmap(deltatheta)));
88 }
89 
90 }
91 //******************************************************************************
92 TEST( AHRSFactor, PreintegratedMeasurements ) {
93  // Linearization point
94  Vector3 bias(0,0,0);
95 
96  // Measurements
97  Vector3 measuredOmega(M_PI / 100.0, 0.0, 0.0);
98  double deltaT = 0.5;
99 
100  // Expected preintegrated values
101  Rot3 expectedDeltaR1 = Rot3::RzRyRx(0.5 * M_PI / 100.0, 0.0, 0.0);
102  double expectedDeltaT1(0.5);
103 
104  // Actual preintegrated values
105  AHRSFactor::PreintegratedMeasurements actual1(bias, Z_3x3);
106  actual1.integrateMeasurement(measuredOmega, deltaT);
107 
108  EXPECT(assert_equal(expectedDeltaR1, Rot3(actual1.deltaRij()), 1e-6));
109  DOUBLES_EQUAL(expectedDeltaT1, actual1.deltaTij(), 1e-6);
110 
111  // Integrate again
112  Rot3 expectedDeltaR2 = Rot3::RzRyRx(2.0 * 0.5 * M_PI / 100.0, 0.0, 0.0);
113  double expectedDeltaT2(1);
114 
115  // Actual preintegrated values
116  AHRSFactor::PreintegratedMeasurements actual2 = actual1;
117  actual2.integrateMeasurement(measuredOmega, deltaT);
118 
119  EXPECT(assert_equal(expectedDeltaR2, Rot3(actual2.deltaRij()), 1e-6));
120  DOUBLES_EQUAL(expectedDeltaT2, actual2.deltaTij(), 1e-6);
121 }
122 
123 //******************************************************************************
124 TEST( AHRSFactor, PreintegratedAhrsMeasurementsConstructor ) {
125  Matrix3 gyroscopeCovariance = Matrix3::Ones()*0.4;
126  Vector3 omegaCoriolis(0.1, 0.5, 0.9);
127  PreintegratedRotationParams params(gyroscopeCovariance, omegaCoriolis);
128  Vector3 bias(1.0,2.0,3.0);
129  Rot3 deltaRij(Rot3::RzRyRx(M_PI / 12.0, M_PI / 6.0, M_PI / 4.0));
130  double deltaTij = 0.02;
131  Matrix3 delRdelBiasOmega = Matrix3::Ones()*0.5;
132  Matrix3 preintMeasCov = Matrix3::Ones()*0.2;
134  boost::make_shared<PreintegratedRotationParams>(params),
135  bias,
136  deltaTij,
137  deltaRij,
138  delRdelBiasOmega,
139  preintMeasCov);
140  EXPECT(assert_equal(gyroscopeCovariance,
141  actualPim.p().getGyroscopeCovariance(), 1e-6));
142  EXPECT(assert_equal(omegaCoriolis,
143  actualPim.p().getOmegaCoriolis().get(), 1e-6));
144  EXPECT(assert_equal(bias, actualPim.biasHat(), 1e-6));
145  DOUBLES_EQUAL(deltaTij, actualPim.deltaTij(), 1e-6);
146  EXPECT(assert_equal(deltaRij, Rot3(actualPim.deltaRij()), 1e-6));
147  EXPECT(assert_equal(delRdelBiasOmega, actualPim.delRdelBiasOmega(), 1e-6));
148  EXPECT(assert_equal(preintMeasCov, actualPim.preintMeasCov(), 1e-6));
149 }
150 
151 /* ************************************************************************* */
152 TEST(AHRSFactor, Error) {
153  // Linearization point
154  Vector3 bias(0.,0.,0.); // Bias
155  Rot3 x1(Rot3::RzRyRx(M_PI / 12.0, M_PI / 6.0, M_PI / 4.0));
156  Rot3 x2(Rot3::RzRyRx(M_PI / 12.0 + M_PI / 100.0, M_PI / 6.0, M_PI / 4.0));
157 
158  // Measurements
160  measuredOmega << M_PI / 100, 0, 0;
161  double deltaT = 1.0;
162  AHRSFactor::PreintegratedMeasurements pim(bias, Z_3x3);
163  pim.integrateMeasurement(measuredOmega, deltaT);
164 
165  // Create factor
166  AHRSFactor factor(X(1), X(2), B(1), pim, kZeroOmegaCoriolis, boost::none);
167 
168  Vector3 errorActual = factor.evaluateError(x1, x2, bias);
169 
170  // Expected error
171  Vector3 errorExpected(3);
172  errorExpected << 0, 0, 0;
173  EXPECT(assert_equal(Vector(errorExpected), Vector(errorActual), 1e-6));
174 
175  // Expected Jacobians
176  Matrix H1e = numericalDerivative11<Vector3, Rot3>(
177  boost::bind(&callEvaluateError, factor, _1, x2, bias), x1);
178  Matrix H2e = numericalDerivative11<Vector3, Rot3>(
179  boost::bind(&callEvaluateError, factor, x1, _1, bias), x2);
180  Matrix H3e = numericalDerivative11<Vector3, Vector3>(
181  boost::bind(&callEvaluateError, factor, x1, x2, _1), bias);
182 
183  // Check rotation Jacobians
184  Matrix RH1e = numericalDerivative11<Rot3, Rot3>(
185  boost::bind(&evaluateRotationError, factor, _1, x2, bias), x1);
186  Matrix RH2e = numericalDerivative11<Rot3, Rot3>(
187  boost::bind(&evaluateRotationError, factor, x1, _1, bias), x2);
188 
189  // Actual Jacobians
190  Matrix H1a, H2a, H3a;
191  (void) factor.evaluateError(x1, x2, bias, H1a, H2a, H3a);
192 
193  // rotations
194  EXPECT(assert_equal(RH1e, H1a, 1e-5));
195  // 1e-5 needs to be added only when using quaternions for rotations
196 
197  EXPECT(assert_equal(H2e, H2a, 1e-5));
198 
199  // rotations
200  EXPECT(assert_equal(RH2e, H2a, 1e-5));
201  // 1e-5 needs to be added only when using quaternions for rotations
202 
203  EXPECT(assert_equal(H3e, H3a, 1e-5));
204  // 1e-5 needs to be added only when using quaternions for rotations
205 }
206 
207 /* ************************************************************************* */
208 TEST(AHRSFactor, ErrorWithBiases) {
209  // Linearization point
210 
211  Vector3 bias(0, 0, 0.3);
212  Rot3 x1(Rot3::Expmap(Vector3(0, 0, M_PI / 4.0)));
213  Rot3 x2(Rot3::Expmap(Vector3(0, 0, M_PI / 4.0 + M_PI / 10.0)));
214 
215  // Measurements
217  measuredOmega << 0, 0, M_PI / 10.0 + 0.3;
218  double deltaT = 1.0;
219 
221  Z_3x3);
222  pim.integrateMeasurement(measuredOmega, deltaT);
223 
224  // Create factor
225  AHRSFactor factor(X(1), X(2), B(1), pim, kZeroOmegaCoriolis);
226 
227  Vector errorActual = factor.evaluateError(x1, x2, bias);
228 
229  // Expected error
230  Vector errorExpected(3);
231  errorExpected << 0, 0, 0;
232  EXPECT(assert_equal(errorExpected, errorActual, 1e-6));
233 
234  // Expected Jacobians
235  Matrix H1e = numericalDerivative11<Vector, Rot3>(
236  boost::bind(&callEvaluateError, factor, _1, x2, bias), x1);
237  Matrix H2e = numericalDerivative11<Vector, Rot3>(
238  boost::bind(&callEvaluateError, factor, x1, _1, bias), x2);
239  Matrix H3e = numericalDerivative11<Vector, Vector3>(
240  boost::bind(&callEvaluateError, factor, x1, x2, _1), bias);
241 
242  // Check rotation Jacobians
243  Matrix RH1e = numericalDerivative11<Rot3, Rot3>(
244  boost::bind(&evaluateRotationError, factor, _1, x2, bias), x1);
245  Matrix RH2e = numericalDerivative11<Rot3, Rot3>(
246  boost::bind(&evaluateRotationError, factor, x1, _1, bias), x2);
247  Matrix RH3e = numericalDerivative11<Rot3, Vector3>(
248  boost::bind(&evaluateRotationError, factor, x1, x2, _1), bias);
249 
250  // Actual Jacobians
251  Matrix H1a, H2a, H3a;
252  (void) factor.evaluateError(x1, x2, bias, H1a, H2a, H3a);
253 
254  EXPECT(assert_equal(H1e, H1a));
255  EXPECT(assert_equal(H2e, H2a));
256  EXPECT(assert_equal(H3e, H3a));
257 }
258 
259 //******************************************************************************
260 TEST( AHRSFactor, PartialDerivativeExpmap ) {
261  // Linearization point
262  Vector3 biasOmega(0,0,0);
263 
264  // Measurements
266  measuredOmega << 0.1, 0, 0;
267  double deltaT = 0.5;
268 
269  // Compute numerical derivatives
270  Matrix expectedDelRdelBiasOmega = numericalDerivative11<Rot3, Vector3>(
271  boost::bind(&evaluateRotation, measuredOmega, _1, deltaT), biasOmega);
272 
273  const Matrix3 Jr = Rot3::ExpmapDerivative(
274  (measuredOmega - biasOmega) * deltaT);
275 
276  Matrix3 actualdelRdelBiasOmega = -Jr * deltaT; // the delta bias appears with the minus sign
277 
278  // Compare Jacobians
279  EXPECT(assert_equal(expectedDelRdelBiasOmega, actualdelRdelBiasOmega, 1e-3));
280  // 1e-3 needs to be added only when using quaternions for rotations
281 
282 }
283 
284 //******************************************************************************
285 TEST( AHRSFactor, PartialDerivativeLogmap ) {
286  // Linearization point
287  Vector3 thetahat;
288  thetahat << 0.1, 0.1, 0;
289 
290  // Measurements
291  Vector3 deltatheta;
292  deltatheta << 0, 0, 0;
293 
294  // Compute numerical derivatives
295  Matrix expectedDelFdeltheta = numericalDerivative11<Vector3, Vector3>(
296  boost::bind(&evaluateLogRotation, thetahat, _1), deltatheta);
297 
298  const Vector3 x = thetahat; // parametrization of so(3)
299  const Matrix3 X = skewSymmetric(x); // element of Lie algebra so(3): X = x^
300  double normx = x.norm();
301  const Matrix3 actualDelFdeltheta = I_3x3 + 0.5 * X
302  + (1 / (normx * normx) - (1 + cos(normx)) / (2 * normx * sin(normx))) * X
303  * X;
304 
305  // Compare Jacobians
306  EXPECT(assert_equal(expectedDelFdeltheta, actualDelFdeltheta));
307 
308 }
309 
310 //******************************************************************************
311 TEST( AHRSFactor, fistOrderExponential ) {
312  // Linearization point
313  Vector3 biasOmega(0,0,0);
314 
315  // Measurements
317  measuredOmega << 0.1, 0, 0;
318  double deltaT = 1.0;
319 
320  // change w.r.t. linearization point
321  double alpha = 0.0;
322  Vector3 deltabiasOmega;
323  deltabiasOmega << alpha, alpha, alpha;
324 
325  const Matrix3 Jr = Rot3::ExpmapDerivative(
326  (measuredOmega - biasOmega) * deltaT);
327 
328  Matrix3 delRdelBiasOmega = -Jr * deltaT; // the delta bias appears with the minus sign
329 
330  const Matrix expectedRot = Rot3::Expmap(
331  (measuredOmega - biasOmega - deltabiasOmega) * deltaT).matrix();
332 
333  const Matrix3 hatRot =
334  Rot3::Expmap((measuredOmega - biasOmega) * deltaT).matrix();
335  const Matrix3 actualRot = hatRot
336  * Rot3::Expmap(delRdelBiasOmega * deltabiasOmega).matrix();
337 
338  // Compare Jacobians
339  EXPECT(assert_equal(expectedRot, actualRot));
340 }
341 
342 //******************************************************************************
343 TEST( AHRSFactor, FirstOrderPreIntegratedMeasurements ) {
344  // Linearization point
345  Vector3 bias = Vector3::Zero();
346 
347  Pose3 body_P_sensor(Rot3::Expmap(Vector3(0, 0.1, 0.1)), Point3(1, 0, 1));
348 
349  // Measurements
350  list<Vector3> measuredOmegas;
351  list<double> deltaTs;
352  measuredOmegas.push_back(Vector3(M_PI / 100.0, 0.0, 0.0));
353  deltaTs.push_back(0.01);
354  measuredOmegas.push_back(Vector3(M_PI / 100.0, 0.0, 0.0));
355  deltaTs.push_back(0.01);
356  for (int i = 1; i < 100; i++) {
357  measuredOmegas.push_back(
358  Vector3(M_PI / 100.0, M_PI / 300.0, 2 * M_PI / 100.0));
359  deltaTs.push_back(0.01);
360  }
361 
362  // Actual preintegrated values
364  evaluatePreintegratedMeasurements(bias, measuredOmegas, deltaTs,
365  Vector3(M_PI / 100.0, 0.0, 0.0));
366 
367  // Compute numerical derivatives
368  Matrix expectedDelRdelBias =
369  numericalDerivative11<Rot3, Vector3>(
370  boost::bind(&evaluatePreintegratedMeasurementsRotation, _1,
371  measuredOmegas, deltaTs, Vector3(M_PI / 100.0, 0.0, 0.0)), bias);
372  Matrix expectedDelRdelBiasOmega = expectedDelRdelBias.rightCols(3);
373 
374  // Compare Jacobians
375  EXPECT(
376  assert_equal(expectedDelRdelBiasOmega, preintegrated.delRdelBiasOmega(), 1e-3));
377  // 1e-3 needs to be added only when using quaternions for rotations
378 }
379 
382 
383 //******************************************************************************
384 TEST( AHRSFactor, ErrorWithBiasesAndSensorBodyDisplacement ) {
385 
386  Vector3 bias(0, 0, 0.3);
387  Rot3 x1(Rot3::Expmap(Vector3(0, 0, M_PI / 4.0)));
388  Rot3 x2(Rot3::Expmap(Vector3(0, 0, M_PI / 4.0 + M_PI / 10.0)));
389 
390  // Measurements
391  Vector3 omegaCoriolis;
392  omegaCoriolis << 0, 0.1, 0.1;
394  measuredOmega << 0, 0, M_PI / 10.0 + 0.3;
395  double deltaT = 1.0;
396 
397  const Pose3 body_P_sensor(Rot3::Expmap(Vector3(0, 0.10, 0.10)),
398  Point3(1, 0, 0));
399 
401 
402  pim.integrateMeasurement(measuredOmega, deltaT);
403 
404  // Check preintegrated covariance
406 
407  // Create factor
408  AHRSFactor factor(X(1), X(2), B(1), pim, omegaCoriolis);
409 
410  // Expected Jacobians
411  Matrix H1e = numericalDerivative11<Vector, Rot3>(
412  boost::bind(&callEvaluateError, factor, _1, x2, bias), x1);
413  Matrix H2e = numericalDerivative11<Vector, Rot3>(
414  boost::bind(&callEvaluateError, factor, x1, _1, bias), x2);
415  Matrix H3e = numericalDerivative11<Vector, Vector3>(
416  boost::bind(&callEvaluateError, factor, x1, x2, _1), bias);
417 
418  // Check rotation Jacobians
419  Matrix RH1e = numericalDerivative11<Rot3, Rot3>(
420  boost::bind(&evaluateRotationError, factor, _1, x2, bias), x1);
421  Matrix RH2e = numericalDerivative11<Rot3, Rot3>(
422  boost::bind(&evaluateRotationError, factor, x1, _1, bias), x2);
423  Matrix RH3e = numericalDerivative11<Rot3, Vector3>(
424  boost::bind(&evaluateRotationError, factor, x1, x2, _1), bias);
425 
426  // Actual Jacobians
427  Matrix H1a, H2a, H3a;
428  (void) factor.evaluateError(x1, x2, bias, H1a, H2a, H3a);
429 
430  EXPECT(assert_equal(H1e, H1a));
431  EXPECT(assert_equal(H2e, H2a));
432  EXPECT(assert_equal(H3e, H3a));
433 }
434 //******************************************************************************
435 TEST (AHRSFactor, predictTest) {
436  Vector3 bias(0,0,0);
437 
438  // Measurements
440  measuredOmega << 0, 0, M_PI / 10.0;
441  double deltaT = 0.2;
443  for (int i = 0; i < 1000; ++i) {
444  pim.integrateMeasurement(measuredOmega, deltaT);
445  }
446  // Check preintegrated covariance
447  Matrix expectedMeasCov(3,3);
448  expectedMeasCov = 200*kMeasuredAccCovariance;
449  EXPECT(assert_equal(expectedMeasCov, pim.preintMeasCov()));
450 
451  AHRSFactor factor(X(1), X(2), B(1), pim, kZeroOmegaCoriolis);
452 
453  // Predict
454  Rot3 x;
455  Rot3 expectedRot = Rot3::Ypr(20*M_PI, 0, 0);
456  Rot3 actualRot = factor.predict(x, bias, pim, kZeroOmegaCoriolis);
457  EXPECT(assert_equal(expectedRot, actualRot, 1e-6));
458 
459  // AHRSFactor::PreintegratedMeasurements::predict
460  Matrix expectedH = numericalDerivative11<Vector3, Vector3>(
461  boost::bind(&AHRSFactor::PreintegratedMeasurements::predict,
462  &pim, _1, boost::none), bias);
463 
464  // Actual Jacobians
465  Matrix H;
466  (void) pim.predict(bias,H);
467  EXPECT(assert_equal(expectedH, H, 1e-8));
468 }
469 //******************************************************************************
472 
473 TEST (AHRSFactor, graphTest) {
474  // linearization point
475  Rot3 x1(Rot3::RzRyRx(0, 0, 0));
476  Rot3 x2(Rot3::RzRyRx(0, M_PI / 4, 0));
477  Vector3 bias(0,0,0);
478 
479  // PreIntegrator
480  Vector3 biasHat(0, 0, 0);
482 
483  // Pre-integrate measurements
484  Vector3 measuredOmega(0, M_PI / 20, 0);
485  double deltaT = 1;
486 
487  // Create Factor
489  noiseModel::Gaussian::Covariance(pim.preintMeasCov());
491  Values values;
492  for (size_t i = 0; i < 5; ++i) {
493  pim.integrateMeasurement(measuredOmega, deltaT);
494  }
495 
496  // pim.print("Pre integrated measurementes");
497  AHRSFactor factor(X(1), X(2), B(1), pim, kZeroOmegaCoriolis);
498  values.insert(X(1), x1);
499  values.insert(X(2), x2);
500  values.insert(B(1), bias);
501  graph.push_back(factor);
502  LevenbergMarquardtOptimizer optimizer(graph, values);
503  Values result = optimizer.optimize();
504  Rot3 expectedRot(Rot3::RzRyRx(0, M_PI / 4, 0));
505  EXPECT(assert_equal(expectedRot, result.at<Rot3>(X(2))));
506 }
507 
508 //******************************************************************************
509 int main() {
510  TestResult tr;
511  return TestRegistry::runAllTests(tr);
512 }
513 //******************************************************************************
Provides additional testing facilities for common data structures.
const Vector3 & biasHat() const
Definition: AHRSFactor.h:79
const Matrix3 & getGyroscopeCovariance() const
int main()
virtual const Values & optimize()
static int runAllTests(TestResult &result)
Eigen::Vector3d Vector3
Definition: Vector.h:43
const Matrix3 & delRdelBiasOmega() const
Factor Graph consisting of non-linear factors.
Global debugging flags.
noiseModel::Diagonal::shared_ptr model
void insert(Key j, const Value &val)
Definition: Values.cpp:140
#define DOUBLES_EQUAL(expected, actual, threshold)
Definition: Test.h:142
TEST(AHRSFactor, PreintegratedMeasurements)
Vector3 kZeroOmegaCoriolis(0, 0, 0)
Eigen::MatrixXd Matrix
Definition: base/Matrix.h:43
#define M_PI
Definition: main.h:78
leaf::MyValues values
Pose2_ Expmap(const Vector3_ &xi)
Definition: Half.h:150
Some functions to compute numerical derivatives.
Pose3 x2(Rot3::Ypr(0.0, 0.0, 0.0), l2)
set noclip points set clip one set noclip two set bar set border lt lw set xdata set ydata set zdata set x2data set y2data set boxwidth set dummy y set format x g set format y g set format x2 g set format y2 g set format z g set angles radians set nogrid set key title set key left top Right noreverse box linetype linewidth samplen spacing width set nolabel set noarrow set nologscale set logscale x set set pointsize set encoding default set nopolar set noparametric set set set set surface set nocontour set clabel set mapping cartesian set nohidden3d set cntrparam order set cntrparam linear set cntrparam levels auto set cntrparam points set size set set xzeroaxis lt lw set x2zeroaxis lt lw set yzeroaxis lt lw set y2zeroaxis lt lw set tics in set ticslevel set tics set mxtics default set mytics default set mx2tics default set my2tics default set xtics border mirror norotate autofreq set ytics border mirror norotate autofreq set ztics border nomirror norotate autofreq set nox2tics set noy2tics set timestamp bottom norotate set rrange[*:*] noreverse nowriteback set trange[*:*] noreverse nowriteback set urange[*:*] noreverse nowriteback set vrange[*:*] noreverse nowriteback set xlabel matrix size set x2label set timefmt d m y n H
NonlinearFactorGraph graph
Matrix< SCALARB, Dynamic, Dynamic > B
Definition: bench_gemm.cpp:36
Vector3 predict(const Vector3 &bias, OptionalJacobian< 3, 3 > H=boost::none) const
Definition: AHRSFactor.cpp:63
T compose(const T &t1, const T &t2)
Definition: lieProxies.h:39
const double & deltaTij() const
EIGEN_DEVICE_FUNC const CosReturnType cos() const
static Rot3 predict(const Rot3 &rot_i, const Vector3 &bias, const PreintegratedMeasurements preintegratedMeasurements, const Vector3 &omegaCoriolis, const boost::optional< Pose3 > &body_P_sensor=boost::none)
Definition: AHRSFactor.cpp:199
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
static const double deltaT
RealScalar alpha
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 &rot_i, const Rot3 &rot_j, const Vector3 &bias, boost::optional< Matrix & > H1=boost::none, boost::optional< Matrix & > H2=boost::none, boost::optional< Matrix & > H3=boost::none) const override
vector of errors
Definition: AHRSFactor.cpp:121
Linear Factor Graph where all factors are Gaussians.
static SmartStereoProjectionParams params
Point3 bias(10,-10, 50)
boost::shared_ptr< Base > shared_ptr
Definition: NoiseModel.h:56
const Matrix3 & preintMeasCov() const
Definition: AHRSFactor.h:80
traits
Definition: chartTesting.h:28
bool assert_equal(const Matrix &expected, const Matrix &actual, double tol)
Definition: Matrix.cpp:42
Matrix3 skewSymmetric(double wx, double wy, double wz)
Definition: base/Matrix.h:404
static const Vector3 measuredOmega(w, 0, 0)
const Matrix3 kMeasuredAccCovariance
boost::optional< Vector3 > getOmegaCoriolis() const
double accNoiseVar
void integrateMeasurement(const Vector3 &measuredOmega, double deltaT)
Definition: AHRSFactor.cpp:50
Pose3 x1
Definition: testPose3.cpp:588
A class for computing marginals in a NonlinearFactorGraph.
EIGEN_DEVICE_FUNC const SinReturnType sin() const
Vector3 Point3
Definition: Point3.h:35
#define X
Definition: icosphere.cpp:20
set noclip points set clip one set noclip two set bar set border lt lw set xdata set ydata set zdata set x2data set y2data set boxwidth set dummy x
Eigen::Matrix< double, Eigen::Dynamic, 1 > Vector


gtsam
Author(s):
autogenerated on Sat May 8 2021 02:46:06