diff --git a/.cproject b/.cproject
index ac9b166ec..10b16f91c 100644
--- a/.cproject
+++ b/.cproject
@@ -5,13 +5,13 @@
-
-
+
+
@@ -60,13 +60,13 @@
-
-
+
+
@@ -116,13 +116,13 @@
-
-
+
+
@@ -484,341 +484,6 @@
-
- make
- -j5
- testCombinedImuFactor.run
- true
- true
- true
-
-
- make
- -j5
- testImuFactor.run
- true
- true
- true
-
-
- make
- -j5
- testAHRSFactor.run
- true
- true
- true
-
-
- make
- -j8
- testAttitudeFactor.run
- true
- true
- true
-
-
- make
- -j2
- all
- true
- true
- true
-
-
- make
- -j2
- testNonlinearConstraint.run
- true
- true
- true
-
-
- make
- -j2
- testLieConfig.run
- true
- true
- true
-
-
- make
- -j2
- testConstraintOptimizer.run
- true
- true
- true
-
-
- make
- -j2
- testGaussianFactor.run
- true
- true
- true
-
-
- make
- -j4
- testImuFactor.run
- true
- true
- true
-
-
- make
- -j2
- all
- true
- true
- true
-
-
- make
- -j2
- check
- true
- true
- true
-
-
- make
- -j2
- clean
- true
- true
- true
-
-
- make
- -j2
- check
- true
- true
- true
-
-
- make
- -j2
- clean
- true
- true
- true
-
-
- make
- -j2
- testBTree.run
- true
- true
- true
-
-
- make
- -j2
- testDSF.run
- true
- true
- true
-
-
- make
- -j2
- testDSFVector.run
- true
- true
- true
-
-
- make
- -j2
- testMatrix.run
- true
- true
- true
-
-
- make
- -j2
- testSPQRUtil.run
- true
- true
- true
-
-
- make
- -j2
- testVector.run
- true
- true
- true
-
-
- make
- -j2
- timeMatrix.run
- true
- true
- true
-
-
- make
- -j2
- all
- true
- true
- true
-
-
- make
- -j2
- all
- true
- true
- true
-
-
- make
- -j2
- clean
- true
- true
- true
-
-
- make
- -j5
- wrap
- true
- true
- true
-
-
- make
- -j2
- check
- true
- true
- true
-
-
- make
- -j2
- clean
- true
- true
- true
-
-
- make
- -j2
- install
- true
- true
- true
-
-
- make
- -j2
- all
- true
- true
- true
-
-
- cmake
- ..
- true
- false
- true
-
-
- make
- -j2
- check
- true
- true
- true
-
-
- make
- -j2
- tests/testLieConfig.run
- true
- true
- true
-
-
- make
- -j4
- testSimilarity3.run
- true
- true
- true
-
-
- make
- -j5
- testInvDepthCamera3.run
- true
- true
- true
-
-
- make
- -j5
- testTriangulation.run
- true
- true
- true
-
-
- make
- -j4
- testEvent.run
- true
- true
- true
-
-
- make
- -j2
- all
- true
- true
- true
-
-
- make
- -j2
- check
- true
- true
- true
-
-
- make
- -j2
- clean
- true
- true
- true
-
-
- make
- -j5
- all
- true
- false
- true
-
-
- make
- -j5
- check
- true
- false
- true
-
make
-j5
@@ -867,183 +532,39 @@
true
true
-
- make
- -j5
- testCal3Bundler.run
- true
- true
- true
-
-
- make
- -j5
- testCal3DS2.run
- true
- true
- true
-
-
- make
- -j5
- testCalibratedCamera.run
- true
- true
- true
-
-
- make
- -j5
- testEssentialMatrix.run
- true
- true
- true
-
-
- make
- -j1 VERBOSE=1
- testHomography2.run
- true
- false
- true
-
-
- make
- -j5
- testPinholeCamera.run
- true
- true
- true
-
-
- make
- -j5
- testPoint2.run
- true
- true
- true
-
-
- make
- -j5
- testPoint3.run
- true
- true
- true
-
-
- make
- -j5
- testPose2.run
- true
- true
- true
-
-
- make
- -j5
- testPose3.run
- true
- true
- true
-
-
- make
- -j5
- testRot3M.run
- true
- true
- true
-
-
- make
- -j5
- testSphere2.run
- true
- true
- true
-
-
- make
- -j5
- testStereoCamera.run
- true
- true
- true
-
-
- make
- -j5
- testCal3Unified.run
- true
- true
- true
-
-
- make
- -j5
- testRot2.run
- true
- true
- true
-
-
- make
- -j5
- testRot3Q.run
- true
- true
- true
-
-
- make
- -j5
- testRot3.run
- true
- true
- true
-
-
+
make
-j4
- testSO3.run
+ testSimilarity3.run
true
true
true
-
+
+ make
+ -j5
+ testInvDepthCamera3.run
+ true
+ true
+ true
+
+
+ make
+ -j5
+ testTriangulation.run
+ true
+ true
+ true
+
+
make
-j4
- testQuaternion.run
+ testEvent.run
true
true
true
-
- make
- -j4
- testOrientedPlane3.run
- true
- true
- true
-
-
- make
- -j4
- testPinholePose.run
- true
- true
- true
-
-
- make
- -j4
- testCyclic.run
- true
- true
- true
-
-
+
make
-j2
all
@@ -1051,7 +572,7 @@
true
true
-
+
make
-j2
clean
@@ -1059,23 +580,143 @@
true
true
-
+
+ make
+ -k
+ check
+ true
+ false
+ true
+
+
+ make
+
+ tests/testBayesTree.run
+ true
+ false
+ true
+
+
+ make
+
+ testBinaryBayesNet.run
+ true
+ false
+ true
+
+
make
-j2
- clean all
+ testFactorGraph.run
true
true
true
-
+
make
-j2
- install
+ testISAM.run
true
true
true
-
+
+ make
+ -j2
+ testJunctionTree.run
+ true
+ true
+ true
+
+
+ make
+ -j2
+ testKey.run
+ true
+ true
+ true
+
+
+ make
+ -j2
+ testOrdering.run
+ true
+ true
+ true
+
+
+ make
+
+ testSymbolicBayesNet.run
+ true
+ false
+ true
+
+
+ make
+
+ tests/testSymbolicFactor.run
+ true
+ false
+ true
+
+
+ make
+
+ testSymbolicFactorGraph.run
+ true
+ false
+ true
+
+
+ make
+ -j2
+ timeSymbolMaps.run
+ true
+ true
+ true
+
+
+ make
+
+ tests/testBayesTree
+ true
+ false
+ true
+
+
+ make
+ -j2
+ tests/testPose2.run
+ true
+ true
+ true
+
+
+ make
+ -j2
+ tests/testPose3.run
+ true
+ true
+ true
+
+
+ make
+ -j2
+ all
+ true
+ true
+ true
+
+
+ make
+ -j2
+ check
+ true
+ true
+ true
+
+
make
-j2
clean
@@ -1227,6 +868,478 @@
true
true
+
+ make
+ -j5
+ testGaussianFactorGraphUnordered.run
+ true
+ true
+ true
+
+
+ make
+ -j5
+ testGaussianBayesNetUnordered.run
+ true
+ true
+ true
+
+
+ make
+ -j5
+ testGaussianConditional.run
+ true
+ true
+ true
+
+
+ make
+ -j5
+ testGaussianDensity.run
+ true
+ true
+ true
+
+
+ make
+ -j5
+ testGaussianJunctionTree.run
+ true
+ true
+ true
+
+
+ make
+ -j5
+ testHessianFactor.run
+ true
+ true
+ true
+
+
+ make
+ -j5
+ testJacobianFactor.run
+ true
+ true
+ true
+
+
+ make
+ -j5
+ testKalmanFilter.run
+ true
+ true
+ true
+
+
+ make
+ -j5
+ testNoiseModel.run
+ true
+ true
+ true
+
+
+ make
+ -j5
+ testSampler.run
+ true
+ true
+ true
+
+
+ make
+ -j5
+ testSerializationLinear.run
+ true
+ true
+ true
+
+
+ make
+ -j5
+ testVectorValues.run
+ true
+ true
+ true
+
+
+ make
+ -j5
+ testGaussianBayesTree.run
+ true
+ true
+ true
+
+
+ make
+ -j5
+ testCombinedImuFactor.run
+ true
+ true
+ true
+
+
+ make
+ -j5
+ testImuFactor.run
+ true
+ true
+ true
+
+
+ make
+ -j5
+ testAHRSFactor.run
+ true
+ true
+ true
+
+
+ make
+ -j8
+ testAttitudeFactor.run
+ true
+ true
+ true
+
+
+ make
+ -j5
+ clean
+ true
+ true
+ true
+
+
+ make
+ -j5
+ all
+ true
+ true
+ true
+
+
+ make
+ -j2
+ all
+ true
+ true
+ true
+
+
+ make
+ -j2
+ clean
+ true
+ true
+ true
+
+
+ make
+ -j2
+ check
+ true
+ true
+ true
+
+
+ make
+ -j2
+ testGaussianConditional.run
+ true
+ true
+ true
+
+
+ make
+ -j2
+ testGaussianFactor.run
+ true
+ true
+ true
+
+
+ make
+ -j2
+ timeGaussianFactor.run
+ true
+ true
+ true
+
+
+ make
+ -j2
+ timeVectorConfig.run
+ true
+ true
+ true
+
+
+ make
+ -j2
+ testVectorBTree.run
+ true
+ true
+ true
+
+
+ make
+ -j2
+ testVectorMap.run
+ true
+ true
+ true
+
+
+ make
+ -j2
+ testNoiseModel.run
+ true
+ true
+ true
+
+
+ make
+ -j2
+ testBayesNetPreconditioner.run
+ true
+ true
+ true
+
+
+ make
+
+ testErrors.run
+ true
+ false
+ true
+
+
+ make
+ -j2
+ check
+ true
+ true
+ true
+
+
+ make
+ -j2
+ tests/testGaussianJunctionTree.run
+ true
+ true
+ true
+
+
+ make
+ -j2
+ tests/testGaussianFactor.run
+ true
+ true
+ true
+
+
+ make
+ -j2
+ tests/testGaussianConditional.run
+ true
+ true
+ true
+
+
+ make
+ -j2
+ tests/timeSLAMlike.run
+ true
+ true
+ true
+
+
+ make
+ -j2
+ check
+ true
+ true
+ true
+
+
+ make
+ -j2
+ clean
+ true
+ true
+ true
+
+
+ make
+ -j2
+ testBTree.run
+ true
+ true
+ true
+
+
+ make
+ -j2
+ testDSF.run
+ true
+ true
+ true
+
+
+ make
+ -j2
+ testDSFVector.run
+ true
+ true
+ true
+
+
+ make
+ -j2
+ testMatrix.run
+ true
+ true
+ true
+
+
+ make
+ -j2
+ testSPQRUtil.run
+ true
+ true
+ true
+
+
+ make
+ -j2
+ testVector.run
+ true
+ true
+ true
+
+
+ make
+ -j2
+ timeMatrix.run
+ true
+ true
+ true
+
+
+ make
+ -j2
+ all
+ true
+ true
+ true
+
+
+ make
+ -j2
+ check
+ true
+ true
+ true
+
+
+ make
+ -j2
+ testClusterTree.run
+ true
+ true
+ true
+
+
+ make
+ -j2
+ testJunctionTree.run
+ true
+ true
+ true
+
+
+ make
+ -j2
+ tests/testEliminationTree.run
+ true
+ true
+ true
+
+
+ make
+ -j2
+ tests/testSymbolicFactor.run
+ true
+ true
+ true
+
+
+ make
+ -j2
+ tests/testVariableSlots.run
+ true
+ true
+ true
+
+
+ make
+ -j2
+ tests/testConditional.run
+ true
+ true
+ true
+
+
+ make
+ -j2
+ tests/testSymbolicFactorGraph.run
+ true
+ true
+ true
+
+
+ make
+ -j2
+ all
+ true
+ true
+ true
+
+
+ make
+ -j2
+ testNonlinearConstraint.run
+ true
+ true
+ true
+
+
+ make
+ -j2
+ testLieConfig.run
+ true
+ true
+ true
+
+
+ make
+ -j2
+ testConstraintOptimizer.run
+ true
+ true
+ true
+
+
+ make
+ -j2
+ check
+ true
+ true
+ true
+
make
-j2
@@ -1368,23 +1481,95 @@
true
true
-
+
make
- -j2
- all
+ -j5
+ testBTree.run
true
true
true
-
+
make
- -j2
- clean
+ -j5
+ testDSF.run
true
true
true
-
+
+ make
+ -j5
+ testDSFMap.run
+ true
+ true
+ true
+
+
+ make
+ -j5
+ testDSFVector.run
+ true
+ true
+ true
+
+
+ make
+ -j5
+ testFixedVector.run
+ true
+ true
+ true
+
+
+ make
+ -j5
+ testEliminationTree.run
+ true
+ true
+ true
+
+
+ make
+ -j5
+ testInference.run
+ true
+ true
+ true
+
+
+ make
+ -j5
+ testKey.run
+ true
+ true
+ true
+
+
+ make
+ -j1
+ testSymbolicBayesTree.run
+ true
+ false
+ true
+
+
+ make
+ -j1
+ testSymbolicSequentialSolver.run
+ true
+ false
+ true
+
+
+ make
+ -j4
+ testLabeledSymbol.run
+ true
+ true
+ true
+
+
make
-j2
check
@@ -1392,178 +1577,10 @@
true
true
-
+
make
-j2
- testGaussianConditional.run
- true
- true
- true
-
-
- make
- -j2
- testGaussianFactor.run
- true
- true
- true
-
-
- make
- -j2
- timeGaussianFactor.run
- true
- true
- true
-
-
- make
- -j2
- timeVectorConfig.run
- true
- true
- true
-
-
- make
- -j2
- testVectorBTree.run
- true
- true
- true
-
-
- make
- -j2
- testVectorMap.run
- true
- true
- true
-
-
- make
- -j2
- testNoiseModel.run
- true
- true
- true
-
-
- make
- -j2
- testBayesNetPreconditioner.run
- true
- true
- true
-
-
- make
-
- testErrors.run
- true
- false
- true
-
-
- make
- -j5
- testAntiFactor.run
- true
- true
- true
-
-
- make
- -j5
- testPriorFactor.run
- true
- true
- true
-
-
- make
- -j5
- testDataset.run
- true
- true
- true
-
-
- make
- -j5
- testEssentialMatrixFactor.run
- true
- true
- true
-
-
- make
- -j5
- testGeneralSFMFactor_Cal3Bundler.run
- true
- true
- true
-
-
- make
- -j5
- testGeneralSFMFactor.run
- true
- true
- true
-
-
- make
- -j5
- testProjectionFactor.run
- true
- true
- true
-
-
- make
- -j5
- testRotateFactor.run
- true
- true
- true
-
-
- make
- -j5
- testPoseRotationPrior.run
- true
- true
- true
-
-
- make
- -j5
- testImplicitSchurFactor.run
- true
- true
- true
-
-
- make
- -j4
- testRangeFactor.run
- true
- true
- true
-
-
- make
- -j4
- testOrientedPlane3Factor.run
- true
- true
- true
-
-
- make
- -j4
- testSmartProjectionPoseFactor.run
+ tests/testLieConfig.run
true
true
true
@@ -1975,7 +1992,15 @@
false
true
-
+
+ make
+ -j4
+ check.sam
+ true
+ true
+ true
+
+
make
-j2
check
@@ -1983,54 +2008,38 @@
true
true
-
+
make
- tests/testGaussianISAM2
+ -j2
+ clean
+ true
+ true
+ true
+
+
+ make
+ -j2
+ install
+ true
+ true
+ true
+
+
+ make
+ -j2
+ all
+ true
+ true
+ true
+
+
+ cmake
+ ..
true
false
true
-
- make
- -j2
- check
- true
- true
- true
-
-
- make
- -j2
- tests/testGaussianJunctionTree.run
- true
- true
- true
-
-
- make
- -j2
- tests/testGaussianFactor.run
- true
- true
- true
-
-
- make
- -j2
- tests/testGaussianConditional.run
- true
- true
- true
-
-
- make
- -j2
- tests/timeSLAMlike.run
- true
- true
- true
-
-
+
make
-j2
testGaussianFactor.run
@@ -2038,503 +2047,207 @@
true
true
-
+
make
-j5
- testParticleFactor.run
+ testCal3Bundler.run
true
true
true
-
+
make
-j5
- schedulingExample.run
+ testCal3DS2.run
true
true
true
-
+
make
-j5
- schedulingQuals12.run
- true
- true
- true
-
-
- make
- -j5
- schedulingQuals13.run
- true
- true
- true
-
-
- make
- -j5
- testCSP.run
- true
- true
- true
-
-
- make
- -j5
- testScheduler.run
- true
- true
- true
-
-
- make
- -j5
- testSudoku.run
- true
- true
- true
-
-
- make
- -j2
- all
- true
- true
- true
-
-
- make
- -j2
- clean
- true
- true
- true
-
-
- make
- -k
- check
- true
- false
- true
-
-
- make
-
- tests/testBayesTree.run
- true
- false
- true
-
-
- make
-
- testBinaryBayesNet.run
- true
- false
- true
-
-
- make
- -j2
- testFactorGraph.run
- true
- true
- true
-
-
- make
- -j2
- testISAM.run
- true
- true
- true
-
-
- make
- -j2
- testJunctionTree.run
- true
- true
- true
-
-
- make
- -j2
- testKey.run
- true
- true
- true
-
-
- make
- -j2
- testOrdering.run
- true
- true
- true
-
-
- make
-
- testSymbolicBayesNet.run
- true
- false
- true
-
-
- make
-
- tests/testSymbolicFactor.run
- true
- false
- true
-
-
- make
-
- testSymbolicFactorGraph.run
- true
- false
- true
-
-
- make
- -j2
- timeSymbolMaps.run
- true
- true
- true
-
-
- make
-
- tests/testBayesTree
- true
- false
- true
-
-
- make
- -j2
- check
- true
- true
- true
-
-
- make
- -j2
- timeCalibratedCamera.run
- true
- true
- true
-
-
- make
- -j2
- timeRot3.run
- true
- true
- true
-
-
- make
- -j2
- clean
- true
- true
- true
-
-
- make
- -j2
- tests/testPose2.run
- true
- true
- true
-
-
- make
- -j2
- tests/testPose3.run
- true
- true
- true
-
-
- make
- -j2
- SimpleRotation.run
- true
- true
- true
-
-
- make
- -j5
- CameraResectioning.run
- true
- true
- true
-
-
- make
- -j5
- PlanarSLAMExample.run
- true
- true
- true
-
-
- make
- -j2
- all
- true
- true
- true
-
-
- make
- -j2
- easyPoint2KalmanFilter.run
- true
- true
- true
-
-
- make
- -j2
- elaboratePoint2KalmanFilter.run
- true
- true
- true
-
-
- make
- -j5
- Pose2SLAMExample.run
- true
- true
- true
-
-
- make
- -j2
- Pose2SLAMwSPCG_easy.run
- true
- true
- true
-
-
- make
- -j5
- UGM_small.run
- true
- true
- true
-
-
- make
- -j5
- LocalizationExample.run
- true
- true
- true
-
-
- make
- -j5
- OdometryExample.run
- true
- true
- true
-
-
- make
- -j5
- RangeISAMExample_plaza2.run
- true
- true
- true
-
-
- make
- -j5
- SelfCalibrationExample.run
- true
- true
- true
-
-
- make
- -j5
- SFMExample.run
- true
- true
- true
-
-
- make
- -j5
- VisualISAMExample.run
- true
- true
- true
-
-
- make
- -j5
- VisualISAM2Example.run
- true
- true
- true
-
-
- make
- -j5
- Pose2SLAMExample_graphviz.run
- true
- true
- true
-
-
- make
- -j5
- Pose2SLAMExample_graph.run
- true
- true
- true
-
-
- make
- -j5
- SFMExample_bal.run
- true
- true
- true
-
-
- make
- -j5
- Pose2SLAMExample_lago.run
- true
- true
- true
-
-
- make
- -j5
- Pose2SLAMExample_g2o.run
- true
- true
- true
-
-
- make
- -j5
- SFMExample_SmartFactor.run
- true
- true
- true
-
-
- make
- -j4
- Pose2SLAMExampleExpressions.run
- true
- true
- true
-
-
- make
- -j4
- SFMExampleExpressions.run
- true
- true
- true
-
-
- make
- -j4
- SFMExampleExpressions_bal.run
- true
- true
- true
-
-
- make
- -j2
- testRot3.run
- true
- true
- true
-
-
- make
- -j2
- testRot2.run
- true
- true
- true
-
-
- make
- -j2
- testPose3.run
- true
- true
- true
-
-
- make
- -j2
- timeRot3.run
- true
- true
- true
-
-
- make
- -j2
- testPose2.run
- true
- true
- true
-
-
- make
- -j2
- testCal3_S2.run
- true
- true
- true
-
-
- make
- -j2
- testSimpleCamera.run
- true
- true
- true
-
-
- make
- -j2
- testHomography2.run
- true
- true
- true
-
-
- make
- -j2
testCalibratedCamera.run
true
true
true
-
+
+ make
+ -j5
+ testEssentialMatrix.run
+ true
+ true
+ true
+
+
+ make
+ -j1 VERBOSE=1
+ testHomography2.run
+ true
+ false
+ true
+
+
+ make
+ -j5
+ testPinholeCamera.run
+ true
+ true
+ true
+
+
+ make
+ -j5
+ testPoint2.run
+ true
+ true
+ true
+
+
+ make
+ -j5
+ testPoint3.run
+ true
+ true
+ true
+
+
+ make
+ -j5
+ testPose2.run
+ true
+ true
+ true
+
+
+ make
+ -j5
+ testPose3.run
+ true
+ true
+ true
+
+
+ make
+ -j5
+ testRot3M.run
+ true
+ true
+ true
+
+
+ make
+ -j5
+ testSphere2.run
+ true
+ true
+ true
+
+
+ make
+ -j5
+ testStereoCamera.run
+ true
+ true
+ true
+
+
+ make
+ -j5
+ testCal3Unified.run
+ true
+ true
+ true
+
+
+ make
+ -j5
+ testRot2.run
+ true
+ true
+ true
+
+
+ make
+ -j5
+ testRot3Q.run
+ true
+ true
+ true
+
+
+ make
+ -j5
+ testRot3.run
+ true
+ true
+ true
+
+
+ make
+ -j4
+ testSO3.run
+ true
+ true
+ true
+
+
+ make
+ -j4
+ testQuaternion.run
+ true
+ true
+ true
+
+
+ make
+ -j4
+ testOrientedPlane3.run
+ true
+ true
+ true
+
+
+ make
+ -j4
+ testPinholePose.run
+ true
+ true
+ true
+
+
+ make
+ -j4
+ testCyclic.run
+ true
+ true
+ true
+
+
+ make
+ -j4
+ testUnit3.run
+ true
+ true
+ true
+
+
+ make
+ -j4
+ testBearingRange.run
+ true
+ true
+ true
+
+
+ make
+ -j2
+ all
+ true
+ true
+ true
+
+
make
-j2
check
@@ -2542,7 +2255,7 @@
true
true
-
+
make
-j2
clean
@@ -2550,10 +2263,58 @@
true
true
-
+
+ make
+ -j5
+ all
+ true
+ false
+ true
+
+
+ make
+ -j5
+ check
+ true
+ false
+ true
+
+
make
-j2
- testPoint2.run
+ all
+ true
+ true
+ true
+
+
+ make
+ -j2
+ clean
+ true
+ true
+ true
+
+
+ make
+ -j2
+ all
+ true
+ true
+ true
+
+
+ make
+ -j2
+ clean
+ true
+ true
+ true
+
+
+ make
+ -j2
+ clean all
true
true
true
@@ -2598,198 +2359,6 @@
true
true
-
- make
- -j5
- testEliminationTree.run
- true
- true
- true
-
-
- make
- -j5
- testInference.run
- true
- true
- true
-
-
- make
- -j5
- testKey.run
- true
- true
- true
-
-
- make
- -j1
- testSymbolicBayesTree.run
- true
- false
- true
-
-
- make
- -j1
- testSymbolicSequentialSolver.run
- true
- false
- true
-
-
- make
- -j4
- testLabeledSymbol.run
- true
- true
- true
-
-
- make
- -j2
- check
- true
- true
- true
-
-
- make
- -j2
- testClusterTree.run
- true
- true
- true
-
-
- make
- -j2
- testJunctionTree.run
- true
- true
- true
-
-
- make
- -j2
- tests/testEliminationTree.run
- true
- true
- true
-
-
- make
- -j2
- tests/testSymbolicFactor.run
- true
- true
- true
-
-
- make
- -j2
- tests/testVariableSlots.run
- true
- true
- true
-
-
- make
- -j2
- tests/testConditional.run
- true
- true
- true
-
-
- make
- -j2
- tests/testSymbolicFactorGraph.run
- true
- true
- true
-
-
- make
- -j5
- testLago.run
- true
- true
- true
-
-
- make
- -j5
- testLinearContainerFactor.run
- true
- true
- true
-
-
- make
- -j5
- testOrdering.run
- true
- true
- true
-
-
- make
- -j5
- testValues.run
- true
- true
- true
-
-
- make
- -j5
- testWhiteNoiseFactor.run
- true
- true
- true
-
-
- make
- -j4
- testExpression.run
- true
- true
- true
-
-
- make
- -j4
- testAdaptAutoDiff.run
- true
- true
- true
-
-
- make
- -j4
- testCallRecord.run
- true
- true
- true
-
-
- make
- -j4
- testExpressionFactor.run
- true
- true
- true
-
-
- make
- -j4
- testExecutionTrace.run
- true
- true
- true
-
make
-j5
@@ -2822,135 +2391,31 @@
true
true
-
+
make
- -j5
+ -j2
+ check
+ true
+ true
+ true
+
+
+ make
+ -j2
timeCalibratedCamera.run
true
true
true
-
- make
- -j5
- timePinholeCamera.run
- true
- true
- true
-
-
- make
- -j5
- timeStereoCamera.run
- true
- true
- true
-
-
- make
- -j5
- timeLago.run
- true
- true
- true
-
-
- make
- -j5
- timePose3.run
- true
- true
- true
-
-
- make
- -j4
- timeAdaptAutoDiff.run
- true
- true
- true
-
-
- make
- -j4
- timeCameraExpression.run
- true
- true
- true
-
-
- make
- -j4
- timeOneCameraExpression.run
- true
- true
- true
-
-
- make
- -j4
- timeSFMExpressions.run
- true
- true
- true
-
-
- make
- -j4
- timeIncremental.run
- true
- true
- true
-
-
- make
- -j5
- testBTree.run
- true
- true
- true
-
-
- make
- -j5
- testDSF.run
- true
- true
- true
-
-
- make
- -j5
- testDSFMap.run
- true
- true
- true
-
-
- make
- -j5
- testDSFVector.run
- true
- true
- true
-
-
- make
- -j5
- testFixedVector.run
- true
- true
- true
-
-
+
make
-j2
- all
+ timeRot3.run
true
true
true
-
+
make
-j2
clean
@@ -2958,110 +2423,6 @@
true
true
-
- make
- -j5
- testGaussianFactorGraphUnordered.run
- true
- true
- true
-
-
- make
- -j5
- testGaussianBayesNetUnordered.run
- true
- true
- true
-
-
- make
- -j5
- testGaussianConditional.run
- true
- true
- true
-
-
- make
- -j5
- testGaussianDensity.run
- true
- true
- true
-
-
- make
- -j5
- testGaussianJunctionTree.run
- true
- true
- true
-
-
- make
- -j5
- testHessianFactor.run
- true
- true
- true
-
-
- make
- -j5
- testJacobianFactor.run
- true
- true
- true
-
-
- make
- -j5
- testKalmanFilter.run
- true
- true
- true
-
-
- make
- -j5
- testNoiseModel.run
- true
- true
- true
-
-
- make
- -j5
- testSampler.run
- true
- true
- true
-
-
- make
- -j5
- testSerializationLinear.run
- true
- true
- true
-
-
- make
- -j5
- testVectorValues.run
- true
- true
- true
-
-
- make
- -j5
- testGaussianBayesTree.run
- true
- true
- true
-
make
-j5
@@ -3142,18 +2503,66 @@
true
true
-
+
make
- -j2
- all
+ -j5
+ schedulingExample.run
true
true
true
-
+
+ make
+ -j5
+ schedulingQuals12.run
+ true
+ true
+ true
+
+
+ make
+ -j5
+ schedulingQuals13.run
+ true
+ true
+ true
+
+
+ make
+ -j5
+ testCSP.run
+ true
+ true
+ true
+
+
+ make
+ -j5
+ testScheduler.run
+ true
+ true
+ true
+
+
+ make
+ -j5
+ testSudoku.run
+ true
+ true
+ true
+
+
make
-j2
- clean
+ vSFMexample.run
+ true
+ true
+ true
+
+
+ make
+ -j2
+ testVSLAMGraph
true
true
true
@@ -3438,31 +2847,479 @@
true
true
-
+
make
- -j2
- vSFMexample.run
+ -j4
+ testSerializationSLAM.run
true
true
true
-
+
make
-j5
+ testParticleFactor.run
+ true
+ true
+ true
+
+
+ make
+ -j2
+ testGaussianFactor.run
+ true
+ true
+ true
+
+
+ make
+ -j2
+ install
+ true
+ true
+ true
+
+
+ make
+ -j2
clean
true
true
true
-
+
make
- -j5
+ -j2
all
true
true
true
-
+
+ make
+ -j2
+ clean
+ true
+ true
+ true
+
+
+ make
+ -j2
+ all
+ true
+ true
+ true
+
+
+ make
+ -j2
+ clean
+ true
+ true
+ true
+
+
+ make
+ -j5
+ testAntiFactor.run
+ true
+ true
+ true
+
+
+ make
+ -j5
+ testPriorFactor.run
+ true
+ true
+ true
+
+
+ make
+ -j5
+ testDataset.run
+ true
+ true
+ true
+
+
+ make
+ -j5
+ testEssentialMatrixFactor.run
+ true
+ true
+ true
+
+
+ make
+ -j5
+ testGeneralSFMFactor_Cal3Bundler.run
+ true
+ true
+ true
+
+
+ make
+ -j5
+ testGeneralSFMFactor.run
+ true
+ true
+ true
+
+
+ make
+ -j5
+ testProjectionFactor.run
+ true
+ true
+ true
+
+
+ make
+ -j5
+ testRotateFactor.run
+ true
+ true
+ true
+
+
+ make
+ -j5
+ testPoseRotationPrior.run
+ true
+ true
+ true
+
+
+ make
+ -j5
+ testImplicitSchurFactor.run
+ true
+ true
+ true
+
+
+ make
+ -j4
+ testOrientedPlane3Factor.run
+ true
+ true
+ true
+
+
+ make
+ -j4
+ testSmartProjectionPoseFactor.run
+ true
+ true
+ true
+
+
+ make
+ -j4
+ testInitializePose3.run
+ true
+ true
+ true
+
+
+ make
+ -j2
+ SimpleRotation.run
+ true
+ true
+ true
+
+
+ make
+ -j5
+ CameraResectioning.run
+ true
+ true
+ true
+
+
+ make
+ -j5
+ PlanarSLAMExample.run
+ true
+ true
+ true
+
+
+ make
+ -j2
+ all
+ true
+ true
+ true
+
+
+ make
+ -j2
+ easyPoint2KalmanFilter.run
+ true
+ true
+ true
+
+
+ make
+ -j2
+ elaboratePoint2KalmanFilter.run
+ true
+ true
+ true
+
+
+ make
+ -j5
+ Pose2SLAMExample.run
+ true
+ true
+ true
+
+
+ make
+ -j2
+ Pose2SLAMwSPCG_easy.run
+ true
+ true
+ true
+
+
+ make
+ -j5
+ UGM_small.run
+ true
+ true
+ true
+
+
+ make
+ -j5
+ LocalizationExample.run
+ true
+ true
+ true
+
+
+ make
+ -j5
+ OdometryExample.run
+ true
+ true
+ true
+
+
+ make
+ -j5
+ RangeISAMExample_plaza2.run
+ true
+ true
+ true
+
+
+ make
+ -j5
+ SelfCalibrationExample.run
+ true
+ true
+ true
+
+
+ make
+ -j5
+ SFMExample.run
+ true
+ true
+ true
+
+
+ make
+ -j5
+ VisualISAMExample.run
+ true
+ true
+ true
+
+
+ make
+ -j5
+ VisualISAM2Example.run
+ true
+ true
+ true
+
+
+ make
+ -j5
+ Pose2SLAMExample_graphviz.run
+ true
+ true
+ true
+
+
+ make
+ -j5
+ Pose2SLAMExample_graph.run
+ true
+ true
+ true
+
+
+ make
+ -j5
+ SFMExample_bal.run
+ true
+ true
+ true
+
+
+ make
+ -j5
+ Pose2SLAMExample_lago.run
+ true
+ true
+ true
+
+
+ make
+ -j5
+ Pose2SLAMExample_g2o.run
+ true
+ true
+ true
+
+
+ make
+ -j5
+ SFMExample_SmartFactor.run
+ true
+ true
+ true
+
+
+ make
+ -j4
+ Pose2SLAMExampleExpressions.run
+ true
+ true
+ true
+
+
+ make
+ -j4
+ SFMExampleExpressions.run
+ true
+ true
+ true
+
+
+ make
+ -j4
+ SFMExampleExpressions_bal.run
+ true
+ true
+ true
+
+
+ make
+ -j5
+ testLago.run
+ true
+ true
+ true
+
+
+ make
+ -j5
+ testLinearContainerFactor.run
+ true
+ true
+ true
+
+
+ make
+ -j5
+ testOrdering.run
+ true
+ true
+ true
+
+
+ make
+ -j5
+ testValues.run
+ true
+ true
+ true
+
+
+ make
+ -j5
+ testWhiteNoiseFactor.run
+ true
+ true
+ true
+
+
+ make
+ -j4
+ testExpression.run
+ true
+ true
+ true
+
+
+ make
+ -j4
+ testAdaptAutoDiff.run
+ true
+ true
+ true
+
+
+ make
+ -j4
+ testCallRecord.run
+ true
+ true
+ true
+
+
+ make
+ -j4
+ testExpressionFactor.run
+ true
+ true
+ true
+
+
+ make
+ -j4
+ testExecutionTrace.run
+ true
+ true
+ true
+
+
+ make
+ -j4
+ testSerializationNonlinear.run
+ true
+ true
+ true
+
+
+ make
+ -j4
+ testImuFactor.run
+ true
+ true
+ true
+
+
make
-j2
check
@@ -3470,10 +3327,233 @@
true
true
-
+
+ make
+ tests/testGaussianISAM2
+ true
+ false
+ true
+
+
+ make
+ -j5
+ timeCalibratedCamera.run
+ true
+ true
+ true
+
+
+ make
+ -j5
+ timePinholeCamera.run
+ true
+ true
+ true
+
+
+ make
+ -j5
+ timeStereoCamera.run
+ true
+ true
+ true
+
+
+ make
+ -j5
+ timeLago.run
+ true
+ true
+ true
+
+
+ make
+ -j5
+ timePose3.run
+ true
+ true
+ true
+
+
+ make
+ -j4
+ timeAdaptAutoDiff.run
+ true
+ true
+ true
+
+
+ make
+ -j4
+ timeCameraExpression.run
+ true
+ true
+ true
+
+
+ make
+ -j4
+ timeOneCameraExpression.run
+ true
+ true
+ true
+
+
+ make
+ -j4
+ timeSFMExpressions.run
+ true
+ true
+ true
+
+
+ make
+ -j4
+ timeIncremental.run
+ true
+ true
+ true
+
+
+ make
+ -j4
+ timeSchurFactors.run
+ true
+ true
+ true
+
+
+ make
+ -j4
+ timeRot2.run
+ true
+ true
+ true
+
+
make
-j2
- testVSLAMGraph
+ testRot3.run
+ true
+ true
+ true
+
+
+ make
+ -j2
+ testRot2.run
+ true
+ true
+ true
+
+
+ make
+ -j2
+ testPose3.run
+ true
+ true
+ true
+
+
+ make
+ -j2
+ timeRot3.run
+ true
+ true
+ true
+
+
+ make
+ -j2
+ testPose2.run
+ true
+ true
+ true
+
+
+ make
+ -j2
+ testCal3_S2.run
+ true
+ true
+ true
+
+
+ make
+ -j2
+ testSimpleCamera.run
+ true
+ true
+ true
+
+
+ make
+ -j2
+ testHomography2.run
+ true
+ true
+ true
+
+
+ make
+ -j2
+ testCalibratedCamera.run
+ true
+ true
+ true
+
+
+ make
+ -j2
+ check
+ true
+ true
+ true
+
+
+ make
+ -j2
+ clean
+ true
+ true
+ true
+
+
+ make
+ -j2
+ testPoint2.run
+ true
+ true
+ true
+
+
+ make
+ -j4
+ testBearingFactor.run
+ true
+ true
+ true
+
+
+ make
+ -j4
+ testRangeFactor.run
+ true
+ true
+ true
+
+
+ make
+ -j4
+ testBearingRangeFactor.run
+ true
+ true
+ true
+
+
+ make
+ -j5
+ wrap
true
true
true
diff --git a/.gitignore b/.gitignore
index d46bddd10..04e8e76d1 100644
--- a/.gitignore
+++ b/.gitignore
@@ -6,3 +6,5 @@
/examples/Data/pose3example-rewritten.txt
*.txt.user
*.txt.user.6d59f0c
+/python-build/
+*.pydevproject
diff --git a/CMakeLists.txt b/CMakeLists.txt
index 6e9aa0009..75c24f76d 100644
--- a/CMakeLists.txt
+++ b/CMakeLists.txt
@@ -64,6 +64,8 @@ option(GTSAM_WITH_TBB "Use Intel Threaded Building Blocks (TB
option(GTSAM_WITH_EIGEN_MKL "Eigen will use Intel MKL if available" ON)
option(GTSAM_WITH_EIGEN_MKL_OPENMP "Eigen, when using Intel MKL, will also use OpenMP for multithreading if available" ON)
option(GTSAM_THROW_CHEIRALITY_EXCEPTION "Throw exception when a triangulated point is behind a camera" ON)
+option(GTSAM_BUILD_PYTHON "Enable/Disable building & installation of Python module" ON)
+option(GTSAM_ALLOW_DEPRECATED_SINCE_V4 "Allow use of methods/functions deprecated in GTSAM 4" ON)
# Options relating to MATLAB wrapper
# TODO: Check for matlab mex binary before handling building of binaries
@@ -82,6 +84,10 @@ if(GTSAM_INSTALL_MATLAB_TOOLBOX AND GTSAM_BUILD_STATIC_LIBRARY)
message(FATAL_ERROR "GTSAM_INSTALL_MATLAB_TOOLBOX and GTSAM_BUILD_STATIC_LIBRARY are both enabled. The MATLAB wrapper cannot be compiled with a static GTSAM library because mex modules are themselves shared libraries. If you want a self-contained mex module, enable GTSAM_MEX_BUILD_STATIC_MODULE instead of GTSAM_BUILD_STATIC_LIBRARY.")
endif()
+if(GTSAM_BUILD_PYTHON AND GTSAM_ALLOW_DEPRECATED_SINCE_V4)
+ message(FATAL_ERROR "GTSAM_BUILD_PYTHON and GTSAM_ALLOW_DEPRECATED_SINCE_V4 are both enabled. The python module cannot be compiled with deprecated functions turned on. Turn one of the two options off.")
+endif()
+
# Flags for choosing default packaging tools
set(CPACK_SOURCE_GENERATOR "TGZ" CACHE STRING "CPack Default Source Generator")
set(CPACK_GENERATOR "TGZ" CACHE STRING "CPack Default Binary Generator")
@@ -131,7 +137,7 @@ endif()
if(NOT (${Boost_VERSION} LESS 105600))
message("Ignoring Boost restriction on optional lvalue assignment from rvalues")
- add_definitions(-DBOOST_OPTIONAL_ALLOW_BINDING_TO_RVALUES)
+ add_definitions(-DBOOST_OPTIONAL_ALLOW_BINDING_TO_RVALUES -DBOOST_OPTIONAL_CONFIG_ALLOW_BINDING_TO_RVALUES)
endif()
###############################################################################
@@ -158,6 +164,12 @@ else()
set(GTSAM_USE_TBB 0) # This will go into config.h
endif()
+###############################################################################
+# Prohibit Timing build mode in combination with TBB
+if(GTSAM_USE_TBB AND (CMAKE_BUILD_TYPE STREQUAL "Timing"))
+ message(FATAL_ERROR "Timing build mode cannot be used together with TBB. Use a sampling profiler such as Instruments or Intel VTune Amplifier instead.")
+endif()
+
###############################################################################
# Find Google perftools
@@ -173,6 +185,11 @@ if(MKL_FOUND AND GTSAM_WITH_EIGEN_MKL)
set(EIGEN_USE_MKL_ALL 1) # This will go into config.h - it makes Eigen use MKL
include_directories(${MKL_INCLUDE_DIR})
list(APPEND GTSAM_ADDITIONAL_LIBRARIES ${MKL_LIBRARIES})
+
+ # --no-as-needed is required with gcc according to the MKL link advisor
+ if(CMAKE_CXX_COMPILER_ID STREQUAL "GNU")
+ set(CMAKE_EXE_LINKER_FLAGS "${CMAKE_EXE_LINKER_FLAGS} -Wl,--no-as-needed")
+ endif()
else()
set(GTSAM_USE_EIGEN_MKL 0)
set(EIGEN_USE_MKL_ALL 0)
@@ -266,7 +283,8 @@ endif()
# Include boost - use 'BEFORE' so that a specific boost specified to CMake
# takes precedence over a system-installed one.
-include_directories(BEFORE ${Boost_INCLUDE_DIR})
+# Use 'SYSTEM' to ignore compiler warnings in Boost headers
+include_directories(BEFORE SYSTEM ${Boost_INCLUDE_DIR})
# Add includes for source directories 'BEFORE' boost and any system include
# paths so that the compiler uses GTSAM headers in our source directory instead
@@ -293,10 +311,21 @@ if(CMAKE_CXX_COMPILER_ID STREQUAL "GNU")
endif()
endif()
+# As of XCode 7, clang also complains about this
+if(CMAKE_CXX_COMPILER_ID STREQUAL "Clang")
+ if (NOT CMAKE_CXX_COMPILER_VERSION VERSION_LESS 7.0)
+ add_definitions(-Wno-unused-local-typedefs)
+ endif()
+endif()
+
if(GTSAM_ENABLE_CONSISTENCY_CHECKS)
add_definitions(-DGTSAM_EXTRA_CONSISTENCY_CHECKS)
endif()
+if(GTSAM_ALLOW_DEPRECATED_SINCE_V4)
+ add_definitions(-DGTSAM_ALLOW_DEPRECATED_SINCE_V4)
+endif()
+
###############################################################################
# Add components
@@ -325,6 +354,20 @@ if (GTSAM_INSTALL_MATLAB_TOOLBOX)
add_subdirectory(matlab)
endif()
+# Python wrap
+if (GTSAM_BUILD_PYTHON)
+ include(GtsamPythonWrap)
+
+ # NOTE: The automatic generation of python wrapper from the gtsampy.h interface is
+ # not working yet, so we're using a handwritten wrapper files on python/handwritten.
+ # Once the python wrapping from the interface file is working, you can _swap_ the
+ # comments on the next lines
+
+ # wrap_and_install_python(gtsampy.h "${GTSAM_ADDITIONAL_LIBRARIES}" "")
+ add_subdirectory(python)
+
+endif()
+
# Build gtsam_unstable
if (GTSAM_BUILD_UNSTABLE)
add_subdirectory(gtsam_unstable)
@@ -375,6 +418,8 @@ set(CPACK_DEBIAN_PACKAGE_DEPENDS "libboost-dev (>= 1.43)") #Example: "libc6 (>=
# Print configuration variables
message(STATUS "===============================================================")
message(STATUS "================ Configuration Options ======================")
+message(STATUS " CMAKE_CXX_COMPILER_ID type : ${CMAKE_CXX_COMPILER_ID}")
+message(STATUS " CMAKE_CXX_COMPILER_VERSION : ${CMAKE_CXX_COMPILER_VERSION}")
message(STATUS "Build flags ")
print_config_flag(${GTSAM_BUILD_TESTS} "Build Tests ")
print_config_flag(${GTSAM_BUILD_EXAMPLES_ALWAYS} "Build examples with 'make all' ")
@@ -435,10 +480,22 @@ print_config_flag(${GTSAM_USE_QUATERNIONS} "Quaternions as default R
print_config_flag(${GTSAM_ENABLE_CONSISTENCY_CHECKS} "Runtime consistency checking ")
print_config_flag(${GTSAM_ROT3_EXPMAP} "Rot3 retract is full ExpMap ")
print_config_flag(${GTSAM_POSE3_EXPMAP} "Pose3 retract is full ExpMap ")
+print_config_flag(${GTSAM_ALLOW_DEPRECATED_SINCE_V4} "Deprecated in GTSAM 4 allowed ")
message(STATUS "MATLAB toolbox flags ")
print_config_flag(${GTSAM_INSTALL_MATLAB_TOOLBOX} "Install matlab toolbox ")
print_config_flag(${GTSAM_BUILD_WRAP} "Build Wrap ")
+
+message(STATUS "Python module flags ")
+
+if(GTSAM_PYTHON_WARNINGS)
+ message(STATUS " Build python module : No - dependencies missing")
+else()
+ print_config_flag(${GTSAM_BUILD_PYTHON} "Build python module ")
+endif()
+if(GTSAM_BUILD_PYTHON)
+ message(STATUS " Python version : ${GTSAM_PYTHON_VERSION}")
+endif()
message(STATUS "===============================================================")
# Print warnings at the end
@@ -451,6 +508,9 @@ endif()
if(GTSAM_WITH_EIGEN_MKL_OPENMP AND NOT OPENMP_FOUND AND MKL_FOUND)
message(WARNING "Your compiler does not support OpenMP - this is ok, but performance may be improved with OpenMP. Set GTSAM_WITH_EIGEN_MKL_OPENMP to 'Off' to avoid this warning.")
endif()
+if(GTSAM_BUILD_PYTHON AND GTSAM_PYTHON_WARNINGS)
+ message(WARNING "${GTSAM_PYTHON_WARNINGS}")
+endif()
# Include CPack *after* all flags
include(CPack)
diff --git a/README.md b/README.md
index 679af5a2f..ccdc7f07e 100644
--- a/README.md
+++ b/README.md
@@ -31,6 +31,7 @@ Prerequisites:
- [Boost](http://www.boost.org/users/download/) >= 1.43 (Ubuntu: `sudo apt-get install libboost-all-dev`)
- [CMake](http://www.cmake.org/cmake/resources/software.html) >= 2.6 (Ubuntu: `sudo apt-get install cmake`)
+- A modern compiler, i.e., at least gcc 4.7.3 on Linux.
Optional prerequisites - used automatically if findable by CMake:
@@ -46,6 +47,6 @@ See the [`INSTALL`](INSTALL) file for more detailed installation instructions.
GTSAM is open source under the BSD license, see the [`LICENSE`](LICENSE) and [`LICENSE.BSD`](LICENSE.BSD) files.
-Please see the [`examples/`](examples) directory and the [`USAGE`](USAGE.md) file for examples on how to use GTSAM.
-
+Please see the [`examples/`](examples) directory and the [`USAGE`](USAGE.md) file for examples on how to use GTSAM.
+
GTSAM was developed in the lab of [Frank Dellaert](http://www.cc.gatech.edu/~dellaert) at the [Georgia Institute of Technology](http://www.gatech.edu), with the help of many contributors over the years, see [THANKS](THANKS).
\ No newline at end of file
diff --git a/THANKS b/THANKS
index 9c06a5d28..f84cfa185 100644
--- a/THANKS
+++ b/THANKS
@@ -38,6 +38,10 @@ at Uni Zurich:
* Christian Forster
+at LAAS-CNRS
+
+* Ellon Paiva
+
Many thanks for your hard work!!!!
Frank Dellaert
diff --git a/cmake/FindNumPy.cmake b/cmake/FindNumPy.cmake
new file mode 100644
index 000000000..eafed165e
--- /dev/null
+++ b/cmake/FindNumPy.cmake
@@ -0,0 +1,102 @@
+# - Find the NumPy libraries
+# This module finds if NumPy is installed, and sets the following variables
+# indicating where it is.
+#
+# TODO: Update to provide the libraries and paths for linking npymath lib.
+#
+# NUMPY_FOUND - was NumPy found
+# NUMPY_VERSION - the version of NumPy found as a string
+# NUMPY_VERSION_MAJOR - the major version number of NumPy
+# NUMPY_VERSION_MINOR - the minor version number of NumPy
+# NUMPY_VERSION_PATCH - the patch version number of NumPy
+# NUMPY_VERSION_DECIMAL - e.g. version 1.6.1 is 10601
+# NUMPY_INCLUDE_DIRS - path to the NumPy include files
+
+#============================================================================
+# Copyright 2012 Continuum Analytics, Inc.
+#
+# MIT License
+#
+# Permission is hereby granted, free of charge, to any person obtaining
+# a copy of this software and associated documentation files
+# (the "Software"), to deal in the Software without restriction, including
+# without limitation the rights to use, copy, modify, merge, publish,
+# distribute, sublicense, and/or sell copies of the Software, and to permit
+# persons to whom the Software is furnished to do so, subject to
+# the following conditions:
+#
+# The above copyright notice and this permission notice shall be included
+# in all copies or substantial portions of the Software.
+#
+# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS
+# OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
+# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL
+# THE AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR
+# OTHER LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE,
+# ARISING FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR
+# OTHER DEALINGS IN THE SOFTWARE.
+#
+#============================================================================
+
+# Finding NumPy involves calling the Python interpreter
+if(NumPy_FIND_REQUIRED)
+ find_package(PythonInterp REQUIRED)
+else()
+ find_package(PythonInterp)
+endif()
+
+if(NOT PYTHONINTERP_FOUND)
+ set(NUMPY_FOUND FALSE)
+ return()
+endif()
+
+execute_process(COMMAND "${PYTHON_EXECUTABLE}" "-c"
+ "import numpy as n; print(n.__version__); print(n.get_include());"
+ RESULT_VARIABLE _NUMPY_SEARCH_SUCCESS
+ OUTPUT_VARIABLE _NUMPY_VALUES_OUTPUT
+ ERROR_VARIABLE _NUMPY_ERROR_VALUE
+ OUTPUT_STRIP_TRAILING_WHITESPACE)
+
+if(NOT _NUMPY_SEARCH_SUCCESS MATCHES 0)
+ if(NumPy_FIND_REQUIRED)
+ message(FATAL_ERROR
+ "NumPy import failure:\n${_NUMPY_ERROR_VALUE}")
+ endif()
+ set(NUMPY_FOUND FALSE)
+ return()
+endif()
+
+# Convert the process output into a list
+string(REGEX REPLACE ";" "\\\\;" _NUMPY_VALUES ${_NUMPY_VALUES_OUTPUT})
+string(REGEX REPLACE "\n" ";" _NUMPY_VALUES ${_NUMPY_VALUES})
+# Just in case there is unexpected output from the Python command.
+list(GET _NUMPY_VALUES -2 NUMPY_VERSION)
+list(GET _NUMPY_VALUES -1 NUMPY_INCLUDE_DIRS)
+
+string(REGEX MATCH "^[0-9]+\\.[0-9]+\\.[0-9]+" _VER_CHECK "${NUMPY_VERSION}")
+if("${_VER_CHECK}" STREQUAL "")
+ # The output from Python was unexpected. Raise an error always
+ # here, because we found NumPy, but it appears to be corrupted somehow.
+ message(FATAL_ERROR
+ "Requested version and include path from NumPy, got instead:\n${_NUMPY_VALUES_OUTPUT}\n")
+ return()
+endif()
+
+# Make sure all directory separators are '/'
+string(REGEX REPLACE "\\\\" "/" NUMPY_INCLUDE_DIRS ${NUMPY_INCLUDE_DIRS})
+
+# Get the major and minor version numbers
+string(REGEX REPLACE "\\." ";" _NUMPY_VERSION_LIST ${NUMPY_VERSION})
+list(GET _NUMPY_VERSION_LIST 0 NUMPY_VERSION_MAJOR)
+list(GET _NUMPY_VERSION_LIST 1 NUMPY_VERSION_MINOR)
+list(GET _NUMPY_VERSION_LIST 2 NUMPY_VERSION_PATCH)
+string(REGEX MATCH "[0-9]*" NUMPY_VERSION_PATCH ${NUMPY_VERSION_PATCH})
+math(EXPR NUMPY_VERSION_DECIMAL
+ "(${NUMPY_VERSION_MAJOR} * 10000) + (${NUMPY_VERSION_MINOR} * 100) + ${NUMPY_VERSION_PATCH}")
+
+find_package_message(NUMPY
+ "Found NumPy: version \"${NUMPY_VERSION}\" ${NUMPY_INCLUDE_DIRS}"
+ "${NUMPY_INCLUDE_DIRS}${NUMPY_VERSION}")
+
+set(NUMPY_FOUND TRUE)
+
diff --git a/cmake/GtsamBuildTypes.cmake b/cmake/GtsamBuildTypes.cmake
index c2cd7b449..43ae36929 100644
--- a/cmake/GtsamBuildTypes.cmake
+++ b/cmake/GtsamBuildTypes.cmake
@@ -34,19 +34,19 @@ if(NOT FIRST_PASS_DONE)
set(CMAKE_MODULE_LINKER_FLAGS_PROFILING "${CMAKE_MODULE_LINKER_FLAGS_RELEASE}" CACHE STRING "Linker flags during profiling builds." FORCE)
mark_as_advanced(CMAKE_C_FLAGS_PROFILING CMAKE_CXX_FLAGS_PROFILING CMAKE_EXE_LINKER_FLAGS_PROFILING CMAKE_SHARED_LINKER_FLAGS_PROFILING CMAKE_MODULE_LINKER_FLAGS_PROFILING)
else()
- set(CMAKE_C_FLAGS_DEBUG "${CMAKE_C_FLAGS_DEBUG} -fno-inline -Wall -DEIGEN_INITIALIZE_MATRICES_BY_NAN" CACHE STRING "Flags used by the compiler during debug builds." FORCE)
- set(CMAKE_CXX_FLAGS_DEBUG "${CMAKE_CXX_FLAGS_DEBUG} -fno-inline -Wall -DEIGEN_INITIALIZE_MATRICES_BY_NAN" CACHE STRING "Flags used by the compiler during debug builds." FORCE)
- set(CMAKE_C_FLAGS_RELWITHDEBINFO "-g -O3 -Wall -DNDEBUG" CACHE STRING "Flags used by the compiler during relwithdebinfo builds." FORCE)
- set(CMAKE_CXX_FLAGS_RELWITHDEBINFO "-g -O3 -Wall -DNDEBUG" CACHE STRING "Flags used by the compiler during relwithdebinfo builds." FORCE)
- set(CMAKE_C_FLAGS_RELEASE "-O3 -Wall -DNDEBUG -Wall" CACHE STRING "Flags used by the compiler during release builds." FORCE)
- set(CMAKE_CXX_FLAGS_RELEASE "-O3 -Wall -DNDEBUG -Wall" CACHE STRING "Flags used by the compiler during release builds." FORCE)
+ set(CMAKE_C_FLAGS_DEBUG "${CMAKE_C_FLAGS_DEBUG} -std=c11 -fno-inline -Wall -DEIGEN_INITIALIZE_MATRICES_BY_NAN" CACHE STRING "Flags used by the compiler during debug builds." FORCE)
+ set(CMAKE_CXX_FLAGS_DEBUG "${CMAKE_CXX_FLAGS_DEBUG} -std=c++11 -fno-inline -Wall -DEIGEN_INITIALIZE_MATRICES_BY_NAN" CACHE STRING "Flags used by the compiler during debug builds." FORCE)
+ set(CMAKE_C_FLAGS_RELWITHDEBINFO "-std=c11 -g -O3 -Wall -DNDEBUG" CACHE STRING "Flags used by the compiler during relwithdebinfo builds." FORCE)
+ set(CMAKE_CXX_FLAGS_RELWITHDEBINFO "-std=c++11 -g -O3 -Wall -DNDEBUG" CACHE STRING "Flags used by the compiler during relwithdebinfo builds." FORCE)
+ set(CMAKE_C_FLAGS_RELEASE "-std=c11 -O3 -Wall -DNDEBUG -Wall" CACHE STRING "Flags used by the compiler during release builds." FORCE)
+ set(CMAKE_CXX_FLAGS_RELEASE "-std=c++11 -O3 -Wall -DNDEBUG -Wall" CACHE STRING "Flags used by the compiler during release builds." FORCE)
set(CMAKE_C_FLAGS_TIMING "${CMAKE_C_FLAGS_RELEASE} -DENABLE_TIMING" CACHE STRING "Flags used by the compiler during timing builds." FORCE)
set(CMAKE_CXX_FLAGS_TIMING "${CMAKE_CXX_FLAGS_RELEASE} -DENABLE_TIMING" CACHE STRING "Flags used by the compiler during timing builds." FORCE)
set(CMAKE_EXE_LINKER_FLAGS_TIMING "${CMAKE_EXE_LINKER_FLAGS_RELEASE}" CACHE STRING "Linker flags during timing builds." FORCE)
set(CMAKE_SHARED_LINKER_FLAGS_TIMING "${CMAKE_EXE_LINKER_FLAGS_RELEASE}" CACHE STRING "Linker flags during timing builds." FORCE)
mark_as_advanced(CMAKE_C_FLAGS_TIMING CMAKE_CXX_FLAGS_TIMING CMAKE_EXE_LINKER_FLAGS_TIMING CMAKE_SHARED_LINKER_FLAGS_TIMING)
- set(CMAKE_C_FLAGS_PROFILING "-g -O3 -Wall -DNDEBUG" CACHE STRING "Flags used by the compiler during profiling builds." FORCE)
- set(CMAKE_CXX_FLAGS_PROFILING "-g -O3 -Wall -DNDEBUG" CACHE STRING "Flags used by the compiler during profiling builds." FORCE)
+ set(CMAKE_C_FLAGS_PROFILING "-std=c11 -g -O3 -Wall -DNDEBUG" CACHE STRING "Flags used by the compiler during profiling builds." FORCE)
+ set(CMAKE_CXX_FLAGS_PROFILING "-std=c++11 -g -O3 -Wall -DNDEBUG" CACHE STRING "Flags used by the compiler during profiling builds." FORCE)
set(CMAKE_EXE_LINKER_FLAGS_PROFILING "${CMAKE_EXE_LINKER_FLAGS_RELEASE}" CACHE STRING "Linker flags during profiling builds." FORCE)
set(CMAKE_SHARED_LINKER_FLAGS_PROFILING "${CMAKE__LINKER_FLAGS_RELEASE}" CACHE STRING "Linker flags during profiling builds." FORCE)
mark_as_advanced(CMAKE_C_FLAGS_PROFILING CMAKE_CXX_FLAGS_PROFILING CMAKE_EXE_LINKER_FLAGS_PROFILING CMAKE_SHARED_LINKER_FLAGS_PROFILING)
diff --git a/cmake/GtsamPythonWrap.cmake b/cmake/GtsamPythonWrap.cmake
index d065a7828..714e37488 100644
--- a/cmake/GtsamPythonWrap.cmake
+++ b/cmake/GtsamPythonWrap.cmake
@@ -1,5 +1,5 @@
#Setup cache options
-option(GTSAM_BUILD_PYTHON "Build Python wrapper statically (increases build time)" OFF)
+set(GTSAM_PYTHON_VERSION "Default" CACHE STRING "Target python version for GTSAM python module. Use 'Default' to chose the default version")
set(GTSAM_BUILD_PYTHON_FLAGS "" CACHE STRING "Extra flags for running Matlab PYTHON compilation")
set(GTSAM_PYTHON_INSTALL_PATH "" CACHE PATH "Python toolbox destination, blank defaults to CMAKE_INSTALL_PREFIX/borg/python")
if(NOT GTSAM_PYTHON_INSTALL_PATH)
@@ -8,13 +8,13 @@ endif()
#Author: Paul Furgale Modified by Andrew Melim
function(wrap_python TARGET_NAME PYTHON_MODULE_DIRECTORY)
- # Boost
- find_package(Boost COMPONENTS python filesystem system REQUIRED)
- include_directories(${Boost_INCLUDE_DIRS})
+ # # Boost
+ # find_package(Boost COMPONENTS python filesystem system REQUIRED)
+ # include_directories(${Boost_INCLUDE_DIRS})
- # Find Python
- FIND_PACKAGE(PythonLibs 2.7 REQUIRED)
- INCLUDE_DIRECTORIES(${PYTHON_INCLUDE_DIRS})
+ # # Find Python
+ # FIND_PACKAGE(PythonLibs 2.7 REQUIRED)
+ # INCLUDE_DIRECTORIES(${PYTHON_INCLUDE_DIRS})
IF(APPLE)
# The apple framework headers don't include the numpy headers for some reason.
@@ -36,23 +36,46 @@ function(wrap_python TARGET_NAME PYTHON_MODULE_DIRECTORY)
ENDIF()
ENDIF(APPLE)
+ if(MSVC)
+ add_library(${moduleName}_python MODULE ${ARGN})
+ set_target_properties(${moduleName}_python PROPERTIES
+ OUTPUT_NAME ${moduleName}_python
+ CLEAN_DIRECT_OUTPUT 1
+ VERSION 1
+ SOVERSION 0
+ SUFFIX ".pyd")
+ target_link_libraries(${moduleName}_python ${Boost_PYTHON_LIBRARY} ${PYTHON_LIBRARY} ${gtsamLib}) #temp
- # Create a static library version
- add_library(${TARGET_NAME} SHARED ${ARGN})
+ set(PYLIB_OUTPUT_FILE $)
+ message(${PYLIB_OUTPUT_FILE})
+ get_filename_component(PYLIB_OUTPUT_NAME ${PYLIB_OUTPUT_FILE} NAME_WE)
+ set(PYLIB_SO_NAME ${PYLIB_OUTPUT_NAME}.pyd)
- target_link_libraries(${TARGET_NAME} ${Boost_PYTHON_LIBRARY} ${PYTHON_LIBRARY} gtsam-shared)
- set_target_properties(${TARGET_NAME} PROPERTIES
- OUTPUT_NAME ${TARGET_NAME}
- CLEAN_DIRECT_OUTPUT 1
- VERSION 1
- SOVERSION 0)
+ ELSE()
+ # Create a shared library
+ add_library(${moduleName}_python SHARED ${generated_cpp_file})
+ set_target_properties(${moduleName}_python PROPERTIES
+ OUTPUT_NAME ${moduleName}_python
+ CLEAN_DIRECT_OUTPUT 1)
+ target_link_libraries(${moduleName}_python ${Boost_PYTHON_LIBRARY} ${PYTHON_LIBRARY} ${gtsamLib}) #temp
+ # On OSX and Linux, the python library must end in the extension .so. Build this
+ # filename here.
+ get_property(PYLIB_OUTPUT_FILE TARGET ${moduleName}_python PROPERTY LOCATION)
+ set(PYLIB_OUTPUT_FILE $)
+ message(${PYLIB_OUTPUT_FILE})
+ get_filename_component(PYLIB_OUTPUT_NAME ${PYLIB_OUTPUT_FILE} NAME_WE)
+ set(PYLIB_SO_NAME lib${moduleName}_python.so)
+ ENDIF(MSVC)
- # On OSX and Linux, the python library must end in the extension .so. Build this
- # filename here.
- get_property(PYLIB_OUTPUT_FILE TARGET ${TARGET_NAME} PROPERTY LOCATION)
- get_filename_component(PYLIB_OUTPUT_NAME ${PYLIB_OUTPUT_FILE} NAME_WE)
- set(PYLIB_SO_NAME ${PYLIB_OUTPUT_NAME}.so)
+ # Installs the library in the gtsam folder, which is used by setup.py to create the gtsam package
+ set(PYTHON_MODULE_DIRECTORY ${CMAKE_SOURCE_DIR}/python/gtsam)
+ # Cause the library to be output in the correct directory.
+ add_custom_command(TARGET ${moduleName}_python
+ POST_BUILD
+ COMMAND cp -v ${PYLIB_OUTPUT_FILE} ${PYTHON_MODULE_DIRECTORY}/${PYLIB_SO_NAME}
+ WORKING_DIRECTORY ${PROJECT_SOURCE_DIR}
+ COMMENT "Copying library files to python directory" )
# Cause the library to be output in the correct directory.
add_custom_command(TARGET ${TARGET_NAME}
@@ -64,4 +87,16 @@ function(wrap_python TARGET_NAME PYTHON_MODULE_DIRECTORY)
get_directory_property(AMCF ADDITIONAL_MAKE_CLEAN_FILES)
list(APPEND AMCF ${PYTHON_MODULE_DIRECTORY}/${PYLIB_SO_NAME})
set_directory_properties(PROPERTIES ADDITIONAL_MAKE_CLEAN_FILES "${AMCF}")
-endfunction(wrap_python)
\ No newline at end of file
+endfunction(wrap_python)
+
+# Macro to get list of subdirectories
+macro(SUBDIRLIST result curdir)
+ file(GLOB children RELATIVE ${curdir} ${curdir}/*)
+ set(dirlist "")
+ foreach(child ${children})
+ if(IS_DIRECTORY ${curdir}/${child})
+ list(APPEND dirlist ${child})
+ endif()
+ endforeach()
+ set(${result} ${dirlist})
+endmacro()
diff --git a/cmake/GtsamTesting.cmake b/cmake/GtsamTesting.cmake
index 4b3af9810..3e5cadd32 100644
--- a/cmake/GtsamTesting.cmake
+++ b/cmake/GtsamTesting.cmake
@@ -195,7 +195,9 @@ macro(gtsamAddTestsGlob_impl groupName globPatterns excludedFiles linkLibraries)
add_test(NAME ${target_name} COMMAND ${target_name})
add_dependencies(check.${groupName} ${target_name})
add_dependencies(check ${target_name})
- add_dependencies(all.tests ${script_name})
+ if(NOT XCODE_VERSION)
+ add_dependencies(all.tests ${script_name})
+ endif()
# Add TOPSRCDIR
set_property(SOURCE ${script_srcs} APPEND PROPERTY COMPILE_DEFINITIONS "TOPSRCDIR=\"${PROJECT_SOURCE_DIR}\"")
diff --git a/doc/.gitignore b/doc/.gitignore
index ac7af2e80..8a3139177 100644
--- a/doc/.gitignore
+++ b/doc/.gitignore
@@ -1 +1,3 @@
/html/
+*.lyx~
+*.bib~
diff --git a/doc/ImuFactor.lyx b/doc/ImuFactor.lyx
new file mode 100644
index 000000000..d9cd35584
--- /dev/null
+++ b/doc/ImuFactor.lyx
@@ -0,0 +1,1399 @@
+#LyX 2.0 created this file. For more info see http://www.lyx.org/
+\lyxformat 413
+\begin_document
+\begin_header
+\textclass article
+\use_default_options true
+\maintain_unincluded_children false
+\language english
+\language_package default
+\inputencoding auto
+\fontencoding global
+\font_roman default
+\font_sans default
+\font_typewriter default
+\font_default_family default
+\use_non_tex_fonts false
+\font_sc false
+\font_osf false
+\font_sf_scale 100
+\font_tt_scale 100
+
+\graphics default
+\default_output_format default
+\output_sync 0
+\bibtex_command default
+\index_command default
+\paperfontsize 11
+\spacing single
+\use_hyperref false
+\papersize default
+\use_geometry true
+\use_amsmath 1
+\use_esint 1
+\use_mhchem 1
+\use_mathdots 1
+\cite_engine basic
+\use_bibtopic false
+\use_indices false
+\paperorientation portrait
+\suppress_date false
+\use_refstyle 1
+\index Index
+\shortcut idx
+\color #008000
+\end_index
+\leftmargin 3cm
+\topmargin 3cm
+\rightmargin 3cm
+\bottommargin 3cm
+\secnumdepth 3
+\tocdepth 3
+\paragraph_separation indent
+\paragraph_indentation default
+\quotes_language english
+\papercolumns 1
+\papersides 1
+\paperpagestyle default
+\tracking_changes false
+\output_changes false
+\html_math_output 0
+\html_css_as_file 0
+\html_be_strict false
+\end_header
+
+\begin_body
+
+\begin_layout Title
+The new IMU Factor
+\end_layout
+
+\begin_layout Author
+Frank Dellaert
+\end_layout
+
+\begin_layout Standard
+\begin_inset CommandInset include
+LatexCommand include
+filename "macros.lyx"
+
+\end_inset
+
+
+\end_layout
+
+\begin_layout Standard
+\begin_inset FormulaMacro
+\renewcommand{\sothree}{\mathfrak{so(3)}}
+{\mathfrak{so(3)}}
+\end_inset
+
+
+\end_layout
+
+\begin_layout Subsubsection*
+Navigation States
+\end_layout
+
+\begin_layout Standard
+Let us assume a setup where frames with image and/or laser measurements
+ are processed at some fairly low rate, e.g., 10 Hz.
+\end_layout
+
+\begin_layout Standard
+We define the state of the vehicle at those times as attitude, position,
+ and velocity.
+ These three quantities are jointly referred to as a NavState
+\begin_inset Formula $X_{b}^{n}\define\left\{ R_{b}^{n},P_{b}^{n},V_{b}^{n}\right\} $
+\end_inset
+
+, where the superscript
+\begin_inset Formula $n$
+\end_inset
+
+ denotes the
+\emph on
+navigation frame
+\emph default
+, and
+\begin_inset Formula $b$
+\end_inset
+
+ the
+\emph on
+body frame
+\emph default
+.
+ For simplicity, we drop these indices below where clear from context.
+\end_layout
+
+\begin_layout Subsubsection*
+Vector Fields and Differential Equations
+\end_layout
+
+\begin_layout Standard
+We need a way to describe the evolution of a NavState over time.
+ The NavState lives in a 9-dimensional manifold
+\begin_inset Formula $M$
+\end_inset
+
+, defined by the orthonormality constraints on
+\begin_inset Formula $\Rone$
+\end_inset
+
+.
+ For a NavState
+\begin_inset Formula $X$
+\end_inset
+
+ evolving over time we can write down a differential equation
+\begin_inset Formula
+\begin{equation}
+\dot{X}(t)=F(t,X)\label{eq:diffeqM}
+\end{equation}
+
+\end_inset
+
+where
+\begin_inset Formula $F$
+\end_inset
+
+ is a time-varying
+\series bold
+vector field
+\series default
+ on
+\begin_inset Formula $M$
+\end_inset
+
+, defined as a mapping from
+\begin_inset Formula $\Rone\times M$
+\end_inset
+
+ to tangent vectors at
+\begin_inset Formula $X$
+\end_inset
+
+.
+ A
+\series bold
+tangent vector
+\series default
+ at
+\begin_inset Formula $X$
+\end_inset
+
+ is defined as the derivative of a trajectory at
+\begin_inset Formula $X$
+\end_inset
+
+, and for the NavState manifold this will be a triplet
+\begin_inset Formula
+\[
+\left[\dot{R}(t,X),\dot{P}(t,X),\dot{V}(t,X)\right]\in\sothree\times\Rthree\times\Rthree
+\]
+
+\end_inset
+
+where we use square brackets to indicate a tangent vector.
+ The space of all tangent vectors at
+\begin_inset Formula $X$
+\end_inset
+
+ is denoted by
+\family roman
+\series medium
+\shape up
+\size normal
+\emph off
+\bar no
+\strikeout off
+\uuline off
+\uwave off
+\noun off
+\color none
+
+\begin_inset Formula $T_{X}M$
+\end_inset
+
+
+\family default
+\series default
+\shape default
+\size default
+\emph default
+\bar default
+\strikeout default
+\uuline default
+\uwave default
+\noun default
+\color inherit
+, and hence
+\begin_inset Formula $F(t,X)\in T_{X}M$
+\end_inset
+
+.
+ For example, if the state evolves along a constant velocity trajectory
+\begin_inset Formula
+\[
+X(t)=\left\{ R_{0},P_{0}+V_{0}t,V_{0}\right\}
+\]
+
+\end_inset
+
+then the differential equation describing the trajectory is
+\begin_inset Formula
+\[
+\dot{X}(t)=\left[0_{3x3},V_{0},0_{3x1}\right],\,\,\,\,\, X(0)=\left\{ R_{0},P_{0},V_{0}\right\}
+\]
+
+\end_inset
+
+
+\end_layout
+
+\begin_layout Standard
+Valid vector fields on a NavState manifold are special, in that the attitude
+ and velocity derivatives can be arbitrary functions of X and t, but the
+ derivative of position is constrained to be equal to the current velocity
+
+\begin_inset Formula $V(t)$
+\end_inset
+
+:
+\begin_inset Formula
+\begin{equation}
+\dot{X}(t)=\left[\dot{R}(X,t),V(t),\dot{V}(X,t)\right]\label{eq:validField}
+\end{equation}
+
+\end_inset
+
+Suppose we are given the
+\series bold
+body angular velocity
+\series default
+
+\begin_inset Formula $\omega^{b}(t)$
+\end_inset
+
+ and non-gravity
+\series bold
+acceleration
+\series default
+
+\begin_inset Formula $a^{b}(t)$
+\end_inset
+
+ in the body frame.
+ We know (from Murray84book) that the derivative of
+\begin_inset Formula $R$
+\end_inset
+
+ can be written as
+\begin_inset Formula
+\[
+\dot{R}(X,t)=R(t)\Skew{\omega^{b}(t)}
+\]
+
+\end_inset
+
+where
+\begin_inset Formula $\Skew{\theta}\in so(3)$
+\end_inset
+
+ is the skew-symmetric matrix corresponding to
+\begin_inset Formula $\theta$
+\end_inset
+
+, and hence the resulting exact vector field is
+\begin_inset Formula
+\begin{equation}
+\dot{X}(t)=\left[\dot{R}(X,t),V(t),\dot{V}(X,t)\right]=\left[R(t)\Skew{\omega^{b}(t)},V(t),g+R(t)a^{b}(t)\right]\label{eq:bodyField}
+\end{equation}
+
+\end_inset
+
+
+\end_layout
+
+\begin_layout Subsubsection*
+Local Coordinates
+\end_layout
+
+\begin_layout Standard
+Optimization on manifolds relies crucially on the concept of
+\series bold
+local coordinates
+\series default
+.
+ For example, when optimizing over the rotations
+\begin_inset Formula $\SOthree$
+\end_inset
+
+ starting from an initial estimate
+\begin_inset Formula $R_{0}$
+\end_inset
+
+, we define a local map
+\begin_inset Formula $\Phi_{R_{0}}$
+\end_inset
+
+ from
+\begin_inset Formula $\theta\in\Rthree$
+\end_inset
+
+ to a neighborhood of
+\begin_inset Formula $\SOthree$
+\end_inset
+
+ centered around
+\begin_inset Formula $R_{0}$
+\end_inset
+
+,
+\begin_inset Formula
+\[
+\Phi_{R_{0}}(\theta)=R_{0}\exp\left(\Skew{\theta}\right)
+\]
+
+\end_inset
+
+where
+\begin_inset Formula $\exp$
+\end_inset
+
+ is the matrix exponential, given by
+\begin_inset Formula
+\begin{equation}
+\exp\left(\Skew{\theta}\right)=\sum_{k=0}^{\infty}\frac{1}{k!}\Skew{\theta}^{k}\label{eq:expm}
+\end{equation}
+
+\end_inset
+
+which for
+\begin_inset Formula $\SOthree$
+\end_inset
+
+ can be efficiently computed in closed form.
+\end_layout
+
+\begin_layout Standard
+The local coordinates
+\begin_inset Formula $\theta$
+\end_inset
+
+ are isomorphic to tangent vectors at
+\emph on
+
+\begin_inset Formula $R_{0}$
+\end_inset
+
+
+\emph default
+.
+ To see this, define
+\begin_inset Formula $\theta=\omega t$
+\end_inset
+
+ and note that
+\begin_inset Formula
+\[
+\frac{d\Phi_{R_{0}}\left(\omega t\right)}{dt}\biggr\vert_{t=0}=\frac{dR_{0}\exp\left(\Skew{\omega t}\right)}{dt}\biggr\vert_{t=0}=R_{0}\Skew{\omega}
+\]
+
+\end_inset
+
+Hence, the 3-vector
+\begin_inset Formula $\omega$
+\end_inset
+
+ defines a direction of travel on the
+\begin_inset Formula $\SOthree$
+\end_inset
+
+ manifold, but does so in the local coordinate frame define by
+\begin_inset Formula $R_{0}$
+\end_inset
+
+.
+\end_layout
+
+\begin_layout Standard
+A similar story holds in
+\begin_inset Formula $\SEthree$
+\end_inset
+
+: we define local coordinates
+\begin_inset Formula $\xi=\left[\omega t,vt\right]\in\Rsix$
+\end_inset
+
+ and a mapping
+\begin_inset Formula
+\[
+\Phi_{T_{0}}(\xi)=T_{0}\exp\xihat
+\]
+
+\end_inset
+
+where
+\begin_inset Formula $\xihat\in\sethree$
+\end_inset
+
+ is defined as
+\begin_inset Formula
+\[
+\xihat=\left[\begin{array}{cc}
+\Skew{\omega} & v\\
+0 & 0
+\end{array}\right]t
+\]
+
+\end_inset
+
+and the 6-vectors
+\begin_inset Formula $\xi$
+\end_inset
+
+ are mapped to tangent vectors
+\begin_inset Formula $T_{0}\xihat$
+\end_inset
+
+ at
+\begin_inset Formula $T_{0}$
+\end_inset
+
+.
+\end_layout
+
+\begin_layout Subsubsection*
+Derivative of The Local Coordinate Mapping
+\end_layout
+
+\begin_layout Standard
+For the local coordinate mapping
+\family roman
+\series medium
+\shape up
+\size normal
+\emph off
+\bar no
+\strikeout off
+\uuline off
+\uwave off
+\noun off
+\color none
+
+\begin_inset Formula $\Phi_{R_{0}}\left(\theta\right)$
+\end_inset
+
+
+\family default
+\series default
+\shape default
+\size default
+\emph default
+\bar default
+\strikeout default
+\uuline default
+\uwave default
+\noun default
+\color inherit
+ in
+\begin_inset Formula $\SOthree$
+\end_inset
+
+ we can define a
+\begin_inset Formula $3\times3$
+\end_inset
+
+
+\family roman
+\series medium
+\shape up
+\size normal
+\emph off
+\bar no
+\strikeout off
+\uuline off
+\uwave off
+\noun off
+\color none
+Jacobian
+\begin_inset Formula $H(\theta)$
+\end_inset
+
+ that models the effect of an incremental change
+\begin_inset Formula $\delta$
+\end_inset
+
+ to the local coordinates:
+\family default
+\series default
+\shape default
+\size default
+\emph default
+\bar default
+\strikeout default
+\uuline default
+\uwave default
+\noun default
+\color inherit
+
+\begin_inset Formula
+\begin{equation}
+\Phi_{R_{0}}\left(\theta+\delta\right)\approx\Phi_{R_{0}}\left(\theta\right)\,\exp\left(\Skew{H(\theta)\delta}\right)=\Phi_{\Phi_{R_{0}}\left(\theta\right)}\left(H(\theta)\delta\right)\label{eq:push_exp}
+\end{equation}
+
+\end_inset
+
+This Jacobian depends only on
+\begin_inset Formula $\theta$
+\end_inset
+
+ and, for the case of
+\begin_inset Formula $\SOthree$
+\end_inset
+
+, is given by a formula similar to the matrix exponential map,
+\begin_inset Formula
+\[
+H(\theta)=\sum_{k=0}^{\infty}\frac{(-1)^{k}}{(k+1)!}\Skew{\theta}^{k}
+\]
+
+\end_inset
+
+which can also be computed in closed form.
+ In particular,
+\begin_inset Formula $H(0)=I_{3\times3}$
+\end_inset
+
+ at the base
+\begin_inset Formula $R_{0}$
+\end_inset
+
+.
+\end_layout
+
+\begin_layout Subsubsection*
+Numerical Integration in Local Coordinates
+\end_layout
+
+\begin_layout Standard
+Inspired by the paper
+\begin_inset Quotes eld
+\end_inset
+
+Lie Group Methods
+\begin_inset Quotes erd
+\end_inset
+
+ by Iserles et al.
+
+\begin_inset CommandInset citation
+LatexCommand cite
+key "Iserles00an"
+
+\end_inset
+
+, when we have a differential equation on
+\begin_inset Formula $\SOthree$
+\end_inset
+
+,
+\begin_inset Formula
+\begin{equation}
+\dot{R}(t)=F(R,t),\,\,\,\, R(0)=R_{0}\label{eq:diffSo3}
+\end{equation}
+
+\end_inset
+
+we can transfer it to a differential equation in the 3-dimensional local
+ coordinate space.
+ To do so, we model the solution to
+\begin_inset CommandInset ref
+LatexCommand eqref
+reference "eq:diffSo3"
+
+\end_inset
+
+ as
+\begin_inset Formula
+\[
+R(t)=\Phi_{R_{0}}(\theta(t))
+\]
+
+\end_inset
+
+To find an expression for
+\begin_inset Formula $\dot{\theta}(t)$
+\end_inset
+
+, create a trajectory
+\begin_inset Formula $\gamma(\delta)$
+\end_inset
+
+ that passes through
+\begin_inset Formula $R(t)$
+\end_inset
+
+ for
+\begin_inset Formula $\delta=0$
+\end_inset
+
+, and moves
+\begin_inset Formula $\theta(t)$
+\end_inset
+
+ along the direction
+\begin_inset Formula $\dot{\theta}(t)$
+\end_inset
+
+:
+\begin_inset Formula
+\[
+\gamma(\delta)=R(t+\delta)=\Phi_{R_{0}}\left(\theta(t)+\dot{\theta}(t)\delta\right)\approx\Phi_{R(t)}\left(H(\theta)\dot{\theta}(t)\delta\right)
+\]
+
+\end_inset
+
+Taking the derivative for
+\begin_inset Formula $\delta=0$
+\end_inset
+
+ we obtain
+\begin_inset Formula
+\[
+\dot{R}(t)=\frac{d\gamma(\delta)}{d\delta}\biggr\vert_{\delta=0}=\frac{d\Phi_{R(t)}\left(H(\theta)\dot{\theta}(t)\delta\right)}{d\delta}\biggr\vert_{\delta=0}=R(t)\Skew{H(\theta)\dot{\theta}(t)}
+\]
+
+\end_inset
+
+Comparing this to
+\begin_inset CommandInset ref
+LatexCommand eqref
+reference "eq:diffSo3"
+
+\end_inset
+
+ we obtain a differential equation for
+\begin_inset Formula $\theta(t)$
+\end_inset
+
+:
+\begin_inset Formula
+\[
+\dot{\theta}(t)=H(\theta)^{-1}\left\{ R(t)^{T}F(R,t)\right\} \check{},\,\,\,\,\theta(0)=0_{3\times1}
+\]
+
+\end_inset
+
+In other words, the vector field
+\begin_inset Formula $F(R,t)$
+\end_inset
+
+ is rotated to the local frame, the inverse hat operator is applied to get
+ a 3-vector, which is then corrected by
+\begin_inset Formula $H(\theta)^{-1}$
+\end_inset
+
+ away from
+\begin_inset Formula $\theta=0$
+\end_inset
+
+.
+\end_layout
+
+\begin_layout Subsubsection*
+Retractions
+\end_layout
+
+\begin_layout Standard
+\begin_inset FormulaMacro
+\newcommand{\Rnine}{\mathfrak{\mathbb{R}^{9}}}
+{\mathfrak{\mathbb{R}^{9}}}
+\end_inset
+
+
+\end_layout
+
+\begin_layout Standard
+Note that the use of the exponential map in local coordinate mappings is
+ not obligatory, even in the context of Lie groups.
+ Often it is computationally expedient to use mappings that are easier to
+ compute, but yet induce the same tangent vector at
+\begin_inset Formula $T_{0}.$
+\end_inset
+
+ Mappings that satisfy this constraint are collectively known as
+\series bold
+retractions
+\series default
+.
+ For example, for
+\begin_inset Formula $\SEthree$
+\end_inset
+
+ one could use the retraction
+\begin_inset Formula $\mathcal{R}_{T_{0}}:\Rsix\rightarrow\SEthree$
+\end_inset
+
+
+\begin_inset Formula
+\[
+\mathcal{R}_{T_{0}}\left(\xi\right)=T_{0}\left\{ \exp\left(\Skew{\omega t}\right),vt\right\} =\left\{ \Phi_{R_{0}}\left(\omega t\right),P_{0}+R_{0}vt\right\}
+\]
+
+\end_inset
+
+This trajectory describes a linear path in position while the frame rotates,
+ as opposed to the helical path traced out by the exponential map.
+ The tangent vector at
+\begin_inset Formula $T_{0}$
+\end_inset
+
+ can be computed as
+\end_layout
+
+\begin_layout Standard
+\begin_inset Formula
+\[
+\frac{d\mathcal{R}_{T_{0}}\left(\xi\right)}{dt}\biggr\vert_{t=0}=\left[R_{0}\Skew{\omega},R_{0}v\right]
+\]
+
+\end_inset
+
+which is identical to the one induced by
+\family roman
+\series medium
+\shape up
+\size normal
+\emph off
+\bar no
+\strikeout off
+\uuline off
+\uwave off
+\noun off
+\color none
+
+\begin_inset Formula $\Phi_{T_{0}}(\xi)=T_{0}\exp\xihat$
+\end_inset
+
+.
+\end_layout
+
+\begin_layout Standard
+The NavState manifold is not a Lie group like
+\begin_inset Formula $\SEthree$
+\end_inset
+
+, but we can easily define a retraction that behaves similarly to the one
+ for
+\begin_inset Formula $\SEthree$
+\end_inset
+
+, while treating velocities the same way as positions:
+\begin_inset Formula
+\[
+\mathcal{R}_{X_{0}}(\zeta)=\left\{ \Phi_{R_{0}}\left(\omega t\right),P_{0}+R_{0}vt,V_{0}+R_{0}at\right\}
+\]
+
+\end_inset
+
+Here
+\begin_inset Formula $\zeta=\left[\omega t,vt,at\right]$
+\end_inset
+
+ is a 9-vector, with respectively angular, position, and velocity components.
+ The tangent vector at
+\begin_inset Formula $X_{0}$
+\end_inset
+
+ is
+\begin_inset Formula
+\[
+\frac{d\mathcal{R}_{X_{0}}(\zeta)}{dt}\biggr\vert_{t=0}=\left[R_{0}\Skew{\omega},R_{0}v,R_{0}a\right]
+\]
+
+\end_inset
+
+and the isomorphism between
+\begin_inset Formula $\Rnine$
+\end_inset
+
+ and
+\begin_inset Formula $T_{X_{0}}M$
+\end_inset
+
+ is
+\begin_inset Formula $\zeta\rightarrow\left[R_{0}\Skew{\omega t},R_{0}vt,R_{0}at\right]$
+\end_inset
+
+.
+\end_layout
+
+\begin_layout Subsubsection*
+Integration in Local Coordinates
+\end_layout
+
+\begin_layout Standard
+We now proceed exactly as before to describe the evolution of the NavState
+ in local coordinates.
+ Let us model the solution of the differential equation
+\begin_inset CommandInset ref
+LatexCommand eqref
+reference "eq:diffeqM"
+
+\end_inset
+
+ as a trajectory
+\begin_inset Formula $\zeta(t)=\left[\theta(t),p(t),v(t)\right]$
+\end_inset
+
+, with
+\begin_inset Formula $\zeta(0)=0$
+\end_inset
+
+, in the local coordinate frame anchored at
+\begin_inset Formula $X_{0}$
+\end_inset
+
+.
+ Note that this trajectory evolves away from
+\begin_inset Formula $X_{0}$
+\end_inset
+
+, and we use the symbols
+\begin_inset Formula $\theta$
+\end_inset
+
+,
+\begin_inset Formula $p$
+\end_inset
+
+, and
+\begin_inset Formula $v$
+\end_inset
+
+ to indicate that these are integrated rather than differential quantities.
+ With that, we have
+\begin_inset Formula
+\begin{equation}
+X(t)=\mathcal{R}_{X_{0}}(\zeta(t))=\left\{ \Phi_{R_{0}}\left(\theta(t)\right),P_{0}+R_{0}p(t),V_{0}+R_{0}v(t)\right\} \label{eq:scheme1}
+\end{equation}
+
+\end_inset
+
+We can create a trajectory
+\begin_inset Formula $\gamma(\delta)$
+\end_inset
+
+ that passes through
+\begin_inset Formula $X(t)$
+\end_inset
+
+ for
+\begin_inset Formula $\delta=0$
+\end_inset
+
+
+\begin_inset Formula
+\[
+\gamma(\delta)=X(t+\delta)=\left\{ \Phi_{R_{0}}\left(\theta(t)+\dot{\theta}(t)\delta\right),P_{0}+R_{0}\left\{ p(t)+\dot{p}(t)\delta\right\} ,V_{0}+R_{0}\left\{ v(t)+\dot{v}(t)\delta\right\} \right\}
+\]
+
+\end_inset
+
+and taking the derivative for
+\begin_inset Formula $\delta=0$
+\end_inset
+
+ we obtain
+\begin_inset Formula
+\[
+\dot{X}(t)=\frac{d\gamma(\delta)}{d\delta}\biggr\vert_{\delta=0}=\left[R(t)\Skew{H(\theta)\dot{\theta}(t)},R_{0}\,\dot{p}(t),R_{0}\,\dot{v}(t)\right]
+\]
+
+\end_inset
+
+Comparing that with the vector field
+\begin_inset CommandInset ref
+LatexCommand eqref
+reference "eq:bodyField"
+
+\end_inset
+
+, we have exact integration iff
+\begin_inset Formula
+\[
+\left[R(t)\Skew{H(\theta)\dot{\theta}(t)},R_{0}\,\dot{p}(t),R_{0}\,\dot{v}(t)\right]=\left[R(t)\Skew{\omega^{b}(t)},V(t),g+R(t)a^{b}(t)\right]
+\]
+
+\end_inset
+
+Or, as another way to state this, if we solve the differential equations
+ for
+\begin_inset Formula $\theta(t)$
+\end_inset
+
+,
+\begin_inset Formula $p(t)$
+\end_inset
+
+, and
+\begin_inset Formula $v(t)$
+\end_inset
+
+ such that
+\begin_inset Formula
+\begin{eqnarray*}
+\dot{\theta}(t) & = & H(\theta)^{-1}\,\omega^{b}(t)\\
+\dot{p}(t) & = & R_{0}^{T}\, V_{0}+v(t)\\
+\dot{v}(t) & = & R_{0}^{T}\, g+R_{b}^{0}(t)a^{b}(t)
+\end{eqnarray*}
+
+\end_inset
+
+where
+\family roman
+\series medium
+\shape up
+\size normal
+\emph off
+\bar no
+\strikeout off
+\uuline off
+\uwave off
+\noun off
+\color none
+
+\begin_inset Formula $R_{b}^{0}(t)=R_{0}^{T}R(t)$
+\end_inset
+
+ is the rotation of the body frame with respect to
+\begin_inset Formula $R_{0}$
+\end_inset
+
+, and we have used
+\begin_inset Formula $V(t)=V_{0}+R_{0}v(t)$
+\end_inset
+
+.
+\end_layout
+
+\begin_layout Subsubsection*
+Application: The New IMU Factor
+\end_layout
+
+\begin_layout Standard
+In the IMU factor, we need to predict the NavState
+\begin_inset Formula $X_{j}$
+\end_inset
+
+ from the current NavState
+\begin_inset Formula $X_{i}$
+\end_inset
+
+ and the IMU measurements in-between.
+ The above scheme suffers from a problem, which is that
+\begin_inset Formula $X_{i}$
+\end_inset
+
+ needs to be known in order to compensate properly for the initial velocity
+ and rotated gravity vector.
+ Hence, the idea of Lupton was to split up
+\begin_inset Formula $v(t)$
+\end_inset
+
+ into a gravity-induced part and an accelerometer part
+\begin_inset Formula
+\[
+v(t)=v_{g}(t)+v_{a}(t)
+\]
+
+\end_inset
+
+evolving as
+\begin_inset Formula
+\begin{eqnarray*}
+\dot{v}_{g}(t) & = & R_{i}^{T}\, g\\
+\dot{v}_{a}(t) & = & R_{b}^{i}(t)a^{b}(t)
+\end{eqnarray*}
+
+\end_inset
+
+The solution for the first equation is simply
+\begin_inset Formula $v_{g}(t)=R_{i}^{T}gt$
+\end_inset
+
+.
+ Similarly, we split the position
+\begin_inset Formula $p(t)$
+\end_inset
+
+ up in three parts
+\begin_inset Formula
+\[
+p(t)=p_{i}(t)+p_{g}(t)+p_{v}(t)
+\]
+
+\end_inset
+
+evolving as
+\begin_inset Formula
+\begin{eqnarray*}
+\dot{p}_{i}(t) & = & R_{i}^{T}\, V_{i}\\
+\dot{p}_{g}(t) & = & v_{g}(t)=R_{i}^{T}gt\\
+\dot{p}_{v}(t) & = & v_{a}(t)
+\end{eqnarray*}
+
+\end_inset
+
+Here the solutions for the two first equations are simply
+\begin_inset Formula
+\begin{eqnarray*}
+p_{i}(t) & = & R_{i}^{T}V_{i}t\\
+p_{g}(t) & = & R_{i}^{T}\frac{gt^{2}}{2}
+\end{eqnarray*}
+
+\end_inset
+
+The recipe for the IMU factor is then, in summary.
+ Solve the ordinary differential equations
+\begin_inset Formula
+\begin{eqnarray*}
+\dot{\theta}(t) & = & H(\theta(t))^{-1}\,\omega^{b}(t)\\
+\dot{p}_{v}(t) & = & v_{a}(t)\\
+\dot{v}_{a}(t) & = & R_{b}^{i}(t)a^{b}(t)
+\end{eqnarray*}
+
+\end_inset
+
+starting from zero, up to time
+\begin_inset Formula $t_{ij}$
+\end_inset
+
+, where
+\begin_inset Formula $R_{b}^{i}(t)=\exp\Skew{\theta(t)}$
+\end_inset
+
+ at all times.
+ Form the local coordinate vector as
+\begin_inset Formula
+\[
+\zeta(t_{ij})=\left[\theta(t_{ij}),p(t_{ij}),v(t_{ij})\right]=\left[\theta(t_{ij}),R_{i}^{T}V_{i}t_{ij}+R_{i}^{T}\frac{gt_{ij}^{2}}{2}+p_{v}(t_{ij}),R_{i}^{T}gt_{ij}+v_{a}(t_{ij})\right]
+\]
+
+\end_inset
+
+Predict the NavState
+\begin_inset Formula $X_{j}$
+\end_inset
+
+ at time
+\begin_inset Formula $t_{j}$
+\end_inset
+
+ from
+\begin_inset Formula
+\[
+X_{j}=\mathcal{R}_{X_{i}}(\zeta(t_{ij}))=\left\{ \Phi_{R_{0}}\left(\theta(t_{ij})\right),P_{i}+V_{i}t_{ij}+\frac{gt_{ij}^{2}}{2}+R_{i}\, p_{v}(t_{ij}),V_{i}+gt_{ij}+R_{i}\, v_{a}(t_{ij})\right\}
+\]
+
+\end_inset
+
+
+\end_layout
+
+\begin_layout Standard
+Note that the predicted NavState
+\begin_inset Formula $X_{j}$
+\end_inset
+
+ depends on
+\begin_inset Formula $X_{i}$
+\end_inset
+
+, but the integrated quantities
+\begin_inset Formula $\theta(t)$
+\end_inset
+
+,
+\begin_inset Formula $p_{v}(t)$
+\end_inset
+
+, and
+\begin_inset Formula $v_{a}(t)$
+\end_inset
+
+ do not.
+\end_layout
+
+\begin_layout Subsubsection*
+A Simple Euler Scheme
+\end_layout
+
+\begin_layout Standard
+To solve the differential equation we can use a simple Euler scheme:
+\begin_inset Formula
+\begin{eqnarray}
+\theta_{k+1}=\theta_{k}+\dot{\theta}(t_{k})\Delta_{t} & = & \theta_{k}+H(\theta_{k})^{-1}\,\omega_{k}^{b}\Delta_{t}\label{eq:euler_theta-1}\\
+p_{k+1}=p_{k}+\dot{p}_{v}(t_{k})\Delta_{t} & = & p_{k}+v_{k}\Delta_{t}\label{eq:euler_p-1}\\
+v_{k+1}=v_{k}+\dot{v}_{a}(t_{k})\Delta_{t} & = & v_{k}+\exp\left(\Skew{\theta_{k}}\right)a_{k}^{b}\Delta_{t}\label{eq:euler_v-1}
+\end{eqnarray}
+
+\end_inset
+
+where
+\begin_inset Formula $\theta_{k}\define\theta(t_{k})$
+\end_inset
+
+,
+\begin_inset Formula $p_{k}\define p_{v}(t_{k})$
+\end_inset
+
+, and
+\begin_inset Formula $v_{k}\define v_{a}(t_{k})$
+\end_inset
+
+.
+ However, the position propagation can be done more accurately, by using
+ exact integration of the zero-order hold acceleration
+\begin_inset Formula $a_{k}^{b}$
+\end_inset
+
+:
+\begin_inset Formula
+\begin{eqnarray}
+\theta_{k+1} & = & \theta_{k}+H(\theta_{k})^{-1}\,\omega_{k}^{b}\Delta_{t}\label{eq:euler_theta}\\
+p_{k+1} & = & p_{k}+v_{k}\Delta_{t}+R_{k}a_{k}^{b}\frac{\Delta_{t}^{2}}{2}\label{eq:euler_p}\\
+v_{k+1} & = & v_{k}+R_{k}a_{k}^{b}\Delta_{t}\label{eq:euler_v}
+\end{eqnarray}
+
+\end_inset
+
+where we defined the rotation matrix
+\begin_inset Formula $R_{k}=\exp\left(\Skew{\theta_{k}}\right)$
+\end_inset
+
+.
+\end_layout
+
+\begin_layout Subsubsection*
+Noise Propagation
+\end_layout
+
+\begin_layout Standard
+Even when we assume uncorrelated noise on
+\begin_inset Formula $\omega^{b}$
+\end_inset
+
+ and
+\begin_inset Formula $a^{b}$
+\end_inset
+
+, the noise on the final computed quantities will have a non-trivial covariance
+ structure, because the intermediate quantities
+\begin_inset Formula $\theta_{k}$
+\end_inset
+
+ and
+\begin_inset Formula $v_{k}$
+\end_inset
+
+ appear in multiple places.
+ To model the noise propagation, let us define
+\begin_inset Formula $\zeta_{k}=[\theta_{k},p_{k},v_{k}]$
+\end_inset
+
+ and rewrite Eqns.
+ (
+\begin_inset CommandInset ref
+LatexCommand ref
+reference "eq:euler_theta"
+
+\end_inset
+
+-
+\begin_inset CommandInset ref
+LatexCommand ref
+reference "eq:euler_v"
+
+\end_inset
+
+) as the non-linear function
+\begin_inset Formula $f$
+\end_inset
+
+
+\begin_inset Formula
+\[
+\zeta_{k+1}=f\left(\zeta_{k},a_{k}^{b},\omega_{k}^{b}\right)
+\]
+
+\end_inset
+
+Then the noise on
+\begin_inset Formula $\zeta_{k+1}$
+\end_inset
+
+ propagates as
+\begin_inset Formula
+\begin{equation}
+\Sigma_{k+1}=A_{k}\Sigma_{k}A_{k}^{T}+B_{k}\Sigma_{\eta}^{ad}B_{k}+C_{k}\Sigma_{\eta}^{gd}C_{k}\label{eq:prop}
+\end{equation}
+
+\end_inset
+
+where
+\begin_inset Formula $A_{k}$
+\end_inset
+
+ is the
+\begin_inset Formula $9\times9$
+\end_inset
+
+ partial derivative of
+\begin_inset Formula $f$
+\end_inset
+
+ wrpt
+\begin_inset Formula $\zeta$
+\end_inset
+
+, and
+\begin_inset Formula $B_{k}$
+\end_inset
+
+ and
+\begin_inset Formula $C_{k}$
+\end_inset
+
+ the respective
+\begin_inset Formula $9\times3$
+\end_inset
+
+ partial derivatives with respect to the measured quantities
+\begin_inset Formula $a^{b}$
+\end_inset
+
+ and
+\begin_inset Formula $\omega^{b}$
+\end_inset
+
+.
+\end_layout
+
+\begin_layout Standard
+We start with the noise propagation on
+\begin_inset Formula $\theta$
+\end_inset
+
+, which is independent of the other quantities.
+ Taking the derivative, we have
+\end_layout
+
+\begin_layout Standard
+\begin_inset Formula
+\[
+\deriv{\theta_{k+1}}{\theta_{k}}=I_{3x3}+\deriv{H(\theta_{k})^{-1}\omega_{k}^{b}}{\theta_{k}}\Delta_{t}
+\]
+
+\end_inset
+
+It can be shown that for small
+\begin_inset Formula $\theta_{k}$
+\end_inset
+
+ we have
+\begin_inset Formula
+\[
+\deriv{H(\theta_{k})^{-1}\omega_{k}^{b}}{\theta_{k}}\approx-\frac{1}{2}\Skew{\omega_{k}^{b}}\mbox{ and hence }\deriv{\theta_{k+1}}{\theta_{k}}=I_{3x3}-\frac{\Delta t}{2}\Skew{\omega_{k}^{b}}
+\]
+
+\end_inset
+
+For the derivatives of
+\begin_inset Formula $p_{k+1}$
+\end_inset
+
+ and
+\begin_inset Formula $v_{k+1}$
+\end_inset
+
+ we need the derivative
+\begin_inset Formula
+\[
+\deriv{R_{k}a_{k}^{b}}{\theta_{k}}=R_{k}\Skew{-a_{k}^{b}}\deriv{R_{k}}{\theta_{k}}=R_{k}\Skew{-a_{k}^{b}}H(\theta_{k})
+\]
+
+\end_inset
+
+where we used
+\begin_inset Formula
+\[
+\deriv{\left(Ra\right)}R\approx R\Skew{-a}
+\]
+
+\end_inset
+
+and the fact that the dependence of the rotation
+\begin_inset Formula $R_{k}$
+\end_inset
+
+ on
+\begin_inset Formula $\theta_{k}$
+\end_inset
+
+ is the already computed
+\begin_inset Formula $H(\theta_{k})$
+\end_inset
+
+.
+
+\end_layout
+
+\begin_layout Standard
+Putting all this together, we finally obtain
+\begin_inset Formula
+\[
+A_{k}\approx\left[\begin{array}{ccc}
+I_{3\times3}-\frac{\Delta_{t}}{2}\Skew{\omega_{k}^{b}}\\
+R_{k}\Skew{-a_{k}^{b}}H(\theta_{k})\frac{\Delta_{t}}{2}^{2} & I_{3\times3} & I_{3\times3}\Delta_{t}\\
+R_{k}\Skew{-a_{k}^{b}}H(\theta_{k})\Delta_{t} & & I_{3\times3}
+\end{array}\right]
+\]
+
+\end_inset
+
+The other partial derivatives are simply
+\begin_inset Formula
+\[
+B_{k}=\left[\begin{array}{c}
+0_{3\times3}\\
+R_{k}\frac{\Delta_{t}}{2}^{2}\\
+R_{k}\Delta_{t}
+\end{array}\right],\,\,\,\, C_{k}=\left[\begin{array}{c}
+H(\theta_{k})^{-1}\Delta_{t}\\
+0_{3\times3}\\
+0_{3\times3}
+\end{array}\right]
+\]
+
+\end_inset
+
+
+\end_layout
+
+\begin_layout Standard
+\begin_inset CommandInset bibtex
+LatexCommand bibtex
+bibfiles "refs"
+options "plain"
+
+\end_inset
+
+
+\end_layout
+
+\end_body
+\end_document
diff --git a/doc/ImuFactor.pdf b/doc/ImuFactor.pdf
new file mode 100644
index 000000000..f5a25f54f
Binary files /dev/null and b/doc/ImuFactor.pdf differ
diff --git a/doc/LieGroups.lyx b/doc/LieGroups.lyx
index adf62314c..0d194b31d 100644
--- a/doc/LieGroups.lyx
+++ b/doc/LieGroups.lyx
@@ -76,335 +76,10 @@ Frank Dellaert
\end_layout
\begin_layout Standard
-\begin_inset Note Comment
-status open
+\begin_inset CommandInset include
+LatexCommand include
+filename "macros.lyx"
-\begin_layout Plain Layout
-Derivatives
-\end_layout
-
-\end_inset
-
-
-\end_layout
-
-\begin_layout Standard
-\begin_inset FormulaMacro
-\newcommand{\deriv}[2]{\frac{\partial#1}{\partial#2}}
-{\frac{\partial#1}{\partial#2}}
-\end_inset
-
-
-\begin_inset FormulaMacro
-\newcommand{\at}[2]{#1\biggr\rvert_{#2}}
-{#1\biggr\rvert_{#2}}
-\end_inset
-
-
-\begin_inset FormulaMacro
-\newcommand{\Jac}[3]{ \at{\deriv{#1}{#2}} {#3} }
-{\at{\deriv{#1}{#2}}{#3}}
-\end_inset
-
-
-\end_layout
-
-\begin_layout Standard
-\begin_inset Note Comment
-status open
-
-\begin_layout Plain Layout
-Lie Groups
-\end_layout
-
-\end_inset
-
-
-\end_layout
-
-\begin_layout Standard
-\begin_inset FormulaMacro
-\newcommand{\xhat}{\hat{x}}
-{\hat{x}}
-\end_inset
-
-
-\begin_inset FormulaMacro
-\newcommand{\yhat}{\hat{y}}
-{\hat{y}}
-\end_inset
-
-
-\begin_inset FormulaMacro
-\newcommand{\Ad}[1]{Ad_{#1}}
-{Ad_{#1}}
-\end_inset
-
-
-\begin_inset FormulaMacro
-\newcommand{\AAdd}[1]{\mathbf{\mathop{Ad}}{}_{#1}}
-{\mathbf{\mathop{Ad}}{}_{#1}}
-\end_inset
-
-
-\end_layout
-
-\begin_layout Standard
-\begin_inset FormulaMacro
-\newcommand{\define}{\stackrel{\Delta}{=}}
-{\stackrel{\Delta}{=}}
-\end_inset
-
-
-\begin_inset FormulaMacro
-\newcommand{\gg}{\mathfrak{g}}
-{\mathfrak{g}}
-\end_inset
-
-
-\begin_inset FormulaMacro
-\newcommand{\Rn}{\mathbb{R}^{n}}
-{\mathbb{R}^{n}}
-\end_inset
-
-
-\end_layout
-
-\begin_layout Standard
-\begin_inset Note Comment
-status open
-
-\begin_layout Plain Layout
-SO(2), 1
-\end_layout
-
-\end_inset
-
-
-\end_layout
-
-\begin_layout Standard
-\begin_inset FormulaMacro
-\newcommand{\Rtwo}{\mathfrak{\mathbb{R}^{2}}}
-{\mathfrak{\mathbb{R}^{2}}}
-\end_inset
-
-
-\begin_inset FormulaMacro
-\newcommand{\SOtwo}{SO(2)}
-{SO(2)}
-\end_inset
-
-
-\begin_inset FormulaMacro
-\newcommand{\sotwo}{\mathfrak{so(2)}}
-{\mathfrak{so(2)}}
-\end_inset
-
-
-\begin_inset FormulaMacro
-\newcommand{\that}{\hat{\theta}}
-{\hat{\theta}}
-\end_inset
-
-
-\begin_inset FormulaMacro
-\newcommand{\skew}[1]{[#1]_{+}}
-{[#1]_{+}}
-\end_inset
-
-
-\end_layout
-
-\begin_layout Standard
-\begin_inset Note Comment
-status open
-
-\begin_layout Plain Layout
-SE(2), 3
-\end_layout
-
-\end_inset
-
-
-\end_layout
-
-\begin_layout Standard
-\begin_inset FormulaMacro
-\newcommand{\SEtwo}{SE(2)}
-{SE(2)}
-\end_inset
-
-
-\begin_inset FormulaMacro
-\newcommand{\setwo}{\mathfrak{se(2)}}
-{\mathfrak{se(2)}}
-\end_inset
-
-
-\begin_inset FormulaMacro
-\newcommand{\Skew}[1]{[#1]_{\times}}
-{[#1]_{\times}}
-\end_inset
-
-
-\end_layout
-
-\begin_layout Standard
-\begin_inset Note Comment
-status open
-
-\begin_layout Plain Layout
-SO(3), 3
-\end_layout
-
-\end_inset
-
-
-\end_layout
-
-\begin_layout Standard
-\begin_inset FormulaMacro
-\newcommand{\Rthree}{\mathfrak{\mathbb{R}^{3}}}
-{\mathfrak{\mathbb{R}^{3}}}
-\end_inset
-
-
-\begin_inset FormulaMacro
-\newcommand{\SOthree}{SO(3)}
-{SO(3)}
-\end_inset
-
-
-\begin_inset FormulaMacro
-\newcommand{\sothree}{\mathfrak{so(3)}}
-{\mathfrak{so(3)}}
-\end_inset
-
-
-\begin_inset FormulaMacro
-\newcommand{\what}{\hat{\omega}}
-{\hat{\omega}}
-\end_inset
-
-
-\end_layout
-
-\begin_layout Standard
-\begin_inset Note Comment
-status open
-
-\begin_layout Plain Layout
-SE(3),6
-\end_layout
-
-\end_inset
-
-
-\end_layout
-
-\begin_layout Standard
-\begin_inset FormulaMacro
-\newcommand{\Rsix}{\mathfrak{\mathbb{R}^{6}}}
-{\mathfrak{\mathbb{R}^{6}}}
-\end_inset
-
-
-\begin_inset FormulaMacro
-\newcommand{\SEthree}{SE(3)}
-{SE(3)}
-\end_inset
-
-
-\begin_inset FormulaMacro
-\newcommand{\sethree}{\mathfrak{se(3)}}
-{\mathfrak{se(3)}}
-\end_inset
-
-
-\begin_inset FormulaMacro
-\newcommand{\xihat}{\hat{\xi}}
-{\hat{\xi}}
-\end_inset
-
-
-\end_layout
-
-\begin_layout Standard
-\begin_inset Note Comment
-status open
-
-\begin_layout Plain Layout
-Aff(2),6
-\end_layout
-
-\end_inset
-
-
-\end_layout
-
-\begin_layout Standard
-\begin_inset FormulaMacro
-\newcommand{\Afftwo}{Aff(2)}
-{Aff(2)}
-\end_inset
-
-
-\begin_inset FormulaMacro
-\newcommand{\afftwo}{\mathfrak{aff(2)}}
-{\mathfrak{aff(2)}}
-\end_inset
-
-
-\begin_inset FormulaMacro
-\newcommand{\aa}{a}
-{a}
-\end_inset
-
-
-\begin_inset FormulaMacro
-\newcommand{\ahat}{\hat{a}}
-{\hat{a}}
-\end_inset
-
-
-\end_layout
-
-\begin_layout Standard
-\begin_inset Note Comment
-status collapsed
-
-\begin_layout Plain Layout
-SL(3),8
-\end_layout
-
-\end_inset
-
-
-\end_layout
-
-\begin_layout Standard
-\begin_inset FormulaMacro
-\newcommand{\SLthree}{SL(3)}
-{SL(3)}
-\end_inset
-
-
-\begin_inset FormulaMacro
-\newcommand{\slthree}{\mathfrak{sl(3)}}
-{\mathfrak{sl(3)}}
-\end_inset
-
-
-\begin_inset FormulaMacro
-\newcommand{\hh}{h}
-{h}
-\end_inset
-
-
-\begin_inset FormulaMacro
-\newcommand{\hhat}{\hat{h}}
-{\hat{h}}
\end_inset
diff --git a/doc/macros.lyx b/doc/macros.lyx
index 1e57e1675..0d8429c4a 100644
--- a/doc/macros.lyx
+++ b/doc/macros.lyx
@@ -1,42 +1,60 @@
-#LyX 1.6.5 created this file. For more info see http://www.lyx.org/
-\lyxformat 345
+#LyX 2.0 created this file. For more info see http://www.lyx.org/
+\lyxformat 413
\begin_document
\begin_header
\textclass article
\use_default_options true
+\maintain_unincluded_children false
\language english
+\language_package default
\inputencoding auto
+\fontencoding global
\font_roman default
\font_sans default
\font_typewriter default
\font_default_family default
+\use_non_tex_fonts false
\font_sc false
\font_osf false
\font_sf_scale 100
\font_tt_scale 100
\graphics default
+\default_output_format default
+\output_sync 0
+\bibtex_command default
+\index_command default
\paperfontsize default
\use_hyperref false
\papersize default
\use_geometry false
\use_amsmath 1
\use_esint 1
+\use_mhchem 1
+\use_mathdots 0
\cite_engine basic
\use_bibtopic false
+\use_indices false
\paperorientation portrait
+\suppress_date false
+\use_refstyle 0
+\index Index
+\shortcut idx
+\color #008000
+\end_index
\secnumdepth 3
\tocdepth 3
\paragraph_separation indent
-\defskip medskip
+\paragraph_indentation default
\quotes_language english
\papercolumns 1
\papersides 1
\paperpagestyle default
\tracking_changes false
\output_changes false
-\author ""
-\author ""
+\html_math_output 0
+\html_css_as_file 0
+\html_be_strict false
\end_header
\begin_body
@@ -62,14 +80,14 @@ Derivatives
\begin_inset FormulaMacro
-\newcommand{\at}[2]{#1\biggr\rvert_{#2}}
-{#1\biggr\rvert_{#2}}
+\newcommand{\at}[1]{#1\biggr\vert_{\#2}}
+{#1\biggr\vert_{\#2}}
\end_inset
\begin_inset FormulaMacro
\newcommand{\Jac}[3]{ \at{\deriv{#1}{#2}} {#3} }
-{\at{\deriv{#1}{#2}}{#3}}
+{\at{\deriv{#1}{#2}}#3}
\end_inset
@@ -107,6 +125,15 @@ Lie Groups
\end_inset
+\end_layout
+
+\begin_layout Standard
+\begin_inset FormulaMacro
+\newcommand{\AAdd}[1]{\mathbf{\mathop{Ad}}{}_{#1}}
+{\mathbf{\mathop{Ad}}{}_{#1}}
+\end_inset
+
+
\end_layout
\begin_layout Standard
@@ -144,6 +171,12 @@ SO(2)
\end_layout
\begin_layout Standard
+\begin_inset FormulaMacro
+\newcommand{\Rone}{\mathfrak{\mathbb{R}}}
+{\mathfrak{\mathbb{R}}}
+\end_inset
+
+
\begin_inset FormulaMacro
\newcommand{\Rtwo}{\mathfrak{\mathbb{R}^{2}}}
{\mathfrak{\mathbb{R}^{2}}}
@@ -202,6 +235,12 @@ SE(2)
\end_inset
+\begin_inset FormulaMacro
+\newcommand{\Skew}[1]{[#1]_{\times}}
+{[#1]_{\times}}
+\end_inset
+
+
\end_layout
\begin_layout Standard
@@ -243,7 +282,7 @@ SO(3)
\begin_inset FormulaMacro
-\newcommand{\Skew}[1]{[#1]_{\times}}
+\renewcommand{\Skew}[1]{[#1]_{\times}}
{[#1]_{\times}}
\end_inset
@@ -288,6 +327,86 @@ SE(3)
\end_inset
+\end_layout
+
+\begin_layout Standard
+\begin_inset Note Comment
+status open
+
+\begin_layout Plain Layout
+Aff(2),6
+\end_layout
+
+\end_inset
+
+
+\end_layout
+
+\begin_layout Standard
+\begin_inset FormulaMacro
+\newcommand{\Afftwo}{Aff(2)}
+{Aff(2)}
+\end_inset
+
+
+\begin_inset FormulaMacro
+\newcommand{\afftwo}{\mathfrak{aff(2)}}
+{\mathfrak{aff(2)}}
+\end_inset
+
+
+\begin_inset FormulaMacro
+\newcommand{\aa}{a}
+{a}
+\end_inset
+
+
+\begin_inset FormulaMacro
+\newcommand{\ahat}{\hat{a}}
+{\hat{a}}
+\end_inset
+
+
+\end_layout
+
+\begin_layout Standard
+\begin_inset Note Comment
+status collapsed
+
+\begin_layout Plain Layout
+SL(3),8
+\end_layout
+
+\end_inset
+
+
+\end_layout
+
+\begin_layout Standard
+\begin_inset FormulaMacro
+\newcommand{\SLthree}{SL(3)}
+{SL(3)}
+\end_inset
+
+
+\begin_inset FormulaMacro
+\newcommand{\slthree}{\mathfrak{sl(3)}}
+{\mathfrak{sl(3)}}
+\end_inset
+
+
+\begin_inset FormulaMacro
+\newcommand{\hh}{h}
+{h}
+\end_inset
+
+
+\begin_inset FormulaMacro
+\newcommand{\hhat}{\hat{h}}
+{\hat{h}}
+\end_inset
+
+
\end_layout
\end_body
diff --git a/doc/math.lyx b/doc/math.lyx
index d96f1f4c8..5571532f6 100644
--- a/doc/math.lyx
+++ b/doc/math.lyx
@@ -1237,21 +1237,28 @@ reference "eq:ApproximateObjective"
\end_inset
.
- In particular, the notion of an exponential map allows us to define an
- incremental transformation as tracing out a geodesic curve on the group
- manifold along a certain
+ In particular, the notion of an exponential map allows us to define a mapping
+ from
\series bold
-tangent vector
+local coordinates
\series default
\begin_inset Formula $\xi$
+\end_inset
+
+ back to a neighborhood in
+\begin_inset Formula $G$
+\end_inset
+
+ around
+\begin_inset Formula $a$
\end_inset
,
\begin_inset Formula
-\[
-a\oplus\xi\define a\exp\left(\hat{\xi}\right)
-\]
+\begin{equation}
+a\oplus\xi\define a\exp\left(\hat{\xi}\right)\label{eq:expmap}
+\end{equation}
\end_inset
@@ -1263,11 +1270,12 @@ with
\begin_inset Formula $n$
\end_inset
--dimensional Lie group,
+-dimensional Lie group.
+ Above,
\begin_inset Formula $\hat{\xi}\in\mathfrak{g}$
\end_inset
- the Lie algebra element corresponding to the vector
+ is the Lie algebra element corresponding to the vector
\begin_inset Formula $\xi$
\end_inset
@@ -1305,7 +1313,7 @@ For the Lie group
\end_inset
is denoted as
-\begin_inset Formula $\omega$
+\begin_inset Formula $\omega t$
\end_inset
and represents an angular displacement.
@@ -1314,17 +1322,17 @@ For the Lie group
\end_inset
is a skew symmetric matrix denoted as
-\begin_inset Formula $\Skew{\omega}\in\sothree$
+\begin_inset Formula $\Skew{\omega t}\in\sothree$
\end_inset
, and is given by
\begin_inset Formula
\[
-\Skew{\omega}=\left[\begin{array}{ccc}
+\Skew{\omega t}=\left[\begin{array}{ccc}
0 & -\omega_{z} & \omega_{y}\\
\omega_{z} & 0 & -\omega_{x}\\
-\omega_{y} & \omega_{x} & 0
-\end{array}\right]
+\end{array}\right]t
\]
\end_inset
@@ -1334,12 +1342,136 @@ Finally, the increment
\end_inset
corresponds to an incremental rotation
-\begin_inset Formula $R\oplus\omega=Re^{\Skew{\omega}}$
+\begin_inset Formula $R\oplus\omega t=Re^{\Skew{\omega t}}$
\end_inset
.
\end_layout
+\begin_layout Subsection
+Local Coordinates vs.
+ Tangent Vectors
+\end_layout
+
+\begin_layout Standard
+In differential geometry,
+\series bold
+tangent vectors
+\series default
+
+\begin_inset Formula $v\in T_{a}G$
+\end_inset
+
+ at
+\begin_inset Formula $a$
+\end_inset
+
+ are elements of the Lie algebra
+\begin_inset Formula $\mathfrak{g}$
+\end_inset
+
+, and are defined as
+\begin_inset Formula
+\[
+v\define\Jac{\gamma(t)}t{t=0}
+\]
+
+\end_inset
+
+where
+\begin_inset Formula $\gamma$
+\end_inset
+
+ is some curve that passes through
+\begin_inset Formula $a$
+\end_inset
+
+ at
+\begin_inset Formula $t=0$
+\end_inset
+
+, i.e.
+
+\begin_inset Formula $\gamma(0)=a$
+\end_inset
+
+.
+ In particular, for any fixed local coordinate
+\begin_inset Formula $\xi$
+\end_inset
+
+ the map
+\begin_inset CommandInset ref
+LatexCommand eqref
+reference "eq:expmap"
+
+\end_inset
+
+ can be used to define a
+\series bold
+geodesic curve
+\series default
+ on the group manifold defined by
+\begin_inset Formula $\gamma:t\mapsto ae^{\widehat{t\xi}}$
+\end_inset
+
+, and the corresponding tangent vector is given by
+\begin_inset Formula
+\begin{equation}
+\Jac{ae^{\widehat{t\xi}}}t{t=0}=a\xihat\label{eq:tangent-vector}
+\end{equation}
+
+\end_inset
+
+This defines the mapping between local coordinates
+\begin_inset Formula $\xi\in\Rn$
+\end_inset
+
+ and actual tangent vectors
+\begin_inset Formula $a\xihat\in g$
+\end_inset
+
+: the vector
+\begin_inset Formula $\xi$
+\end_inset
+
+ defines a direction of travel on the manifold, but does so in the local
+ coordinate frame
+\begin_inset Formula $a$
+\end_inset
+
+.
+\end_layout
+
+\begin_layout Example
+Assume a rigid body's attitude is described by
+\begin_inset Formula $R_{b}^{n}(t)$
+\end_inset
+
+, where the indices denote the navigation frame
+\begin_inset Formula $N$
+\end_inset
+
+ and body frame
+\begin_inset Formula $B$
+\end_inset
+
+, respectively.
+ An extrinsically calibrated gyroscope measures the angular velocity
+\begin_inset Formula $\omega^{b}$
+\end_inset
+
+, in the body frame, and the corresponding tangent vector is
+\begin_inset Formula
+\[
+\dot{R}_{b}^{n}(t)=R_{b}^{n}(t)\widehat{\omega^{b}}
+\]
+
+\end_inset
+
+
+\end_layout
+
\begin_layout Subsection
Derivatives
\end_layout
@@ -1352,7 +1484,7 @@ reference "def:differentiable"
\end_inset
- to map exponential coordinates
+ to map local coordinates
\begin_inset Formula $\xi$
\end_inset
@@ -1368,7 +1500,7 @@ reference "def:differentiable"
\begin_inset Formula $Df_{a}$
\end_inset
- locally approximates a function
+ approximates the function
\begin_inset Formula $f$
\end_inset
@@ -1378,6 +1510,10 @@ reference "def:differentiable"
to
\begin_inset Formula $\Reals m$
+\end_inset
+
+ in a neighborhood around
+\begin_inset Formula $a$
\end_inset
:
@@ -1455,41 +1591,6 @@ derivative
.
\end_layout
-\begin_layout Standard
-Note that the vectors
-\begin_inset Formula $\xi$
-\end_inset
-
- can be viewed as lying in the tangent space to
-\begin_inset Formula $G$
-\end_inset
-
- at
-\begin_inset Formula $a$
-\end_inset
-
-, but defining this rigorously would take us on a longer tour of differential
- geometry.
- Informally,
-\begin_inset Formula $\xi$
-\end_inset
-
- is simply the direction, in a local coordinate frame, that is locally tangent
- at
-\begin_inset Formula $a$
-\end_inset
-
- to a geodesic curve
-\begin_inset Formula $\gamma:t\mapsto ae^{\widehat{t\xi}}$
-\end_inset
-
- traced out by the exponential map, with
-\begin_inset Formula $\gamma(0)=a$
-\end_inset
-
-.
-\end_layout
-
\begin_layout Subsection
Derivative of an Action
\begin_inset CommandInset label
@@ -3000,7 +3101,7 @@ f(ge^{\xhat})=f(ge^{\xhat}g^{-1}g)=f(e^{\Ad g\xhat}g)
\end_layout
\begin_layout Subsection
-Derivative of the Exponential and Logarithm Map
+Derivative of the Exponential Map
\end_layout
\begin_layout Theorem
@@ -3064,17 +3165,196 @@ For
\begin_inset Formula $\xi\neq0$
\end_inset
-, things are not simple, see .
+, things are not simple.
+ As with pushforwards above, we will be looking for an
+\begin_inset Formula $n\times n$
+\end_inset
+
-\begin_inset Flex URL
+\family roman
+\series medium
+\shape up
+\size normal
+\emph off
+\bar no
+\strikeout off
+\uuline off
+\uwave off
+\noun off
+\color none
+Jacobian
+\begin_inset Formula $f'(\xi)$
+\end_inset
+
+ such that
+\family default
+\series default
+\shape default
+\size default
+\emph default
+\bar default
+\strikeout default
+\uuline default
+\uwave default
+\noun default
+\color inherit
+
+\begin_inset Formula
+\begin{equation}
+f\left(\xi+\delta\right)\approx f\left(\xi\right)\exp\left(\widehat{f'(\xi)\delta}\right)\label{eq:push_exp}
+\end{equation}
+
+\end_inset
+
+Differential geometry tells us that for any Lie algebra element
+\begin_inset Formula $\xihat\in\mathfrak{g}$
+\end_inset
+
+ there exists a
+\emph on
+linear
+\emph default
+ map
+\begin_inset Formula $d\exp_{\xihat}:T_{\xihat}\mathfrak{g}\rightarrow T_{\exp(\xihat)}G$
+\end_inset
+
+, which is given by
+\begin_inset Foot
status collapsed
\begin_layout Plain Layout
+See
+\begin_inset Flex URL
+status open
-http://deltaepsilons.wordpress.com/2009/11/06/helgasons-formula-for-the-differenti
-al-of-the-exponential/
+\begin_layout Plain Layout
+
+http://deltaepsilons.wordpress.com/2009/11/06/
\end_layout
+\end_inset
+
+ or
+\begin_inset Flex URL
+status open
+
+\begin_layout Plain Layout
+
+https://en.wikipedia.org/wiki/Derivative_of_the_exponential_map
+\end_layout
+
+\end_inset
+
+.
+\end_layout
+
+\end_inset
+
+
+\begin_inset Formula
+\begin{equation}
+d\exp_{\xihat}\hat{x}=\exp(\xihat)\frac{1-\exp(-ad_{\xihat})}{ad_{\xihat}}\hat{x}\label{eq:dexp}
+\end{equation}
+
+\end_inset
+
+with
+\begin_inset Formula $\hat{x}\in T_{\xihat}\mathfrak{g}$
+\end_inset
+
+ and
+\begin_inset Formula $ad_{\xihat}$
+\end_inset
+
+ itself a linear map taking
+\begin_inset Formula $\hat{x}$
+\end_inset
+
+ to
+\begin_inset Formula $[\xihat,\hat{x}]$
+\end_inset
+
+, the Lie bracket.
+ The actual formula above is not really as important as the fact that the
+ linear map exists, although it is expressed directly in terms of tangent
+ vectors to
+\begin_inset Formula $\mathfrak{g}$
+\end_inset
+
+ and
+\begin_inset Formula $G$
+\end_inset
+
+.
+ Equation
+\begin_inset CommandInset ref
+LatexCommand eqref
+reference "eq:dexp"
+
+\end_inset
+
+ is a tangent vector, and comparing with
+\begin_inset CommandInset ref
+LatexCommand eqref
+reference "eq:tangent-vector"
+
+\end_inset
+
+ we see that it maps to local coordinates
+\begin_inset Formula $y$
+\end_inset
+
+ as follows:
+\begin_inset Formula
+\[
+\yhat=\frac{1-\exp(-ad_{\xihat})}{ad_{\xihat}}\hat{x}
+\]
+
+\end_inset
+
+which can be used to construct the Jacobian
+\begin_inset Formula $f'(\xi)$
+\end_inset
+
+.
+\end_layout
+
+\begin_layout Example
+For
+\begin_inset Formula $\SOthree$
+\end_inset
+
+, the operator
+\begin_inset Formula $ad_{\xihat}$
+\end_inset
+
+ is simply a matrix multiplication when representing
+\begin_inset Formula $\sothree$
+\end_inset
+
+ using 3-vectors, i.e.,
+\begin_inset Formula $ad_{\xihat}x=\xihat x$
+\end_inset
+
+, and the
+\begin_inset Formula $3\times3$
+\end_inset
+
+ Jacobian corresponding to
+\begin_inset Formula $d\exp$
+\end_inset
+
+ is
+\begin_inset Formula
+\[
+f'(\xi)=\frac{I_{3\times3}-\exp(-\xihat)}{\xihat}=\sum_{k=0}^{\infty}\frac{(-1)^{k}}{(k+1)!}\xihat^{k}
+\]
+
+\end_inset
+
+which, similar to the exponential map, has a simple closed form expression
+ for
+\begin_inset Formula $\SOthree$
\end_inset
.
@@ -3097,7 +3377,7 @@ Retractions
\begin_layout Standard
\begin_inset FormulaMacro
-\newcommand{\retract}{\mathcal{R}}
+\renewcommand{\retract}{\mathcal{R}}
{\mathcal{R}}
\end_inset
@@ -6797,7 +7077,7 @@ Then
\begin_layout Standard
\begin_inset CommandInset bibtex
LatexCommand bibtex
-bibfiles "/Users/dellaert/papers/refs"
+bibfiles "refs"
options "plain"
\end_inset
diff --git a/doc/refs.bib b/doc/refs.bib
new file mode 100644
index 000000000..414773483
--- /dev/null
+++ b/doc/refs.bib
@@ -0,0 +1,26 @@
+@article{Iserles00an,
+ title = {Lie-group methods},
+ author = {Iserles, Arieh and Munthe-Kaas, Hans Z and
+ N{\o}rsett, Syvert P and Zanna, Antonella},
+ journal = {Acta Numerica 2000},
+ volume = {9},
+ pages = {215--365},
+ year = {2000},
+ publisher = {Cambridge Univ Press}
+}
+
+@book{Murray94book,
+ title = {A mathematical introduction to robotic manipulation},
+ author = {Murray, Richard M and Li, Zexiang and Sastry, S
+ Shankar and Sastry, S Shankara},
+ year = {1994},
+ publisher = {CRC press}
+}
+
+@book{Spivak65book,
+ title = {Calculus on manifolds},
+ author = {Spivak, Michael},
+ volume = {1},
+ year = {1965},
+ publisher = {WA Benjamin New York}
+}
\ No newline at end of file
diff --git a/examples/CreateSFMExampleData.cpp b/examples/CreateSFMExampleData.cpp
index bcc0b6320..010f474bf 100644
--- a/examples/CreateSFMExampleData.cpp
+++ b/examples/CreateSFMExampleData.cpp
@@ -35,7 +35,7 @@ void createExampleBALFile(const string& filename, const vector& P,
SfM_data data;
// Create two cameras
- Rot3 aRb = Rot3::yaw(M_PI_2);
+ Rot3 aRb = Rot3::Yaw(M_PI_2);
Point3 aTb(0.1, 0, 0);
Pose3 identity, aPb(aRb, aTb);
data.cameras.push_back(SfM_Camera(pose1, K));
@@ -66,7 +66,7 @@ void createExampleBALFile(const string& filename, const vector& P,
void create5PointExample1() {
// Create two cameras poses
- Rot3 aRb = Rot3::yaw(M_PI_2);
+ Rot3 aRb = Rot3::Yaw(M_PI_2);
Point3 aTb(0.1, 0, 0);
Pose3 pose1, pose2(aRb, aTb);
@@ -85,7 +85,7 @@ void create5PointExample1() {
void create5PointExample2() {
// Create two cameras poses
- Rot3 aRb = Rot3::yaw(M_PI_2);
+ Rot3 aRb = Rot3::Yaw(M_PI_2);
Point3 aTb(10, 0, 0);
Pose3 pose1, pose2(aRb, aTb);
diff --git a/examples/Data/.gitignore b/examples/Data/.gitignore
new file mode 100644
index 000000000..2211df63d
--- /dev/null
+++ b/examples/Data/.gitignore
@@ -0,0 +1 @@
+*.txt
diff --git a/examples/PlanarSLAMExample.cpp b/examples/PlanarSLAMExample.cpp
index 84f9be3a1..a716f9cd8 100644
--- a/examples/PlanarSLAMExample.cpp
+++ b/examples/PlanarSLAMExample.cpp
@@ -42,7 +42,7 @@
// Also, we will initialize the robot at the origin using a Prior factor.
#include
#include
-#include
+#include
// When the factors are created, we will add them to a Factor Graph. As the factors we are using
// are nonlinear factors, we will need a Nonlinear Factor Graph.
diff --git a/examples/RangeISAMExample_plaza2.cpp b/examples/RangeISAMExample_plaza2.cpp
index 04632e9e3..4d116c7ec 100644
--- a/examples/RangeISAMExample_plaza2.cpp
+++ b/examples/RangeISAMExample_plaza2.cpp
@@ -39,7 +39,7 @@
// have been provided with the library for solving robotics SLAM problems.
#include
#include
-#include
+#include
#include
// Standard headers, added last, so we know headers above work on their own
diff --git a/examples/SFMExample.cpp b/examples/SFMExample.cpp
index 38dd1ca81..8da9847b8 100644
--- a/examples/SFMExample.cpp
+++ b/examples/SFMExample.cpp
@@ -97,7 +97,7 @@ int main(int argc, char* argv[]) {
// Intentionally initialize the variables off from the ground truth
Values initialEstimate;
for (size_t i = 0; i < poses.size(); ++i)
- initialEstimate.insert(Symbol('x', i), poses[i].compose(Pose3(Rot3::rodriguez(-0.1, 0.2, 0.25), Point3(0.05, -0.10, 0.20))));
+ initialEstimate.insert(Symbol('x', i), poses[i].compose(Pose3(Rot3::Rodrigues(-0.1, 0.2, 0.25), Point3(0.05, -0.10, 0.20))));
for (size_t j = 0; j < points.size(); ++j)
initialEstimate.insert(Symbol('l', j), points[j].compose(Point3(-0.25, 0.20, 0.15)));
initialEstimate.print("Initial Estimates:\n");
diff --git a/examples/SFMExampleExpressions.cpp b/examples/SFMExampleExpressions.cpp
index e9c9e920d..df5488ec3 100644
--- a/examples/SFMExampleExpressions.cpp
+++ b/examples/SFMExampleExpressions.cpp
@@ -84,7 +84,7 @@ int main(int argc, char* argv[]) {
// Create perturbed initial
Values initial;
- Pose3 delta(Rot3::rodriguez(-0.1, 0.2, 0.25), Point3(0.05, -0.10, 0.20));
+ Pose3 delta(Rot3::Rodrigues(-0.1, 0.2, 0.25), Point3(0.05, -0.10, 0.20));
for (size_t i = 0; i < poses.size(); ++i)
initial.insert(Symbol('x', i), poses[i].compose(delta));
for (size_t j = 0; j < points.size(); ++j)
diff --git a/examples/SFMExample_SmartFactor.cpp b/examples/SFMExample_SmartFactor.cpp
index fce046a59..e7c0aa696 100644
--- a/examples/SFMExample_SmartFactor.cpp
+++ b/examples/SFMExample_SmartFactor.cpp
@@ -34,6 +34,9 @@ using namespace gtsam;
// Make the typename short so it looks much cleaner
typedef SmartProjectionPoseFactor SmartFactor;
+// create a typedef to the camera type
+typedef PinholePose Camera;
+
/* ************************************************************************* */
int main(int argc, char* argv[]) {
@@ -55,12 +58,12 @@ int main(int argc, char* argv[]) {
for (size_t j = 0; j < points.size(); ++j) {
// every landmark represent a single landmark, we use shared pointer to init the factor, and then insert measurements.
- SmartFactor::shared_ptr smartfactor(new SmartFactor());
+ SmartFactor::shared_ptr smartfactor(new SmartFactor(measurementNoise, K));
for (size_t i = 0; i < poses.size(); ++i) {
// generate the 2D measurement
- SimpleCamera camera(poses[i], *K);
+ Camera camera(poses[i], K);
Point2 measurement = camera.project(points[j]);
// call add() function to add measurement into a single factor, here we need to add:
@@ -68,7 +71,7 @@ int main(int argc, char* argv[]) {
// 2. the corresponding camera's key
// 3. camera noise model
// 4. camera calibration
- smartfactor->add(measurement, i, measurementNoise, K);
+ smartfactor->add(measurement, i);
}
// insert the smart factor in the graph
@@ -77,24 +80,24 @@ int main(int argc, char* argv[]) {
// Add a prior on pose x0. This indirectly specifies where the origin is.
// 30cm std on x,y,z 0.1 rad on roll,pitch,yaw
- noiseModel::Diagonal::shared_ptr poseNoise = noiseModel::Diagonal::Sigmas(
+ noiseModel::Diagonal::shared_ptr noise = noiseModel::Diagonal::Sigmas(
(Vector(6) << Vector3::Constant(0.3), Vector3::Constant(0.1)).finished());
- graph.push_back(PriorFactor(0, poses[0], poseNoise));
+ graph.push_back(PriorFactor(0, Camera(poses[0],K), noise));
// Because the structure-from-motion problem has a scale ambiguity, the problem is
// still under-constrained. Here we add a prior on the second pose x1, so this will
// fix the scale by indicating the distance between x0 and x1.
// Because these two are fixed, the rest of the poses will be also be fixed.
- graph.push_back(PriorFactor(1, poses[1], poseNoise)); // add directly to graph
+ graph.push_back(PriorFactor(1, Camera(poses[1],K), noise)); // add directly to graph
graph.print("Factor Graph:\n");
// Create the initial estimate to the solution
// Intentionally initialize the variables off from the ground truth
Values initialEstimate;
- Pose3 delta(Rot3::rodriguez(-0.1, 0.2, 0.25), Point3(0.05, -0.10, 0.20));
+ Pose3 delta(Rot3::Rodrigues(-0.1, 0.2, 0.25), Point3(0.05, -0.10, 0.20));
for (size_t i = 0; i < poses.size(); ++i)
- initialEstimate.insert(i, poses[i].compose(delta));
+ initialEstimate.insert(i, Camera(poses[i].compose(delta), K));
initialEstimate.print("Initial Estimates:\n");
// Optimize the graph and print results
diff --git a/examples/SFMExample_SmartFactorPCG.cpp b/examples/SFMExample_SmartFactorPCG.cpp
index 49482292f..743934c7c 100644
--- a/examples/SFMExample_SmartFactorPCG.cpp
+++ b/examples/SFMExample_SmartFactorPCG.cpp
@@ -30,6 +30,9 @@ using namespace gtsam;
// Make the typename short so it looks much cleaner
typedef SmartProjectionPoseFactor SmartFactor;
+// create a typedef to the camera type
+typedef PinholePose Camera;
+
/* ************************************************************************* */
int main(int argc, char* argv[]) {
@@ -51,16 +54,16 @@ int main(int argc, char* argv[]) {
for (size_t j = 0; j < points.size(); ++j) {
// every landmark represent a single landmark, we use shared pointer to init the factor, and then insert measurements.
- SmartFactor::shared_ptr smartfactor(new SmartFactor());
+ SmartFactor::shared_ptr smartfactor(new SmartFactor(measurementNoise, K));
for (size_t i = 0; i < poses.size(); ++i) {
// generate the 2D measurement
- SimpleCamera camera(poses[i], *K);
+ Camera camera(poses[i], K);
Point2 measurement = camera.project(points[j]);
// call add() function to add measurement into a single factor, here we need to add:
- smartfactor->add(measurement, i, measurementNoise, K);
+ smartfactor->add(measurement, i);
}
// insert the smart factor in the graph
@@ -69,18 +72,18 @@ int main(int argc, char* argv[]) {
// Add a prior on pose x0. This indirectly specifies where the origin is.
// 30cm std on x,y,z 0.1 rad on roll,pitch,yaw
- noiseModel::Diagonal::shared_ptr poseNoise = noiseModel::Diagonal::Sigmas(
+ noiseModel::Diagonal::shared_ptr noise = noiseModel::Diagonal::Sigmas(
(Vector(6) << Vector3::Constant(0.3), Vector3::Constant(0.1)).finished());
- graph.push_back(PriorFactor(0, poses[0], poseNoise));
+ graph.push_back(PriorFactor(0, Camera(poses[0],K), noise));
// Fix the scale ambiguity by adding a prior
- graph.push_back(PriorFactor(1, poses[1], poseNoise));
+ graph.push_back(PriorFactor(1, Camera(poses[0],K), noise));
// Create the initial estimate to the solution
Values initialEstimate;
- Pose3 delta(Rot3::rodriguez(-0.1, 0.2, 0.25), Point3(0.05, -0.10, 0.20));
+ Pose3 delta(Rot3::Rodrigues(-0.1, 0.2, 0.25), Point3(0.05, -0.10, 0.20));
for (size_t i = 0; i < poses.size(); ++i)
- initialEstimate.insert(i, poses[i].compose(delta));
+ initialEstimate.insert(i, Camera(poses[i].compose(delta),K));
// We will use LM in the outer optimization loop, but by specifying "Iterative" below
// We indicate that an iterative linear solver should be used.
diff --git a/examples/SFMExample_bal_COLAMD_METIS.cpp b/examples/SFMExample_bal_COLAMD_METIS.cpp
new file mode 100644
index 000000000..4bbaac3ef
--- /dev/null
+++ b/examples/SFMExample_bal_COLAMD_METIS.cpp
@@ -0,0 +1,144 @@
+/* ----------------------------------------------------------------------------
+
+ * GTSAM Copyright 2010, Georgia Tech Research Corporation,
+ * Atlanta, Georgia 30332-0415
+ * All Rights Reserved
+ * Authors: Frank Dellaert, et al. (see THANKS for the full author list)
+
+ * See LICENSE for the license information
+
+ * -------------------------------------------------------------------------- */
+
+/**
+ * @file SFMExample.cpp
+ * @brief This file is to compare the ordering performance for COLAMD vs METIS.
+ * Example problem is to solve a structure-from-motion problem from a "Bundle Adjustment in the Large" file.
+ * @author Frank Dellaert, Zhaoyang Lv
+ */
+
+// For an explanation of headers, see SFMExample.cpp
+#include
+#include
+#include
+#include
+#include
+#include
+#include // for loading BAL datasets !
+
+#include
+
+#include
+
+using namespace std;
+using namespace gtsam;
+using symbol_shorthand::C;
+using symbol_shorthand::P;
+
+// We will be using a projection factor that ties a SFM_Camera to a 3D point.
+// An SFM_Camera is defined in datase.h as a camera with unknown Cal3Bundler calibration
+// and has a total of 9 free parameters
+typedef GeneralSFMFactor MyFactor;
+
+/* ************************************************************************* */
+int main (int argc, char* argv[]) {
+
+ // Find default file, but if an argument is given, try loading a file
+ string filename = findExampleDataFile("dubrovnik-3-7-pre");
+ if (argc>1) filename = string(argv[1]);
+
+ // Load the SfM data from file
+ SfM_data mydata;
+ readBAL(filename, mydata);
+ cout << boost::format("read %1% tracks on %2% cameras\n") % mydata.number_tracks() % mydata.number_cameras();
+
+ // Create a factor graph
+ NonlinearFactorGraph graph;
+
+ // We share *one* noiseModel between all projection factors
+ noiseModel::Isotropic::shared_ptr noise =
+ noiseModel::Isotropic::Sigma(2, 1.0); // one pixel in u and v
+
+ // Add measurements to the factor graph
+ size_t j = 0;
+ BOOST_FOREACH(const SfM_Track& track, mydata.tracks) {
+ BOOST_FOREACH(const SfM_Measurement& m, track.measurements) {
+ size_t i = m.first;
+ Point2 uv = m.second;
+ graph.push_back(MyFactor(uv, noise, C(i), P(j))); // note use of shorthand symbols C and P
+ }
+ j += 1;
+ }
+
+ // Add a prior on pose x1. This indirectly specifies where the origin is.
+ // and a prior on the position of the first landmark to fix the scale
+ graph.push_back(PriorFactor(C(0), mydata.cameras[0], noiseModel::Isotropic::Sigma(9, 0.1)));
+ graph.push_back(PriorFactor (P(0), mydata.tracks[0].p, noiseModel::Isotropic::Sigma(3, 0.1)));
+
+ // Create initial estimate
+ Values initial;
+ size_t i = 0; j = 0;
+ BOOST_FOREACH(const SfM_Camera& camera, mydata.cameras) initial.insert(C(i++), camera);
+ BOOST_FOREACH(const SfM_Track& track, mydata.tracks) initial.insert(P(j++), track.p);
+
+ /** --------------- COMPARISON -----------------------**/
+ /** ----------------------------------------------------**/
+
+ LevenbergMarquardtParams params_using_COLAMD, params_using_METIS;
+ try {
+ params_using_METIS.setVerbosity("ERROR");
+ gttic_(METIS_ORDERING);
+ params_using_METIS.ordering = Ordering::Create(Ordering::METIS, graph);
+ gttoc_(METIS_ORDERING);
+
+ params_using_COLAMD.setVerbosity("ERROR");
+ gttic_(COLAMD_ORDERING);
+ params_using_COLAMD.ordering = Ordering::Create(Ordering::COLAMD, graph);
+ gttoc_(COLAMD_ORDERING);
+ } catch (exception& e) {
+ cout << e.what();
+ }
+
+ // expect they have different ordering results
+ if(params_using_COLAMD.ordering == params_using_METIS.ordering) {
+ cout << "COLAMD and METIS produce the same ordering. "
+ << "Problem here!!!" << endl;
+ }
+
+ /* Optimize the graph with METIS and COLAMD and time the results */
+
+ Values result_METIS, result_COLAMD;
+ try {
+ gttic_(OPTIMIZE_WITH_METIS);
+ LevenbergMarquardtOptimizer lm_METIS(graph, initial, params_using_METIS);
+ result_METIS = lm_METIS.optimize();
+ gttoc_(OPTIMIZE_WITH_METIS);
+
+ gttic_(OPTIMIZE_WITH_COLAMD);
+ LevenbergMarquardtOptimizer lm_COLAMD(graph, initial, params_using_COLAMD);
+ result_COLAMD = lm_COLAMD.optimize();
+ gttoc_(OPTIMIZE_WITH_COLAMD);
+ } catch (exception& e) {
+ cout << e.what();
+ }
+
+
+ { // printing the result
+
+ cout << "COLAMD final error: " << graph.error(result_COLAMD) << endl;
+ cout << "METIS final error: " << graph.error(result_METIS) << endl;
+
+ cout << endl << endl;
+
+ cout << "Time comparison by solving " << filename << " results:" << endl;
+ cout << boost::format("%1% point tracks and %2% cameras\n") \
+ % mydata.number_tracks() % mydata.number_cameras() \
+ << endl;
+
+ tictoc_print_();
+ }
+
+
+ return 0;
+}
+/* ************************************************************************* */
+
diff --git a/examples/SelfCalibrationExample.cpp b/examples/SelfCalibrationExample.cpp
index 8ebf005ab..f5702e7fb 100644
--- a/examples/SelfCalibrationExample.cpp
+++ b/examples/SelfCalibrationExample.cpp
@@ -82,7 +82,7 @@ int main(int argc, char* argv[]) {
Values initialEstimate;
initialEstimate.insert(Symbol('K', 0), Cal3_S2(60.0, 60.0, 0.0, 45.0, 45.0));
for (size_t i = 0; i < poses.size(); ++i)
- initialEstimate.insert(Symbol('x', i), poses[i].compose(Pose3(Rot3::rodriguez(-0.1, 0.2, 0.25), Point3(0.05, -0.10, 0.20))));
+ initialEstimate.insert(Symbol('x', i), poses[i].compose(Pose3(Rot3::Rodrigues(-0.1, 0.2, 0.25), Point3(0.05, -0.10, 0.20))));
for (size_t j = 0; j < points.size(); ++j)
initialEstimate.insert(Symbol('l', j), points[j].compose(Point3(-0.25, 0.20, 0.15)));
diff --git a/examples/SolverComparer.cpp b/examples/SolverComparer.cpp
index 0393affe1..2000b348b 100644
--- a/examples/SolverComparer.cpp
+++ b/examples/SolverComparer.cpp
@@ -32,7 +32,7 @@
*/
#include
-#include
+#include
#include
#include
#include
@@ -44,6 +44,7 @@
#include
#include
#include
+#include // for GTSAM_USE_TBB
#include
#include
@@ -575,7 +576,7 @@ void runStats()
{
cout << "Gathering statistics..." << endl;
GaussianFactorGraph linear = *datasetMeasurements.linearize(initial);
- GaussianJunctionTree jt(GaussianEliminationTree(linear, Ordering::colamd(linear)));
+ GaussianJunctionTree jt(GaussianEliminationTree(linear, Ordering::Colamd(linear)));
treeTraversal::ForestStatistics statistics = treeTraversal::GatherStatistics(jt);
ofstream file;
diff --git a/examples/TimeTBB.cpp b/examples/TimeTBB.cpp
index a35980836..602a00593 100644
--- a/examples/TimeTBB.cpp
+++ b/examples/TimeTBB.cpp
@@ -17,6 +17,7 @@
#include
#include
+
#include
#include
#include