diff --git a/.cproject b/.cproject
index 7c8190e6a..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,175 +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
-j2
all
@@ -1043,7 +572,7 @@
true
true
-
+
make
-j2
clean
@@ -1051,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
@@ -1219,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
@@ -1360,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
@@ -1384,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
@@ -1967,7 +1992,15 @@
false
true
-
+
+ make
+ -j4
+ check.sam
+ true
+ true
+ true
+
+
make
-j2
check
@@ -1975,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
@@ -2030,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
@@ -2534,7 +2255,7 @@
true
true
-
+
make
-j2
clean
@@ -2542,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
@@ -2590,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
@@ -2814,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
@@ -2950,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
@@ -3134,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
@@ -3190,6 +2607,14 @@
true
true
+
+ make
+ -j4
+ testGroup.run
+ true
+ true
+ true
+
make
-j5
@@ -3414,31 +2839,487 @@
true
true
-
+
make
- -j2
- vSFMexample.run
+ -j4
+ testLie.run
true
true
true
-
+
+ make
+ -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
@@ -3446,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/CMakeLists.txt b/CMakeLists.txt
index 6e9aa0009..fd11a6733 100644
--- a/CMakeLists.txt
+++ b/CMakeLists.txt
@@ -158,6 +158,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 +179,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)
diff --git a/cmake/GtsamMatlabWrap.cmake b/cmake/GtsamMatlabWrap.cmake
index 2da2d02c2..d1d3d93dd 100644
--- a/cmake/GtsamMatlabWrap.cmake
+++ b/cmake/GtsamMatlabWrap.cmake
@@ -367,6 +367,11 @@ endfunction()
# should be installed to all build type toolboxes
function(install_matlab_scripts source_directory patterns)
set(patterns_args "")
+ set(exclude_patterns "")
+ if(NOT GTSAM_WRAP_SERIALIZATION)
+ set(exclude_patterns "testSerialization.m")
+ endif()
+
foreach(pattern ${patterns})
list(APPEND patterns_args PATTERN "${pattern}")
endforeach()
@@ -381,10 +386,10 @@ function(install_matlab_scripts source_directory patterns)
# Split up filename to strip trailing '/' in GTSAM_TOOLBOX_INSTALL_PATH if there is one
get_filename_component(location "${GTSAM_TOOLBOX_INSTALL_PATH}" PATH)
get_filename_component(name "${GTSAM_TOOLBOX_INSTALL_PATH}" NAME)
- install(DIRECTORY "${source_directory}" DESTINATION "${location}/${name}${build_type_tag}" CONFIGURATIONS "${build_type}" FILES_MATCHING ${patterns_args} PATTERN ".svn" EXCLUDE)
+ install(DIRECTORY "${source_directory}" DESTINATION "${location}/${name}${build_type_tag}" CONFIGURATIONS "${build_type}" FILES_MATCHING ${patterns_args} PATTERN "${exclude_patterns}" EXCLUDE)
endforeach()
else()
- install(DIRECTORY "${source_directory}" DESTINATION "${GTSAM_TOOLBOX_INSTALL_PATH}" FILES_MATCHING ${patterns_args} PATTERN ".svn" EXCLUDE)
+ install(DIRECTORY "${source_directory}" DESTINATION "${GTSAM_TOOLBOX_INSTALL_PATH}" FILES_MATCHING ${patterns_args} PATTERN "${exclude_patterns}" EXCLUDE)
endif()
endfunction()
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/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..bb8935439 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(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, measurementNoise);
}
// 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..7ec5f8268 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(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, measurementNoise);
}
// 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