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 diff --git a/examples/VisualISAM2Example.cpp b/examples/VisualISAM2Example.cpp index a5b91ff38..75c0a2fa5 100644 --- a/examples/VisualISAM2Example.cpp +++ b/examples/VisualISAM2Example.cpp @@ -95,7 +95,7 @@ int main(int argc, char* argv[]) { // Add an initial guess for the current pose // Intentionally initialize the variables off from the ground truth - 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)))); // If this is the first iteration, add a prior on the first pose to set the coordinate frame // and a prior on the first landmark to set the scale diff --git a/examples/VisualISAMExample.cpp b/examples/VisualISAMExample.cpp index 8abe84eb6..9380410ea 100644 --- a/examples/VisualISAMExample.cpp +++ b/examples/VisualISAMExample.cpp @@ -95,7 +95,7 @@ int main(int argc, char* argv[]) { } // Intentionally initialize the variables off from the ground truth - Pose3 noise(Rot3::rodriguez(-0.1, 0.2, 0.25), Point3(0.05, -0.10, 0.20)); + Pose3 noise(Rot3::Rodrigues(-0.1, 0.2, 0.25), Point3(0.05, -0.10, 0.20)); Pose3 initial_xi = poses[i].compose(noise); // Add an initial guess for the current pose diff --git a/gtsam.h b/gtsam.h index 70f3b566f..16f247a34 100644 --- a/gtsam.h +++ b/gtsam.h @@ -1,4 +1,5 @@ /** + * GTSAM Wrap Module Definition * * These are the current classes available through the matlab toolbox interface, @@ -156,7 +157,7 @@ virtual class Value { size_t dim() const; }; -#include +#include class LieScalar { // Standard constructors LieScalar(); @@ -185,7 +186,7 @@ class LieScalar { static Vector Logmap(const gtsam::LieScalar& p); }; -#include +#include class LieVector { // Standard constructors LieVector(); @@ -217,7 +218,7 @@ class LieVector { void serialize() const; }; -#include +#include class LieMatrix { // Standard constructors LieMatrix(); @@ -433,12 +434,12 @@ class Rot3 { static gtsam::Rot3 Rz(double t); static gtsam::Rot3 RzRyRx(double x, double y, double z); static gtsam::Rot3 RzRyRx(Vector xyz); - static gtsam::Rot3 yaw(double t); // positive yaw is to right (as in aircraft heading) - static gtsam::Rot3 pitch(double t); // positive pitch is up (increasing aircraft altitude) - static gtsam::Rot3 roll(double t); // positive roll is to right (increasing yaw in aircraft) - static gtsam::Rot3 ypr(double y, double p, double r); - static gtsam::Rot3 quaternion(double w, double x, double y, double z); - static gtsam::Rot3 rodriguez(Vector v); + static gtsam::Rot3 Yaw(double t); // positive yaw is to right (as in aircraft heading) + static gtsam::Rot3 Pitch(double t); // positive pitch is up (increasing aircraft altitude) + static gtsam::Rot3 Roll(double t); // positive roll is to right (increasing yaw in aircraft) + static gtsam::Rot3 Ypr(double y, double p, double r); + static gtsam::Rot3 Quaternion(double w, double x, double y, double z); + static gtsam::Rot3 Rodrigues(Vector v); // Testable void print(string s) const; @@ -812,7 +813,7 @@ class CalibratedCamera { // Action on Point3 gtsam::Point2 project(const gtsam::Point3& point) const; - static gtsam::Point2 project_to_camera(const gtsam::Point3& cameraPoint); + static gtsam::Point2 Project(const gtsam::Point3& cameraPoint); // Standard Interface gtsam::Pose3 pose() const; @@ -848,7 +849,7 @@ class PinholeCamera { static size_t Dim(); // Transformations and measurement functions - static gtsam::Point2 project_to_camera(const gtsam::Point3& cameraPoint); + static gtsam::Point2 Project(const gtsam::Point3& cameraPoint); pair projectSafe(const gtsam::Point3& pw) const; gtsam::Point2 project(const gtsam::Point3& point); gtsam::Point3 backproject(const gtsam::Point2& p, double depth) const; @@ -884,7 +885,7 @@ virtual class SimpleCamera { static size_t Dim(); // Transformations and measurement functions - static gtsam::Point2 project_to_camera(const gtsam::Point3& cameraPoint); + static gtsam::Point2 Project(const gtsam::Point3& cameraPoint); pair projectSafe(const gtsam::Point3& pw) const; gtsam::Point2 project(const gtsam::Point3& point); gtsam::Point3 backproject(const gtsam::Point2& p, double depth) const; @@ -915,7 +916,7 @@ class StereoCamera { // Standard Interface gtsam::Pose3 pose() const; double baseline() const; - gtsam::Cal3_S2Stereo* calibration() const; + gtsam::Cal3_S2Stereo calibration() const; // Manifold gtsam::StereoCamera retract(const Vector& d) const; @@ -1654,12 +1655,12 @@ char symbolChr(size_t key); size_t symbolIndex(size_t key); // Default keyformatter -void printKeyList (const gtsam::KeyList& keys); -void printKeyList (const gtsam::KeyList& keys, string s); -void printKeyVector(const gtsam::KeyVector& keys); -void printKeyVector(const gtsam::KeyVector& keys, string s); -void printKeySet (const gtsam::KeySet& keys); -void printKeySet (const gtsam::KeySet& keys, string s); +void PrintKeyList (const gtsam::KeyList& keys); +void PrintKeyList (const gtsam::KeyList& keys, string s); +void PrintKeyVector(const gtsam::KeyVector& keys); +void PrintKeyVector(const gtsam::KeyVector& keys, string s); +void PrintKeySet (const gtsam::KeySet& keys); +void PrintKeySet (const gtsam::KeySet& keys, string s); #include class LabeledSymbol { @@ -1776,7 +1777,7 @@ class Values { void swap(gtsam::Values& values); bool exists(size_t j) const; - gtsam::KeyList keys() const; + gtsam::KeyVector keys() const; gtsam::VectorValues zeroVectors() const; @@ -1893,8 +1894,6 @@ class KeySet { class KeyVector { KeyVector(); KeyVector(const gtsam::KeyVector& other); - KeyVector(const gtsam::KeySet& other); - KeyVector(const gtsam::KeyList& other); // Note: no print function @@ -2264,7 +2263,7 @@ virtual class NonlinearEquality : gtsam::NoiseModelFactor { }; -#include +#include template virtual class RangeFactor : gtsam::NoiseModelFactor { RangeFactor(size_t key1, size_t key2, double measured, const gtsam::noiseModel::Base* noiseModel); @@ -2274,20 +2273,16 @@ typedef gtsam::RangeFactor RangeFactorPosePoint2; typedef gtsam::RangeFactor RangeFactorPosePoint3; typedef gtsam::RangeFactor RangeFactorPose2; typedef gtsam::RangeFactor RangeFactorPose3; - -// Commented out by Frank Dec 2014: not poses! -// If needed, we need a RangeFactor that takes a camera, extracts the pose -// Should be easy with Expressions -//typedef gtsam::RangeFactor RangeFactorCalibratedCameraPoint; -//typedef gtsam::RangeFactor RangeFactorSimpleCameraPoint; -//typedef gtsam::RangeFactor RangeFactorCalibratedCamera; -//typedef gtsam::RangeFactor RangeFactorSimpleCamera; +typedef gtsam::RangeFactor RangeFactorCalibratedCameraPoint; +typedef gtsam::RangeFactor RangeFactorSimpleCameraPoint; +typedef gtsam::RangeFactor RangeFactorCalibratedCamera; +typedef gtsam::RangeFactor RangeFactorSimpleCamera; -#include -template +#include +template virtual class BearingFactor : gtsam::NoiseModelFactor { - BearingFactor(size_t key1, size_t key2, const ROTATION& measured, const gtsam::noiseModel::Base* noiseModel); + BearingFactor(size_t key1, size_t key2, const BEARING& measured, const gtsam::noiseModel::Base* noiseModel); // enabling serialization functionality void serialize() const; @@ -2295,19 +2290,18 @@ virtual class BearingFactor : gtsam::NoiseModelFactor { typedef gtsam::BearingFactor BearingFactor2D; - -#include -template +#include +template virtual class BearingRangeFactor : gtsam::NoiseModelFactor { - BearingRangeFactor(size_t poseKey, size_t pointKey, const ROTATION& measuredBearing, double measuredRange, const gtsam::noiseModel::Base* noiseModel); - - pair measured() const; + BearingRangeFactor(size_t poseKey, size_t pointKey, + const BEARING& measuredBearing, const RANGE& measuredRange, + const gtsam::noiseModel::Base* noiseModel); // enabling serialization functionality void serialize() const; }; -typedef gtsam::BearingRangeFactor BearingRangeFactor2D; +typedef gtsam::BearingRangeFactor BearingRangeFactor2D; #include @@ -2354,18 +2348,33 @@ virtual class GeneralSFMFactor2 : gtsam::NoiseModelFactor { void serialize() const; }; +#include +class SmartProjectionParams { + SmartProjectionParams(); + // TODO(frank): make these work: + // void setLinearizationMode(LinearizationMode linMode); + // void setDegeneracyMode(DegeneracyMode degMode); + void setRankTolerance(double rankTol); + void setEnableEPI(bool enableEPI); + void setLandmarkDistanceThreshold(bool landmarkDistanceThreshold); + void setDynamicOutlierRejectionThreshold(bool dynOutRejectionThreshold); +}; + #include template -virtual class SmartProjectionPoseFactor : gtsam::NonlinearFactor { +virtual class SmartProjectionPoseFactor: gtsam::NonlinearFactor { - SmartProjectionPoseFactor(double rankTol, double linThreshold, - bool manageDegeneracy, bool enableEPI, const gtsam::Pose3& body_P_sensor); + SmartProjectionPoseFactor(const gtsam::noiseModel::Base* noise, + const CALIBRATION* K); + SmartProjectionPoseFactor(const gtsam::noiseModel::Base* noise, + const CALIBRATION* K, + const gtsam::Pose3& body_P_sensor); + SmartProjectionPoseFactor(const gtsam::noiseModel::Base* noise, + const CALIBRATION* K, + const gtsam::Pose3& body_P_sensor, + const gtsam::SmartProjectionParams& params); - SmartProjectionPoseFactor(double rankTol); - SmartProjectionPoseFactor(); - - void add(const gtsam::Point2& measured_i, size_t poseKey_i, - const gtsam::noiseModel::Base* noise_i, const CALIBRATION* K_i); + void add(const gtsam::Point2& measured_i, size_t poseKey_i); // enabling serialization functionality //void serialize() const; @@ -2438,7 +2447,7 @@ namespace imuBias { #include class ConstantBias { - // Standard Constructor + // Constructors ConstantBias(); ConstantBias(Vector biasAcc, Vector biasGyro); @@ -2470,136 +2479,143 @@ class ConstantBias { }///\namespace imuBias -#include -class PoseVelocityBias{ - PoseVelocityBias(const gtsam::Pose3& pose, Vector velocity, const gtsam::imuBias::ConstantBias& bias); - }; -class ImuFactorPreintegratedMeasurements { - // Standard Constructor - ImuFactorPreintegratedMeasurements(const gtsam::imuBias::ConstantBias& bias, Matrix measuredAccCovariance,Matrix measuredOmegaCovariance, Matrix integrationErrorCovariance, bool use2ndOrderIntegration); - ImuFactorPreintegratedMeasurements(const gtsam::imuBias::ConstantBias& bias, Matrix measuredAccCovariance,Matrix measuredOmegaCovariance, Matrix integrationErrorCovariance); - // ImuFactorPreintegratedMeasurements(const gtsam::ImuFactorPreintegratedMeasurements& rhs); +#include +class NavState { + // Constructors + NavState(); + NavState(const gtsam::Rot3& R, const gtsam::Point3& t, Vector v); + NavState(const gtsam::Pose3& pose, Vector v); // Testable void print(string s) const; - bool equals(const gtsam::ImuFactorPreintegratedMeasurements& expected, double tol); + bool equals(const gtsam::NavState& expected, double tol) const; + + // Access + gtsam::Rot3 attitude() const; + gtsam::Point3 position() const; + Vector velocity() const; + gtsam::Pose3 pose() const; +}; + +#include +class PreintegrationParams { + PreintegrationParams(Vector n_gravity); + // TODO(frank): add setters/getters or make this MATLAB wrapper feature +}; + +#include +virtual class PreintegrationBase { + // Constructors + PreintegrationBase(const gtsam::PreintegrationParams* params); + PreintegrationBase(const gtsam::PreintegrationParams* params, + const gtsam::imuBias::ConstantBias& bias); + + // Testable + void print(string s) const; + bool equals(const gtsam::PreintegrationBase& expected, double tol); double deltaTij() const; - Matrix deltaRij() const; + gtsam::Rot3 deltaRij() const; Vector deltaPij() const; Vector deltaVij() const; Vector biasHatVector() const; - Matrix delPdelBiasAcc() const; - Matrix delPdelBiasOmega() const; - Matrix delVdelBiasAcc() const; - Matrix delVdelBiasOmega() const; - Matrix delRdelBiasOmega() const; - Matrix preintMeasCov() const; // Standard Interface - void integrateMeasurement(Vector measuredAcc, Vector measuredOmega, double deltaT); - void integrateMeasurement(Vector measuredAcc, Vector measuredOmega, double deltaT, const gtsam::Pose3& body_P_sensor); - gtsam::PoseVelocityBias predict(const gtsam::Pose3& pose_i, Vector vel_i, const gtsam::imuBias::ConstantBias& bias, - Vector gravity, Vector omegaCoriolis) const; + gtsam::NavState predict(const gtsam::NavState& state_i, + const gtsam::imuBias::ConstantBias& bias) const; }; -virtual class ImuFactor : gtsam::NonlinearFactor { - ImuFactor(size_t pose_i, size_t vel_i, size_t pose_j, size_t vel_j, size_t bias, - const gtsam::ImuFactorPreintegratedMeasurements& preintegratedMeasurements, Vector gravity, Vector omegaCoriolis); - ImuFactor(size_t pose_i, size_t vel_i, size_t pose_j, size_t vel_j, size_t bias, - const gtsam::ImuFactorPreintegratedMeasurements& preintegratedMeasurements, Vector gravity, Vector omegaCoriolis, - const gtsam::Pose3& body_P_sensor); +#include +virtual class PreintegratedImuMeasurements: gtsam::PreintegrationBase { + // Constructors + PreintegratedImuMeasurements(const gtsam::PreintegrationParams* params); + PreintegratedImuMeasurements(const gtsam::PreintegrationParams* params, + const gtsam::imuBias::ConstantBias& bias); + + // Testable + void print(string s) const; + bool equals(const gtsam::PreintegratedImuMeasurements& expected, double tol); + // Standard Interface - gtsam::ImuFactorPreintegratedMeasurements preintegratedMeasurements() const; + void integrateMeasurement(Vector measuredAcc, Vector measuredOmega, + double deltaT); + void resetIntegration(); + Matrix preintMeasCov() const; +}; + +virtual class ImuFactor: gtsam::NonlinearFactor { + ImuFactor(size_t pose_i, size_t vel_i, size_t pose_j, size_t vel_j, + size_t bias, + const gtsam::PreintegratedImuMeasurements& preintegratedMeasurements); + + // Standard Interface + gtsam::PreintegratedImuMeasurements preintegratedMeasurements() const; + Vector evaluateError(const gtsam::Pose3& pose_i, Vector vel_i, + const gtsam::Pose3& pose_j, Vector vel_j, + const gtsam::imuBias::ConstantBias& bias); }; #include -class CombinedImuFactorPreintegratedMeasurements { - // Standard Constructor - CombinedImuFactorPreintegratedMeasurements( - const gtsam::imuBias::ConstantBias& bias, - Matrix measuredAccCovariance, - Matrix measuredOmegaCovariance, - Matrix integrationErrorCovariance, - Matrix biasAccCovariance, - Matrix biasOmegaCovariance, - Matrix biasAccOmegaInit); - CombinedImuFactorPreintegratedMeasurements( - const gtsam::imuBias::ConstantBias& bias, - Matrix measuredAccCovariance, - Matrix measuredOmegaCovariance, - Matrix integrationErrorCovariance, - Matrix biasAccCovariance, - Matrix biasOmegaCovariance, - Matrix biasAccOmegaInit, - bool use2ndOrderIntegration); - // CombinedImuFactorPreintegratedMeasurements(const gtsam::CombinedImuFactorPreintegratedMeasurements& rhs); - +virtual class PreintegratedCombinedMeasurements: gtsam::PreintegrationBase { // Testable void print(string s) const; - bool equals(const gtsam::CombinedImuFactorPreintegratedMeasurements& expected, double tol); - - double deltaTij() const; - Matrix deltaRij() const; - Vector deltaPij() const; - Vector deltaVij() const; - Vector biasHatVector() const; - Matrix delPdelBiasAcc() const; - Matrix delPdelBiasOmega() const; - Matrix delVdelBiasAcc() const; - Matrix delVdelBiasOmega() const; - Matrix delRdelBiasOmega() const; - Matrix preintMeasCov() const; + bool equals(const gtsam::PreintegratedCombinedMeasurements& expected, + double tol); // Standard Interface - void integrateMeasurement(Vector measuredAcc, Vector measuredOmega, double deltaT); - void integrateMeasurement(Vector measuredAcc, Vector measuredOmega, double deltaT, const gtsam::Pose3& body_P_sensor); - gtsam::PoseVelocityBias predict(const gtsam::Pose3& pose_i, Vector vel_i, const gtsam::imuBias::ConstantBias& bias, - Vector gravity, Vector omegaCoriolis) const; + void integrateMeasurement(Vector measuredAcc, Vector measuredOmega, + double deltaT); + void resetIntegration(); + Matrix preintMeasCov() const; }; -virtual class CombinedImuFactor : gtsam::NonlinearFactor { - CombinedImuFactor(size_t pose_i, size_t vel_i, size_t pose_j, size_t vel_j, size_t bias_i, size_t bias_j, - const gtsam::CombinedImuFactorPreintegratedMeasurements& CombinedPreintegratedMeasurements, Vector gravity, Vector omegaCoriolis); +virtual class CombinedImuFactor: gtsam::NonlinearFactor { + CombinedImuFactor(size_t pose_i, size_t vel_i, size_t pose_j, size_t vel_j, + size_t bias_i, size_t bias_j, + const gtsam::PreintegratedCombinedMeasurements& CombinedPreintegratedMeasurements); + // Standard Interface - gtsam::CombinedImuFactorPreintegratedMeasurements preintegratedMeasurements() const; + gtsam::PreintegratedCombinedMeasurements preintegratedMeasurements() const; + Vector evaluateError(const gtsam::Pose3& pose_i, Vector vel_i, + const gtsam::Pose3& pose_j, Vector vel_j, + const gtsam::imuBias::ConstantBias& bias_i, + const gtsam::imuBias::ConstantBias& bias_j); }; #include -class AHRSFactorPreintegratedMeasurements { +class PreintegratedAhrsMeasurements { // Standard Constructor - AHRSFactorPreintegratedMeasurements(Vector bias, Matrix measuredOmegaCovariance); - AHRSFactorPreintegratedMeasurements(Vector bias, Matrix measuredOmegaCovariance); - AHRSFactorPreintegratedMeasurements(const gtsam::AHRSFactorPreintegratedMeasurements& rhs); + PreintegratedAhrsMeasurements(Vector bias, Matrix measuredOmegaCovariance); + PreintegratedAhrsMeasurements(Vector bias, Matrix measuredOmegaCovariance); + PreintegratedAhrsMeasurements(const gtsam::PreintegratedAhrsMeasurements& rhs); // Testable void print(string s) const; - bool equals(const gtsam::AHRSFactorPreintegratedMeasurements& expected, double tol); + bool equals(const gtsam::PreintegratedAhrsMeasurements& expected, double tol); // get Data - Matrix deltaRij() const; + gtsam::Rot3 deltaRij() const; double deltaTij() const; Vector biasHat() const; // Standard Interface void integrateMeasurement(Vector measuredOmega, double deltaT); - void integrateMeasurement(Vector measuredOmega, double deltaT, const gtsam::Pose3& body_P_sensor); void resetIntegration() ; }; virtual class AHRSFactor : gtsam::NonlinearFactor { AHRSFactor(size_t rot_i, size_t rot_j,size_t bias, - const gtsam::AHRSFactorPreintegratedMeasurements& preintegratedMeasurements, Vector omegaCoriolis); + const gtsam::PreintegratedAhrsMeasurements& preintegratedMeasurements, Vector omegaCoriolis); AHRSFactor(size_t rot_i, size_t rot_j, size_t bias, - const gtsam::AHRSFactorPreintegratedMeasurements& preintegratedMeasurements, Vector omegaCoriolis, + const gtsam::PreintegratedAhrsMeasurements& preintegratedMeasurements, Vector omegaCoriolis, const gtsam::Pose3& body_P_sensor); // Standard Interface - gtsam::AHRSFactorPreintegratedMeasurements preintegratedMeasurements() const; + gtsam::PreintegratedAhrsMeasurements preintegratedMeasurements() const; Vector evaluateError(const gtsam::Rot3& rot_i, const gtsam::Rot3& rot_j, Vector bias) const; gtsam::Rot3 predict(const gtsam::Rot3& rot_i, Vector bias, - const gtsam::AHRSFactorPreintegratedMeasurements& preintegratedMeasurements, + const gtsam::PreintegratedAhrsMeasurements& preintegratedMeasurements, Vector omegaCoriolis) const; }; diff --git a/gtsam/3rdparty/Eigen/.hg_archival.txt b/gtsam/3rdparty/Eigen/.hg_archival.txt index aea5a5515..8c88afc32 100644 --- a/gtsam/3rdparty/Eigen/.hg_archival.txt +++ b/gtsam/3rdparty/Eigen/.hg_archival.txt @@ -1,4 +1,4 @@ repo: 8a21fd850624c931e448cbcfb38168cb2717c790 -node: 10219c95fe653d4962aa9db4946f6fbea96dd740 +node: b30b87236a1b1552af32ac34075ee5696a9b5a33 branch: 3.2 -tag: 3.2.4 +tag: 3.2.7 diff --git a/gtsam/3rdparty/Eigen/.hgtags b/gtsam/3rdparty/Eigen/.hgtags index 7a6e19411..c4ccd33fa 100644 --- a/gtsam/3rdparty/Eigen/.hgtags +++ b/gtsam/3rdparty/Eigen/.hgtags @@ -27,3 +27,6 @@ ffa86ffb557094721ca71dcea6aed2651b9fd610 3.2.0 6b38706d90a9fe182e66ab88477b3dbde34b9f66 3.2.1 1306d75b4a21891e59ff9bd96678882cf831e39f 3.2.2 36fd1ba04c120cfdd90f3e4cede47f43b21d19ad 3.2.3 +10219c95fe653d4962aa9db4946f6fbea96dd740 3.2.4 +bdd17ee3b1b3a166cd5ec36dcad4fc1f3faf774a 3.2.5 +c58038c56923e0fd86de3ded18e03df442e66dfb 3.2.6 diff --git a/gtsam/3rdparty/Eigen/CMakeLists.txt b/gtsam/3rdparty/Eigen/CMakeLists.txt index 76a11b9d2..ed3e67fe9 100644 --- a/gtsam/3rdparty/Eigen/CMakeLists.txt +++ b/gtsam/3rdparty/Eigen/CMakeLists.txt @@ -301,7 +301,7 @@ if(EIGEN_INCLUDE_INSTALL_DIR) ) else() set(INCLUDE_INSTALL_DIR - "${CMAKE_INSTALL_PREFIX}/include/eigen3" + "include/eigen3" CACHE INTERNAL "The directory where we install the header files (internal)" ) @@ -404,7 +404,7 @@ if(cmake_generator_tolower MATCHES "makefile") message(STATUS "make install | Install to ${CMAKE_INSTALL_PREFIX}. To change that:") message(STATUS " | cmake . -DCMAKE_INSTALL_PREFIX=yourpath") message(STATUS " | Eigen headers will then be installed to:") - message(STATUS " | ${INCLUDE_INSTALL_DIR}") + message(STATUS " | ${CMAKE_INSTALL_PREFIX}/${INCLUDE_INSTALL_DIR}") message(STATUS " | To install Eigen headers to a separate location, do:") message(STATUS " | cmake . -DEIGEN_INCLUDE_INSTALL_DIR=yourpath") message(STATUS "make doc | Generate the API documentation, requires Doxygen & LaTeX") diff --git a/gtsam/3rdparty/Eigen/Eigen/Core b/gtsam/3rdparty/Eigen/Eigen/Core index c87f99df3..509c529e1 100644 --- a/gtsam/3rdparty/Eigen/Eigen/Core +++ b/gtsam/3rdparty/Eigen/Eigen/Core @@ -123,7 +123,7 @@ #undef bool #undef vector #undef pixel - #elif defined __ARM_NEON__ + #elif defined __ARM_NEON #define EIGEN_VECTORIZE #define EIGEN_VECTORIZE_NEON #include diff --git a/gtsam/3rdparty/Eigen/Eigen/SparseCore b/gtsam/3rdparty/Eigen/Eigen/SparseCore index 9b5be5e15..24bcf0156 100644 --- a/gtsam/3rdparty/Eigen/Eigen/SparseCore +++ b/gtsam/3rdparty/Eigen/Eigen/SparseCore @@ -14,7 +14,7 @@ /** * \defgroup SparseCore_Module SparseCore module * - * This module provides a sparse matrix representation, and basic associatd matrix manipulations + * This module provides a sparse matrix representation, and basic associated matrix manipulations * and operations. * * See the \ref TutorialSparse "Sparse tutorial" diff --git a/gtsam/3rdparty/Eigen/Eigen/src/Cholesky/LDLT.h b/gtsam/3rdparty/Eigen/Eigen/src/Cholesky/LDLT.h index 02ab93880..abd30bd91 100644 --- a/gtsam/3rdparty/Eigen/Eigen/src/Cholesky/LDLT.h +++ b/gtsam/3rdparty/Eigen/Eigen/src/Cholesky/LDLT.h @@ -235,6 +235,11 @@ template class LDLT } protected: + + static void check_template_parameters() + { + EIGEN_STATIC_ASSERT_NON_INTEGER(Scalar); + } /** \internal * Used to compute and store the Cholesky decomposition A = L D L^* = U^* D U. @@ -434,6 +439,8 @@ template struct LDLT_Traits template LDLT& LDLT::compute(const MatrixType& a) { + check_template_parameters(); + eigen_assert(a.rows()==a.cols()); const Index size = a.rows(); @@ -457,7 +464,7 @@ LDLT& LDLT::compute(const MatrixType& a) */ template template -LDLT& LDLT::rankUpdate(const MatrixBase& w, const typename NumTraits::Real& sigma) +LDLT& LDLT::rankUpdate(const MatrixBase& w, const typename LDLT::RealScalar& sigma) { const Index size = w.rows(); if (m_isInitialized) diff --git a/gtsam/3rdparty/Eigen/Eigen/src/Cholesky/LLT.h b/gtsam/3rdparty/Eigen/Eigen/src/Cholesky/LLT.h index 2e6189f7d..7c11a2dc2 100644 --- a/gtsam/3rdparty/Eigen/Eigen/src/Cholesky/LLT.h +++ b/gtsam/3rdparty/Eigen/Eigen/src/Cholesky/LLT.h @@ -174,6 +174,12 @@ template class LLT LLT rankUpdate(const VectorType& vec, const RealScalar& sigma = 1); protected: + + static void check_template_parameters() + { + EIGEN_STATIC_ASSERT_NON_INTEGER(Scalar); + } + /** \internal * Used to compute and store L * The strict upper part is not used and even not initialized. @@ -283,7 +289,7 @@ template struct llt_inplace return k; mat.coeffRef(k,k) = x = sqrt(x); if (k>0 && rs>0) A21.noalias() -= A20 * A10.adjoint(); - if (rs>0) A21 *= RealScalar(1)/x; + if (rs>0) A21 /= x; } return -1; } @@ -384,6 +390,8 @@ template struct LLT_Traits template LLT& LLT::compute(const MatrixType& a) { + check_template_parameters(); + eigen_assert(a.rows()==a.cols()); const Index size = a.rows(); m_matrix.resize(size, size); diff --git a/gtsam/3rdparty/Eigen/Eigen/src/Cholesky/LLT_MKL.h b/gtsam/3rdparty/Eigen/Eigen/src/Cholesky/LLT_MKL.h index b9bcb5240..f7c365aee 100644 --- a/gtsam/3rdparty/Eigen/Eigen/src/Cholesky/LLT_MKL.h +++ b/gtsam/3rdparty/Eigen/Eigen/src/Cholesky/LLT_MKL.h @@ -60,7 +60,7 @@ template<> struct mkl_llt \ lda = m.outerStride(); \ \ info = LAPACKE_##MKLPREFIX##potrf( matrix_order, uplo, size, (MKLTYPE*)a, lda ); \ - info = (info==0) ? -1 : 1; \ + info = (info==0) ? -1 : info>0 ? info-1 : size; \ return info; \ } \ }; \ diff --git a/gtsam/3rdparty/Eigen/Eigen/src/CholmodSupport/CholmodSupport.h b/gtsam/3rdparty/Eigen/Eigen/src/CholmodSupport/CholmodSupport.h index c449960de..99dbe171c 100644 --- a/gtsam/3rdparty/Eigen/Eigen/src/CholmodSupport/CholmodSupport.h +++ b/gtsam/3rdparty/Eigen/Eigen/src/CholmodSupport/CholmodSupport.h @@ -78,7 +78,7 @@ cholmod_sparse viewAsCholmod(SparseMatrix<_Scalar,_Options,_Index>& mat) { res.itype = CHOLMOD_INT; } - else if (internal::is_same<_Index,UF_long>::value) + else if (internal::is_same<_Index,SuiteSparse_long>::value) { res.itype = CHOLMOD_LONG; } @@ -395,7 +395,7 @@ class CholmodSimplicialLLT : public CholmodBase<_MatrixType, _UpLo, CholmodSimpl CholmodSimplicialLLT(const MatrixType& matrix) : Base() { init(); - compute(matrix); + Base::compute(matrix); } ~CholmodSimplicialLLT() {} @@ -442,7 +442,7 @@ class CholmodSimplicialLDLT : public CholmodBase<_MatrixType, _UpLo, CholmodSimp CholmodSimplicialLDLT(const MatrixType& matrix) : Base() { init(); - compute(matrix); + Base::compute(matrix); } ~CholmodSimplicialLDLT() {} @@ -487,7 +487,7 @@ class CholmodSupernodalLLT : public CholmodBase<_MatrixType, _UpLo, CholmodSuper CholmodSupernodalLLT(const MatrixType& matrix) : Base() { init(); - compute(matrix); + Base::compute(matrix); } ~CholmodSupernodalLLT() {} @@ -534,7 +534,7 @@ class CholmodDecomposition : public CholmodBase<_MatrixType, _UpLo, CholmodDecom CholmodDecomposition(const MatrixType& matrix) : Base() { init(); - compute(matrix); + Base::compute(matrix); } ~CholmodDecomposition() {} diff --git a/gtsam/3rdparty/Eigen/Eigen/src/Core/Array.h b/gtsam/3rdparty/Eigen/Eigen/src/Core/Array.h index 0ab03eff0..0b9c38c82 100644 --- a/gtsam/3rdparty/Eigen/Eigen/src/Core/Array.h +++ b/gtsam/3rdparty/Eigen/Eigen/src/Core/Array.h @@ -124,6 +124,21 @@ class Array } #endif +#ifdef EIGEN_HAVE_RVALUE_REFERENCES + Array(Array&& other) + : Base(std::move(other)) + { + Base::_check_template_params(); + if (RowsAtCompileTime!=Dynamic && ColsAtCompileTime!=Dynamic) + Base::_set_noalias(other); + } + Array& operator=(Array&& other) + { + other.swap(*this); + return *this; + } +#endif + /** Constructs a vector or row-vector with given dimension. \only_for_vectors * * Note that this is only useful for dynamic-size vectors. For fixed-size vectors, diff --git a/gtsam/3rdparty/Eigen/Eigen/src/Core/ArrayBase.h b/gtsam/3rdparty/Eigen/Eigen/src/Core/ArrayBase.h index 38852600d..33ff55371 100644 --- a/gtsam/3rdparty/Eigen/Eigen/src/Core/ArrayBase.h +++ b/gtsam/3rdparty/Eigen/Eigen/src/Core/ArrayBase.h @@ -46,9 +46,6 @@ template class ArrayBase typedef ArrayBase Eigen_BaseClassForSpecializationOfGlobalMathFuncImpl; - using internal::special_scalar_op_base::Scalar, - typename NumTraits::Scalar>::Real>::operator*; - typedef typename internal::traits::StorageKind StorageKind; typedef typename internal::traits::Index Index; typedef typename internal::traits::Scalar Scalar; @@ -56,6 +53,7 @@ template class ArrayBase typedef typename NumTraits::Real RealScalar; typedef DenseBase Base; + using Base::operator*; using Base::RowsAtCompileTime; using Base::ColsAtCompileTime; using Base::SizeAtCompileTime; diff --git a/gtsam/3rdparty/Eigen/Eigen/src/Core/Assign.h b/gtsam/3rdparty/Eigen/Eigen/src/Core/Assign.h index 1dccc2f42..f48173172 100644 --- a/gtsam/3rdparty/Eigen/Eigen/src/Core/Assign.h +++ b/gtsam/3rdparty/Eigen/Eigen/src/Core/Assign.h @@ -439,19 +439,26 @@ struct assign_impl PacketTraits; + typedef typename Derived1::Scalar Scalar; + typedef packet_traits PacketTraits; enum { packetSize = PacketTraits::size, alignable = PacketTraits::AlignedOnScalar, - dstAlignment = alignable ? Aligned : int(assign_traits::DstIsAligned) , + dstIsAligned = assign_traits::DstIsAligned, + dstAlignment = alignable ? Aligned : int(dstIsAligned), srcAlignment = assign_traits::JointAlignment }; + const Scalar *dst_ptr = &dst.coeffRef(0,0); + if((!bool(dstIsAligned)) && (size_t(dst_ptr) % sizeof(Scalar))>0) + { + // the pointer is not aligend-on scalar, so alignment is not possible + return assign_impl::run(dst, src); + } const Index packetAlignedMask = packetSize - 1; const Index innerSize = dst.innerSize(); const Index outerSize = dst.outerSize(); const Index alignedStep = alignable ? (packetSize - dst.outerStride() % packetSize) & packetAlignedMask : 0; - Index alignedStart = ((!alignable) || assign_traits::DstIsAligned) ? 0 - : internal::first_aligned(&dst.coeffRef(0,0), innerSize); + Index alignedStart = ((!alignable) || bool(dstIsAligned)) ? 0 : internal::first_aligned(dst_ptr, innerSize); for(Index outer = 0; outer < outerSize; ++outer) { diff --git a/gtsam/3rdparty/Eigen/Eigen/src/Core/Block.h b/gtsam/3rdparty/Eigen/Eigen/src/Core/Block.h index 87bedfa46..827894443 100644 --- a/gtsam/3rdparty/Eigen/Eigen/src/Core/Block.h +++ b/gtsam/3rdparty/Eigen/Eigen/src/Core/Block.h @@ -66,8 +66,9 @@ struct traits > : traits::MaxColsAtCompileTime), XprTypeIsRowMajor = (int(traits::Flags)&RowMajorBit) != 0, - IsRowMajor = (MaxRowsAtCompileTime==1&&MaxColsAtCompileTime!=1) ? 1 - : (MaxColsAtCompileTime==1&&MaxRowsAtCompileTime!=1) ? 0 + IsDense = is_same::value, + IsRowMajor = (IsDense&&MaxRowsAtCompileTime==1&&MaxColsAtCompileTime!=1) ? 1 + : (IsDense&&MaxColsAtCompileTime==1&&MaxRowsAtCompileTime!=1) ? 0 : XprTypeIsRowMajor, HasSameStorageOrderAsXprType = (IsRowMajor == XprTypeIsRowMajor), InnerSize = IsRowMajor ? int(ColsAtCompileTime) : int(RowsAtCompileTime), diff --git a/gtsam/3rdparty/Eigen/Eigen/src/Core/CommaInitializer.h.orig b/gtsam/3rdparty/Eigen/Eigen/src/Core/CommaInitializer.h.orig deleted file mode 100644 index a036d8c3b..000000000 --- a/gtsam/3rdparty/Eigen/Eigen/src/Core/CommaInitializer.h.orig +++ /dev/null @@ -1,154 +0,0 @@ -// This file is part of Eigen, a lightweight C++ template library -// for linear algebra. -// -// Copyright (C) 2008 Gael Guennebaud -// Copyright (C) 2006-2008 Benoit Jacob -// -// This Source Code Form is subject to the terms of the Mozilla -// Public License v. 2.0. If a copy of the MPL was not distributed -// with this file, You can obtain one at http://mozilla.org/MPL/2.0/. - -#ifndef EIGEN_COMMAINITIALIZER_H -#define EIGEN_COMMAINITIALIZER_H - -namespace Eigen { - -/** \class CommaInitializer - * \ingroup Core_Module - * - * \brief Helper class used by the comma initializer operator - * - * This class is internally used to implement the comma initializer feature. It is - * the return type of MatrixBase::operator<<, and most of the time this is the only - * way it is used. - * - * \sa \ref MatrixBaseCommaInitRef "MatrixBase::operator<<", CommaInitializer::finished() - */ -template -struct CommaInitializer -{ - typedef typename XprType::Scalar Scalar; - typedef typename XprType::Index Index; - - inline CommaInitializer(XprType& xpr, const Scalar& s) - : m_xpr(xpr), m_row(0), m_col(1), m_currentBlockRows(1) - { - m_xpr.coeffRef(0,0) = s; - } - - template - inline CommaInitializer(XprType& xpr, const DenseBase& other) - : m_xpr(xpr), m_row(0), m_col(other.cols()), m_currentBlockRows(other.rows()) - { - m_xpr.block(0, 0, other.rows(), other.cols()) = other; - } - - /* Copy/Move constructor which transfers ownership. This is crucial in - * absence of return value optimization to avoid assertions during destruction. */ - // FIXME in C++11 mode this could be replaced by a proper RValue constructor - inline CommaInitializer(const CommaInitializer& o) - : m_xpr(o.m_xpr), m_row(o.m_row), m_col(o.m_col), m_currentBlockRows(o.m_currentBlockRows) { - // Mark original object as finished. In absence of R-value references we need to const_cast: - const_cast(o).m_row = m_xpr.rows(); - const_cast(o).m_col = m_xpr.cols(); - const_cast(o).m_currentBlockRows = 0; - } - - /* inserts a scalar value in the target matrix */ - CommaInitializer& operator,(const Scalar& s) - { - if (m_col==m_xpr.cols()) - { - m_row+=m_currentBlockRows; - m_col = 0; - m_currentBlockRows = 1; - eigen_assert(m_row - CommaInitializer& operator,(const DenseBase& other) - { - if(other.cols()==0 || other.rows()==0) - return *this; - if (m_col==m_xpr.cols()) - { - m_row+=m_currentBlockRows; - m_col = 0; - m_currentBlockRows = other.rows(); - eigen_assert(m_row+m_currentBlockRows<=m_xpr.rows() - && "Too many rows passed to comma initializer (operator<<)"); - } - eigen_assert(m_col - (m_row, m_col) = other; - else - m_xpr.block(m_row, m_col, other.rows(), other.cols()) = other; - m_col += other.cols(); - return *this; - } - - inline ~CommaInitializer() - { - eigen_assert((m_row+m_currentBlockRows) == m_xpr.rows() - && m_col == m_xpr.cols() - && "Too few coefficients passed to comma initializer (operator<<)"); - } - - /** \returns the built matrix once all its coefficients have been set. - * Calling finished is 100% optional. Its purpose is to write expressions - * like this: - * \code - * quaternion.fromRotationMatrix((Matrix3f() << axis0, axis1, axis2).finished()); - * \endcode - */ - inline XprType& finished() { return m_xpr; } - - XprType& m_xpr; // target expression - Index m_row; // current row id - Index m_col; // current col id - Index m_currentBlockRows; // current block height -}; - -/** \anchor MatrixBaseCommaInitRef - * Convenient operator to set the coefficients of a matrix. - * - * The coefficients must be provided in a row major order and exactly match - * the size of the matrix. Otherwise an assertion is raised. - * - * Example: \include MatrixBase_set.cpp - * Output: \verbinclude MatrixBase_set.out - * - * \note According the c++ standard, the argument expressions of this comma initializer are evaluated in arbitrary order. - * - * \sa CommaInitializer::finished(), class CommaInitializer - */ -template -inline CommaInitializer DenseBase::operator<< (const Scalar& s) -{ - return CommaInitializer(*static_cast(this), s); -} - -/** \sa operator<<(const Scalar&) */ -template -template -inline CommaInitializer -DenseBase::operator<<(const DenseBase& other) -{ - return CommaInitializer(*static_cast(this), other); -} - -} // end namespace Eigen - -#endif // EIGEN_COMMAINITIALIZER_H diff --git a/gtsam/3rdparty/Eigen/Eigen/src/Core/CwiseBinaryOp.h b/gtsam/3rdparty/Eigen/Eigen/src/Core/CwiseBinaryOp.h index 586f77aaf..519a866e6 100644 --- a/gtsam/3rdparty/Eigen/Eigen/src/Core/CwiseBinaryOp.h +++ b/gtsam/3rdparty/Eigen/Eigen/src/Core/CwiseBinaryOp.h @@ -81,7 +81,8 @@ struct traits > ) ), Flags = (Flags0 & ~RowMajorBit) | (LhsFlags & RowMajorBit), - CoeffReadCost = LhsCoeffReadCost + RhsCoeffReadCost + functor_traits::Cost + Cost0 = EIGEN_ADD_COST(LhsCoeffReadCost,RhsCoeffReadCost), + CoeffReadCost = EIGEN_ADD_COST(Cost0,functor_traits::Cost) }; }; } // end namespace internal diff --git a/gtsam/3rdparty/Eigen/Eigen/src/Core/CwiseUnaryOp.h b/gtsam/3rdparty/Eigen/Eigen/src/Core/CwiseUnaryOp.h index f2de749f9..f7ee60e98 100644 --- a/gtsam/3rdparty/Eigen/Eigen/src/Core/CwiseUnaryOp.h +++ b/gtsam/3rdparty/Eigen/Eigen/src/Core/CwiseUnaryOp.h @@ -47,7 +47,7 @@ struct traits > Flags = _XprTypeNested::Flags & ( HereditaryBits | LinearAccessBit | AlignedBit | (functor_traits::PacketAccess ? PacketAccessBit : 0)), - CoeffReadCost = _XprTypeNested::CoeffReadCost + functor_traits::Cost + CoeffReadCost = EIGEN_ADD_COST(_XprTypeNested::CoeffReadCost, functor_traits::Cost) }; }; } diff --git a/gtsam/3rdparty/Eigen/Eigen/src/Core/DenseBase.h b/gtsam/3rdparty/Eigen/Eigen/src/Core/DenseBase.h index 04862f374..354c739f7 100644 --- a/gtsam/3rdparty/Eigen/Eigen/src/Core/DenseBase.h +++ b/gtsam/3rdparty/Eigen/Eigen/src/Core/DenseBase.h @@ -41,14 +41,13 @@ static inline void check_DenseIndex_is_signed() { template class DenseBase #ifndef EIGEN_PARSED_BY_DOXYGEN : public internal::special_scalar_op_base::Scalar, - typename NumTraits::Scalar>::Real> + typename NumTraits::Scalar>::Real, + DenseCoeffsBase > #else : public DenseCoeffsBase #endif // not EIGEN_PARSED_BY_DOXYGEN { public: - using internal::special_scalar_op_base::Scalar, - typename NumTraits::Scalar>::Real>::operator*; class InnerIterator; @@ -63,8 +62,9 @@ template class DenseBase typedef typename internal::traits::Scalar Scalar; typedef typename internal::packet_traits::type PacketScalar; typedef typename NumTraits::Real RealScalar; + typedef internal::special_scalar_op_base > Base; - typedef DenseCoeffsBase Base; + using Base::operator*; using Base::derived; using Base::const_cast_derived; using Base::rows; @@ -183,10 +183,6 @@ template class DenseBase /** \returns the number of nonzero coefficients which is in practice the number * of stored coefficients. */ inline Index nonZeros() const { return size(); } - /** \returns true if either the number of rows or the number of columns is equal to 1. - * In other words, this function returns - * \code rows()==1 || cols()==1 \endcode - * \sa rows(), cols(), IsVectorAtCompileTime. */ /** \returns the outer size. * @@ -266,11 +262,13 @@ template class DenseBase template Derived& operator=(const ReturnByValue& func); -#ifndef EIGEN_PARSED_BY_DOXYGEN - /** Copies \a other into *this without evaluating other. \returns a reference to *this. */ + /** \internal Copies \a other into *this without evaluating other. \returns a reference to *this. */ template Derived& lazyAssign(const DenseBase& other); -#endif // not EIGEN_PARSED_BY_DOXYGEN + + /** \internal Evaluates \a other into *this. \returns a reference to *this. */ + template + Derived& lazyAssign(const ReturnByValue& other); CommaInitializer operator<< (const Scalar& s); diff --git a/gtsam/3rdparty/Eigen/Eigen/src/Core/DenseStorage.h b/gtsam/3rdparty/Eigen/Eigen/src/Core/DenseStorage.h index a72738e55..568493cba 100644 --- a/gtsam/3rdparty/Eigen/Eigen/src/Core/DenseStorage.h +++ b/gtsam/3rdparty/Eigen/Eigen/src/Core/DenseStorage.h @@ -122,33 +122,41 @@ template class DenseSt { internal::plain_array m_data; public: - inline DenseStorage() {} - inline DenseStorage(internal::constructor_without_unaligned_array_assert) + DenseStorage() {} + DenseStorage(internal::constructor_without_unaligned_array_assert) : m_data(internal::constructor_without_unaligned_array_assert()) {} - inline DenseStorage(DenseIndex,DenseIndex,DenseIndex) {} - inline void swap(DenseStorage& other) { std::swap(m_data,other.m_data); } - static inline DenseIndex rows(void) {return _Rows;} - static inline DenseIndex cols(void) {return _Cols;} - inline void conservativeResize(DenseIndex,DenseIndex,DenseIndex) {} - inline void resize(DenseIndex,DenseIndex,DenseIndex) {} - inline const T *data() const { return m_data.array; } - inline T *data() { return m_data.array; } + DenseStorage(const DenseStorage& other) : m_data(other.m_data) {} + DenseStorage& operator=(const DenseStorage& other) + { + if (this != &other) m_data = other.m_data; + return *this; + } + DenseStorage(DenseIndex,DenseIndex,DenseIndex) {} + void swap(DenseStorage& other) { std::swap(m_data,other.m_data); } + static DenseIndex rows(void) {return _Rows;} + static DenseIndex cols(void) {return _Cols;} + void conservativeResize(DenseIndex,DenseIndex,DenseIndex) {} + void resize(DenseIndex,DenseIndex,DenseIndex) {} + const T *data() const { return m_data.array; } + T *data() { return m_data.array; } }; // null matrix template class DenseStorage { public: - inline DenseStorage() {} - inline DenseStorage(internal::constructor_without_unaligned_array_assert) {} - inline DenseStorage(DenseIndex,DenseIndex,DenseIndex) {} - inline void swap(DenseStorage& ) {} - static inline DenseIndex rows(void) {return _Rows;} - static inline DenseIndex cols(void) {return _Cols;} - inline void conservativeResize(DenseIndex,DenseIndex,DenseIndex) {} - inline void resize(DenseIndex,DenseIndex,DenseIndex) {} - inline const T *data() const { return 0; } - inline T *data() { return 0; } + DenseStorage() {} + DenseStorage(internal::constructor_without_unaligned_array_assert) {} + DenseStorage(const DenseStorage&) {} + DenseStorage& operator=(const DenseStorage&) { return *this; } + DenseStorage(DenseIndex,DenseIndex,DenseIndex) {} + void swap(DenseStorage& ) {} + static DenseIndex rows(void) {return _Rows;} + static DenseIndex cols(void) {return _Cols;} + void conservativeResize(DenseIndex,DenseIndex,DenseIndex) {} + void resize(DenseIndex,DenseIndex,DenseIndex) {} + const T *data() const { return 0; } + T *data() { return 0; } }; // more specializations for null matrices; these are necessary to resolve ambiguities @@ -168,18 +176,29 @@ template class DenseStorage class DenseStorage m_data; DenseIndex m_rows; public: - inline DenseStorage() : m_rows(0) {} - inline DenseStorage(internal::constructor_without_unaligned_array_assert) + DenseStorage() : m_rows(0) {} + DenseStorage(internal::constructor_without_unaligned_array_assert) : m_data(internal::constructor_without_unaligned_array_assert()), m_rows(0) {} - inline DenseStorage(DenseIndex, DenseIndex nbRows, DenseIndex) : m_rows(nbRows) {} - inline void swap(DenseStorage& other) { std::swap(m_data,other.m_data); std::swap(m_rows,other.m_rows); } - inline DenseIndex rows(void) const {return m_rows;} - inline DenseIndex cols(void) const {return _Cols;} - inline void conservativeResize(DenseIndex, DenseIndex nbRows, DenseIndex) { m_rows = nbRows; } - inline void resize(DenseIndex, DenseIndex nbRows, DenseIndex) { m_rows = nbRows; } - inline const T *data() const { return m_data.array; } - inline T *data() { return m_data.array; } + DenseStorage(const DenseStorage& other) : m_data(other.m_data), m_rows(other.m_rows) {} + DenseStorage& operator=(const DenseStorage& other) + { + if (this != &other) + { + m_data = other.m_data; + m_rows = other.m_rows; + } + return *this; + } + DenseStorage(DenseIndex, DenseIndex nbRows, DenseIndex) : m_rows(nbRows) {} + void swap(DenseStorage& other) { std::swap(m_data,other.m_data); std::swap(m_rows,other.m_rows); } + DenseIndex rows(void) const {return m_rows;} + DenseIndex cols(void) const {return _Cols;} + void conservativeResize(DenseIndex, DenseIndex nbRows, DenseIndex) { m_rows = nbRows; } + void resize(DenseIndex, DenseIndex nbRows, DenseIndex) { m_rows = nbRows; } + const T *data() const { return m_data.array; } + T *data() { return m_data.array; } }; // dynamic-size matrix with fixed-size storage and fixed height @@ -207,17 +236,27 @@ template class DenseStorage m_data; DenseIndex m_cols; public: - inline DenseStorage() : m_cols(0) {} - inline DenseStorage(internal::constructor_without_unaligned_array_assert) + DenseStorage() : m_cols(0) {} + DenseStorage(internal::constructor_without_unaligned_array_assert) : m_data(internal::constructor_without_unaligned_array_assert()), m_cols(0) {} - inline DenseStorage(DenseIndex, DenseIndex, DenseIndex nbCols) : m_cols(nbCols) {} - inline void swap(DenseStorage& other) { std::swap(m_data,other.m_data); std::swap(m_cols,other.m_cols); } - inline DenseIndex rows(void) const {return _Rows;} - inline DenseIndex cols(void) const {return m_cols;} - inline void conservativeResize(DenseIndex, DenseIndex, DenseIndex nbCols) { m_cols = nbCols; } - inline void resize(DenseIndex, DenseIndex, DenseIndex nbCols) { m_cols = nbCols; } - inline const T *data() const { return m_data.array; } - inline T *data() { return m_data.array; } + DenseStorage(const DenseStorage& other) : m_data(other.m_data), m_cols(other.m_cols) {} + DenseStorage& operator=(const DenseStorage& other) + { + if (this != &other) + { + m_data = other.m_data; + m_cols = other.m_cols; + } + return *this; + } + DenseStorage(DenseIndex, DenseIndex, DenseIndex nbCols) : m_cols(nbCols) {} + void swap(DenseStorage& other) { std::swap(m_data,other.m_data); std::swap(m_cols,other.m_cols); } + DenseIndex rows(void) const {return _Rows;} + DenseIndex cols(void) const {return m_cols;} + void conservativeResize(DenseIndex, DenseIndex, DenseIndex nbCols) { m_cols = nbCols; } + void resize(DenseIndex, DenseIndex, DenseIndex nbCols) { m_cols = nbCols; } + const T *data() const { return m_data.array; } + T *data() { return m_data.array; } }; // purely dynamic matrix. @@ -227,18 +266,35 @@ template class DenseStorage(size)), m_rows(nbRows), m_cols(nbCols) { EIGEN_INTERNAL_DENSE_STORAGE_CTOR_PLUGIN } - inline ~DenseStorage() { internal::conditional_aligned_delete_auto(m_data, m_rows*m_cols); } - inline void swap(DenseStorage& other) +#ifdef EIGEN_HAVE_RVALUE_REFERENCES + DenseStorage(DenseStorage&& other) + : m_data(std::move(other.m_data)) + , m_rows(std::move(other.m_rows)) + , m_cols(std::move(other.m_cols)) + { + other.m_data = nullptr; + } + DenseStorage& operator=(DenseStorage&& other) + { + using std::swap; + swap(m_data, other.m_data); + swap(m_rows, other.m_rows); + swap(m_cols, other.m_cols); + return *this; + } +#endif + ~DenseStorage() { internal::conditional_aligned_delete_auto(m_data, m_rows*m_cols); } + void swap(DenseStorage& other) { std::swap(m_data,other.m_data); std::swap(m_rows,other.m_rows); std::swap(m_cols,other.m_cols); } - inline DenseIndex rows(void) const {return m_rows;} - inline DenseIndex cols(void) const {return m_cols;} - inline void conservativeResize(DenseIndex size, DenseIndex nbRows, DenseIndex nbCols) + DenseIndex rows(void) const {return m_rows;} + DenseIndex cols(void) const {return m_cols;} + void conservativeResize(DenseIndex size, DenseIndex nbRows, DenseIndex nbCols) { m_data = internal::conditional_aligned_realloc_new_auto(m_data, size, m_rows*m_cols); m_rows = nbRows; @@ -258,8 +314,11 @@ template class DenseStorage class DenseStorage(size)), m_cols(nbCols) + DenseStorage() : m_data(0), m_cols(0) {} + DenseStorage(internal::constructor_without_unaligned_array_assert) : m_data(0), m_cols(0) {} + DenseStorage(DenseIndex size, DenseIndex, DenseIndex nbCols) : m_data(internal::conditional_aligned_new_auto(size)), m_cols(nbCols) { EIGEN_INTERNAL_DENSE_STORAGE_CTOR_PLUGIN } - inline ~DenseStorage() { internal::conditional_aligned_delete_auto(m_data, _Rows*m_cols); } - inline void swap(DenseStorage& other) { std::swap(m_data,other.m_data); std::swap(m_cols,other.m_cols); } - static inline DenseIndex rows(void) {return _Rows;} - inline DenseIndex cols(void) const {return m_cols;} - inline void conservativeResize(DenseIndex size, DenseIndex, DenseIndex nbCols) +#ifdef EIGEN_HAVE_RVALUE_REFERENCES + DenseStorage(DenseStorage&& other) + : m_data(std::move(other.m_data)) + , m_cols(std::move(other.m_cols)) + { + other.m_data = nullptr; + } + DenseStorage& operator=(DenseStorage&& other) + { + using std::swap; + swap(m_data, other.m_data); + swap(m_cols, other.m_cols); + return *this; + } +#endif + ~DenseStorage() { internal::conditional_aligned_delete_auto(m_data, _Rows*m_cols); } + void swap(DenseStorage& other) { std::swap(m_data,other.m_data); std::swap(m_cols,other.m_cols); } + static DenseIndex rows(void) {return _Rows;} + DenseIndex cols(void) const {return m_cols;} + void conservativeResize(DenseIndex size, DenseIndex, DenseIndex nbCols) { m_data = internal::conditional_aligned_realloc_new_auto(m_data, size, _Rows*m_cols); m_cols = nbCols; @@ -294,8 +368,11 @@ template class DenseStorage class DenseStorage(size)), m_rows(nbRows) + DenseStorage() : m_data(0), m_rows(0) {} + DenseStorage(internal::constructor_without_unaligned_array_assert) : m_data(0), m_rows(0) {} + DenseStorage(DenseIndex size, DenseIndex nbRows, DenseIndex) : m_data(internal::conditional_aligned_new_auto(size)), m_rows(nbRows) { EIGEN_INTERNAL_DENSE_STORAGE_CTOR_PLUGIN } - inline ~DenseStorage() { internal::conditional_aligned_delete_auto(m_data, _Cols*m_rows); } - inline void swap(DenseStorage& other) { std::swap(m_data,other.m_data); std::swap(m_rows,other.m_rows); } - inline DenseIndex rows(void) const {return m_rows;} - static inline DenseIndex cols(void) {return _Cols;} - inline void conservativeResize(DenseIndex size, DenseIndex nbRows, DenseIndex) +#ifdef EIGEN_HAVE_RVALUE_REFERENCES + DenseStorage(DenseStorage&& other) + : m_data(std::move(other.m_data)) + , m_rows(std::move(other.m_rows)) + { + other.m_data = nullptr; + } + DenseStorage& operator=(DenseStorage&& other) + { + using std::swap; + swap(m_data, other.m_data); + swap(m_rows, other.m_rows); + return *this; + } +#endif + ~DenseStorage() { internal::conditional_aligned_delete_auto(m_data, _Cols*m_rows); } + void swap(DenseStorage& other) { std::swap(m_data,other.m_data); std::swap(m_rows,other.m_rows); } + DenseIndex rows(void) const {return m_rows;} + static DenseIndex cols(void) {return _Cols;} + void conservativeResize(DenseIndex size, DenseIndex nbRows, DenseIndex) { m_data = internal::conditional_aligned_realloc_new_auto(m_data, size, m_rows*_Cols); m_rows = nbRows; @@ -330,8 +422,11 @@ template class DenseStorage > _Vectorizable = bool(int(MatrixType::Flags)&PacketAccessBit) && _SameTypes && (_ScalarAccessOnDiag || (bool(int(DiagonalType::DiagonalVectorType::Flags)&PacketAccessBit))), _LinearAccessMask = (RowsAtCompileTime==1 || ColsAtCompileTime==1) ? LinearAccessBit : 0, - Flags = ((HereditaryBits|_LinearAccessMask) & (unsigned int)(MatrixType::Flags)) | (_Vectorizable ? PacketAccessBit : 0) | AlignedBit,//(int(MatrixType::Flags)&int(DiagonalType::DiagonalVectorType::Flags)&AlignedBit), - CoeffReadCost = NumTraits::MulCost + MatrixType::CoeffReadCost + DiagonalType::DiagonalVectorType::CoeffReadCost + Flags = ((HereditaryBits|_LinearAccessMask|AlignedBit) & (unsigned int)(MatrixType::Flags)) | (_Vectorizable ? PacketAccessBit : 0),//(int(MatrixType::Flags)&int(DiagonalType::DiagonalVectorType::Flags)&AlignedBit), + Cost0 = EIGEN_ADD_COST(NumTraits::MulCost, MatrixType::CoeffReadCost), + CoeffReadCost = EIGEN_ADD_COST(Cost0,DiagonalType::DiagonalVectorType::CoeffReadCost) }; }; } diff --git a/gtsam/3rdparty/Eigen/Eigen/src/Core/Functors.h b/gtsam/3rdparty/Eigen/Eigen/src/Core/Functors.h index b08b967ff..5f14c6587 100644 --- a/gtsam/3rdparty/Eigen/Eigen/src/Core/Functors.h +++ b/gtsam/3rdparty/Eigen/Eigen/src/Core/Functors.h @@ -259,6 +259,47 @@ template<> struct functor_traits { }; }; +/** \internal + * \brief Template functors for comparison of two scalars + * \todo Implement packet-comparisons + */ +template struct scalar_cmp_op; + +template +struct functor_traits > { + enum { + Cost = NumTraits::AddCost, + PacketAccess = false + }; +}; + +template +struct result_of(Scalar,Scalar)> { + typedef bool type; +}; + + +template struct scalar_cmp_op { + EIGEN_EMPTY_STRUCT_CTOR(scalar_cmp_op) + EIGEN_STRONG_INLINE bool operator()(const Scalar& a, const Scalar& b) const {return a==b;} +}; +template struct scalar_cmp_op { + EIGEN_EMPTY_STRUCT_CTOR(scalar_cmp_op) + EIGEN_STRONG_INLINE bool operator()(const Scalar& a, const Scalar& b) const {return a struct scalar_cmp_op { + EIGEN_EMPTY_STRUCT_CTOR(scalar_cmp_op) + EIGEN_STRONG_INLINE bool operator()(const Scalar& a, const Scalar& b) const {return a<=b;} +}; +template struct scalar_cmp_op { + EIGEN_EMPTY_STRUCT_CTOR(scalar_cmp_op) + EIGEN_STRONG_INLINE bool operator()(const Scalar& a, const Scalar& b) const {return !(a<=b || b<=a);} +}; +template struct scalar_cmp_op { + EIGEN_EMPTY_STRUCT_CTOR(scalar_cmp_op) + EIGEN_STRONG_INLINE bool operator()(const Scalar& a, const Scalar& b) const {return a!=b;} +}; + // unary functors: /** \internal diff --git a/gtsam/3rdparty/Eigen/Eigen/src/Core/GeneralProduct.h b/gtsam/3rdparty/Eigen/Eigen/src/Core/GeneralProduct.h index 9e805a80f..0eae52990 100644 --- a/gtsam/3rdparty/Eigen/Eigen/src/Core/GeneralProduct.h +++ b/gtsam/3rdparty/Eigen/Eigen/src/Core/GeneralProduct.h @@ -257,7 +257,7 @@ template class GeneralProduct : public ProductBase, Lhs, Rhs> { - template struct IsRowMajor : internal::conditional<(int(T::Flags)&RowMajorBit), internal::true_type, internal::false_type>::type {}; + template struct is_row_major : internal::conditional<(int(T::Flags)&RowMajorBit), internal::true_type, internal::false_type>::type {}; public: EIGEN_PRODUCT_PUBLIC_INTERFACE(GeneralProduct) @@ -281,22 +281,22 @@ class GeneralProduct template inline void evalTo(Dest& dest) const { - internal::outer_product_selector_run(*this, dest, set(), IsRowMajor()); + internal::outer_product_selector_run(*this, dest, set(), is_row_major()); } template inline void addTo(Dest& dest) const { - internal::outer_product_selector_run(*this, dest, add(), IsRowMajor()); + internal::outer_product_selector_run(*this, dest, add(), is_row_major()); } template inline void subTo(Dest& dest) const { - internal::outer_product_selector_run(*this, dest, sub(), IsRowMajor()); + internal::outer_product_selector_run(*this, dest, sub(), is_row_major()); } template void scaleAndAddTo(Dest& dest, const Scalar& alpha) const { - internal::outer_product_selector_run(*this, dest, adds(alpha), IsRowMajor()); + internal::outer_product_selector_run(*this, dest, adds(alpha), is_row_major()); } }; diff --git a/gtsam/3rdparty/Eigen/Eigen/src/Core/MapBase.h b/gtsam/3rdparty/Eigen/Eigen/src/Core/MapBase.h index cebed2bb6..a9828f7f4 100644 --- a/gtsam/3rdparty/Eigen/Eigen/src/Core/MapBase.h +++ b/gtsam/3rdparty/Eigen/Eigen/src/Core/MapBase.h @@ -123,7 +123,7 @@ template class MapBase return internal::ploadt(m_data + index * innerStride()); } - inline MapBase(PointerType dataPtr) : m_data(dataPtr), m_rows(RowsAtCompileTime), m_cols(ColsAtCompileTime) + explicit inline MapBase(PointerType dataPtr) : m_data(dataPtr), m_rows(RowsAtCompileTime), m_cols(ColsAtCompileTime) { EIGEN_STATIC_ASSERT_FIXED_SIZE(Derived) checkSanity(); @@ -157,7 +157,7 @@ template class MapBase internal::inner_stride_at_compile_time::ret==1), PACKET_ACCESS_REQUIRES_TO_HAVE_INNER_STRIDE_FIXED_TO_1); eigen_assert(EIGEN_IMPLIES(internal::traits::Flags&AlignedBit, (size_t(m_data) % 16) == 0) - && "data is not aligned"); + && "input pointer is not aligned on a 16 byte boundary"); } PointerType m_data; diff --git a/gtsam/3rdparty/Eigen/Eigen/src/Core/MathFunctions.h b/gtsam/3rdparty/Eigen/Eigen/src/Core/MathFunctions.h index 2bfc5ebd9..adf2f9c51 100644 --- a/gtsam/3rdparty/Eigen/Eigen/src/Core/MathFunctions.h +++ b/gtsam/3rdparty/Eigen/Eigen/src/Core/MathFunctions.h @@ -294,7 +294,7 @@ struct hypot_impl RealScalar _x = abs(x); RealScalar _y = abs(y); RealScalar p = (max)(_x, _y); - if(p==RealScalar(0)) return 0; + if(p==RealScalar(0)) return RealScalar(0); RealScalar q = (min)(_x, _y); RealScalar qp = q/p; return p * sqrt(RealScalar(1) + qp*qp); diff --git a/gtsam/3rdparty/Eigen/Eigen/src/Core/Matrix.h b/gtsam/3rdparty/Eigen/Eigen/src/Core/Matrix.h index d7d0b5b9a..02be142d8 100644 --- a/gtsam/3rdparty/Eigen/Eigen/src/Core/Matrix.h +++ b/gtsam/3rdparty/Eigen/Eigen/src/Core/Matrix.h @@ -211,6 +211,21 @@ class Matrix : Base(internal::constructor_without_unaligned_array_assert()) { Base::_check_template_params(); EIGEN_INITIALIZE_COEFFS_IF_THAT_OPTION_IS_ENABLED } +#ifdef EIGEN_HAVE_RVALUE_REFERENCES + Matrix(Matrix&& other) + : Base(std::move(other)) + { + Base::_check_template_params(); + if (RowsAtCompileTime!=Dynamic && ColsAtCompileTime!=Dynamic) + Base::_set_noalias(other); + } + Matrix& operator=(Matrix&& other) + { + other.swap(*this); + return *this; + } +#endif + /** \brief Constructs a vector or row-vector with given dimension. \only_for_vectors * * Note that this is only useful for dynamic-size vectors. For fixed-size vectors, diff --git a/gtsam/3rdparty/Eigen/Eigen/src/Core/MatrixBase.h b/gtsam/3rdparty/Eigen/Eigen/src/Core/MatrixBase.h index cc3279746..e83ef4dc0 100644 --- a/gtsam/3rdparty/Eigen/Eigen/src/Core/MatrixBase.h +++ b/gtsam/3rdparty/Eigen/Eigen/src/Core/MatrixBase.h @@ -159,13 +159,11 @@ template class MatrixBase template Derived& operator=(const ReturnByValue& other); -#ifndef EIGEN_PARSED_BY_DOXYGEN template Derived& lazyAssign(const ProductBase& other); template Derived& lazyAssign(const MatrixPowerProduct& other); -#endif // not EIGEN_PARSED_BY_DOXYGEN template Derived& operator+=(const MatrixBase& other); @@ -442,6 +440,15 @@ template class MatrixBase template void applyOnTheRight(Index p, Index q, const JacobiRotation& j); +///////// SparseCore module ///////// + + template + EIGEN_STRONG_INLINE const typename SparseMatrixBase::template CwiseProductDenseReturnType::Type + cwiseProduct(const SparseMatrixBase &other) const + { + return other.cwiseProduct(derived()); + } + ///////// MatrixFunctions module ///////// typedef typename internal::stem_function::type StemFunction; diff --git a/gtsam/3rdparty/Eigen/Eigen/src/Core/PermutationMatrix.h b/gtsam/3rdparty/Eigen/Eigen/src/Core/PermutationMatrix.h index f26f3e5cc..85ffae265 100644 --- a/gtsam/3rdparty/Eigen/Eigen/src/Core/PermutationMatrix.h +++ b/gtsam/3rdparty/Eigen/Eigen/src/Core/PermutationMatrix.h @@ -250,6 +250,35 @@ class PermutationBase : public EigenBase template friend inline PlainPermutationType operator*(const Transpose >& other, const PermutationBase& perm) { return PlainPermutationType(internal::PermPermProduct, other.eval(), perm); } + + /** \returns the determinant of the permutation matrix, which is either 1 or -1 depending on the parity of the permutation. + * + * This function is O(\c n) procedure allocating a buffer of \c n booleans. + */ + Index determinant() const + { + Index res = 1; + Index n = size(); + Matrix mask(n); + mask.fill(false); + Index r = 0; + while(r < n) + { + // search for the next seed + while(r=n) + break; + // we got one, let's follow it until we are back to the seed + Index k0 = r++; + mask.coeffRef(k0) = true; + for(Index k=indices().coeff(k0); k!=k0; k=indices().coeff(k)) + { + mask.coeffRef(k) = true; + res = -res; + } + } + return res; + } protected: diff --git a/gtsam/3rdparty/Eigen/Eigen/src/Core/PlainObjectBase.h b/gtsam/3rdparty/Eigen/Eigen/src/Core/PlainObjectBase.h index dd34b59e5..a4e4af4a7 100644 --- a/gtsam/3rdparty/Eigen/Eigen/src/Core/PlainObjectBase.h +++ b/gtsam/3rdparty/Eigen/Eigen/src/Core/PlainObjectBase.h @@ -437,6 +437,36 @@ class PlainObjectBase : public internal::dense_xpr_base::type } #endif +#ifdef EIGEN_HAVE_RVALUE_REFERENCES + PlainObjectBase(PlainObjectBase&& other) + : m_storage( std::move(other.m_storage) ) + { + } + + PlainObjectBase& operator=(PlainObjectBase&& other) + { + using std::swap; + swap(m_storage, other.m_storage); + return *this; + } +#endif + + /** Copy constructor */ + EIGEN_STRONG_INLINE PlainObjectBase(const PlainObjectBase& other) + : m_storage() + { + _check_template_params(); + lazyAssign(other); + } + + template + EIGEN_STRONG_INLINE PlainObjectBase(const DenseBase &other) + : m_storage() + { + _check_template_params(); + lazyAssign(other); + } + EIGEN_STRONG_INLINE PlainObjectBase(Index a_size, Index nbRows, Index nbCols) : m_storage(a_size, nbRows, nbCols) { @@ -573,6 +603,8 @@ class PlainObjectBase : public internal::dense_xpr_base::type : (rows() == other.rows() && cols() == other.cols()))) && "Size mismatch. Automatic resizing is disabled because EIGEN_NO_AUTOMATIC_RESIZING is defined"); EIGEN_ONLY_USED_FOR_DEBUG(other); + if(this->size()==0) + resizeLike(other); #else resizeLike(other); #endif diff --git a/gtsam/3rdparty/Eigen/Eigen/src/Core/Redux.h b/gtsam/3rdparty/Eigen/Eigen/src/Core/Redux.h index 50548fa9a..9b8662a6f 100644 --- a/gtsam/3rdparty/Eigen/Eigen/src/Core/Redux.h +++ b/gtsam/3rdparty/Eigen/Eigen/src/Core/Redux.h @@ -247,8 +247,9 @@ struct redux_impl } }; -template -struct redux_impl +// NOTE: for SliceVectorizedTraversal we simply bypass unrolling +template +struct redux_impl { typedef typename Derived::Scalar Scalar; typedef typename packet_traits::type PacketScalar; diff --git a/gtsam/3rdparty/Eigen/Eigen/src/Core/Ref.h b/gtsam/3rdparty/Eigen/Eigen/src/Core/Ref.h index df87b1af4..7a3becaf8 100644 --- a/gtsam/3rdparty/Eigen/Eigen/src/Core/Ref.h +++ b/gtsam/3rdparty/Eigen/Eigen/src/Core/Ref.h @@ -108,7 +108,8 @@ struct traits > OuterStrideMatch = Derived::IsVectorAtCompileTime || int(StrideType::OuterStrideAtCompileTime)==int(Dynamic) || int(StrideType::OuterStrideAtCompileTime)==int(Derived::OuterStrideAtCompileTime), AlignmentMatch = (_Options!=Aligned) || ((PlainObjectType::Flags&AlignedBit)==0) || ((traits::Flags&AlignedBit)==AlignedBit), - MatchAtCompileTime = HasDirectAccess && StorageOrderMatch && InnerStrideMatch && OuterStrideMatch && AlignmentMatch + ScalarTypeMatch = internal::is_same::value, + MatchAtCompileTime = HasDirectAccess && StorageOrderMatch && InnerStrideMatch && OuterStrideMatch && AlignmentMatch && ScalarTypeMatch }; typedef typename internal::conditional::type type; }; @@ -187,9 +188,11 @@ protected: template class Ref : public RefBase > { + private: typedef internal::traits Traits; template - inline Ref(const PlainObjectBase& expr); + inline Ref(const PlainObjectBase& expr, + typename internal::enable_if::MatchAtCompileTime),Derived>::type* = 0); public: typedef RefBase Base; @@ -198,13 +201,15 @@ template class Ref #ifndef EIGEN_PARSED_BY_DOXYGEN template - inline Ref(PlainObjectBase& expr) + inline Ref(PlainObjectBase& expr, + typename internal::enable_if::MatchAtCompileTime),Derived>::type* = 0) { EIGEN_STATIC_ASSERT(static_cast(Traits::template match::MatchAtCompileTime), STORAGE_LAYOUT_DOES_NOT_MATCH); Base::construct(expr.derived()); } template - inline Ref(const DenseBase& expr) + inline Ref(const DenseBase& expr, + typename internal::enable_if::MatchAtCompileTime),Derived>::type* = 0) #else template inline Ref(DenseBase& expr) @@ -231,13 +236,23 @@ template class Ref< EIGEN_DENSE_PUBLIC_INTERFACE(Ref) template - inline Ref(const DenseBase& expr) + inline Ref(const DenseBase& expr, + typename internal::enable_if::ScalarTypeMatch),Derived>::type* = 0) { // std::cout << match_helper::HasDirectAccess << "," << match_helper::OuterStrideMatch << "," << match_helper::InnerStrideMatch << "\n"; // std::cout << int(StrideType::OuterStrideAtCompileTime) << " - " << int(Derived::OuterStrideAtCompileTime) << "\n"; // std::cout << int(StrideType::InnerStrideAtCompileTime) << " - " << int(Derived::InnerStrideAtCompileTime) << "\n"; construct(expr.derived(), typename Traits::template match::type()); } + + inline Ref(const Ref& other) : Base(other) { + // copy constructor shall not copy the m_object, to avoid unnecessary malloc and copy + } + + template + inline Ref(const RefBase& other) { + construct(other.derived(), typename Traits::template match::type()); + } protected: diff --git a/gtsam/3rdparty/Eigen/Eigen/src/Core/ReturnByValue.h b/gtsam/3rdparty/Eigen/Eigen/src/Core/ReturnByValue.h index d66c24ba0..f635598dc 100644 --- a/gtsam/3rdparty/Eigen/Eigen/src/Core/ReturnByValue.h +++ b/gtsam/3rdparty/Eigen/Eigen/src/Core/ReturnByValue.h @@ -72,6 +72,8 @@ template class ReturnByValue const Unusable& coeff(Index,Index) const { return *reinterpret_cast(this); } Unusable& coeffRef(Index) { return *reinterpret_cast(this); } Unusable& coeffRef(Index,Index) { return *reinterpret_cast(this); } + template Unusable& packet(Index) const; + template Unusable& packet(Index, Index) const; #endif }; @@ -83,6 +85,15 @@ Derived& DenseBase::operator=(const ReturnByValue& other) return derived(); } +template +template +Derived& DenseBase::lazyAssign(const ReturnByValue& other) +{ + other.evalTo(derived()); + return derived(); +} + + } // end namespace Eigen #endif // EIGEN_RETURNBYVALUE_H diff --git a/gtsam/3rdparty/Eigen/Eigen/src/Core/SelfCwiseBinaryOp.h b/gtsam/3rdparty/Eigen/Eigen/src/Core/SelfCwiseBinaryOp.h index 22f3047b4..0956475af 100644 --- a/gtsam/3rdparty/Eigen/Eigen/src/Core/SelfCwiseBinaryOp.h +++ b/gtsam/3rdparty/Eigen/Eigen/src/Core/SelfCwiseBinaryOp.h @@ -180,15 +180,9 @@ inline Derived& DenseBase::operator*=(const Scalar& other) template inline Derived& DenseBase::operator/=(const Scalar& other) { - typedef typename internal::conditional::IsInteger, - internal::scalar_quotient_op, - internal::scalar_product_op >::type BinOp; typedef typename Derived::PlainObject PlainObject; - SelfCwiseBinaryOp tmp(derived()); - Scalar actual_other; - if(NumTraits::IsInteger) actual_other = other; - else actual_other = Scalar(1)/other; - tmp = PlainObject::Constant(rows(),cols(), actual_other); + SelfCwiseBinaryOp, Derived, typename PlainObject::ConstantReturnType> tmp(derived()); + tmp = PlainObject::Constant(rows(),cols(), other); return derived(); } diff --git a/gtsam/3rdparty/Eigen/Eigen/src/Core/arch/NEON/PacketMath.h b/gtsam/3rdparty/Eigen/Eigen/src/Core/arch/NEON/PacketMath.h index 94dfab330..d49670e04 100644 --- a/gtsam/3rdparty/Eigen/Eigen/src/Core/arch/NEON/PacketMath.h +++ b/gtsam/3rdparty/Eigen/Eigen/src/Core/arch/NEON/PacketMath.h @@ -384,6 +384,7 @@ template<> EIGEN_STRONG_INLINE int predux_max(const Packet4i& a) a_lo = vget_low_s32(a); a_hi = vget_high_s32(a); max = vpmax_s32(a_lo, a_hi); + max = vpmax_s32(max, max); return vget_lane_s32(max, 0); } diff --git a/gtsam/3rdparty/Eigen/Eigen/src/Core/arch/SSE/MathFunctions.h b/gtsam/3rdparty/Eigen/Eigen/src/Core/arch/SSE/MathFunctions.h index d16f30bb0..2b07168ae 100644 --- a/gtsam/3rdparty/Eigen/Eigen/src/Core/arch/SSE/MathFunctions.h +++ b/gtsam/3rdparty/Eigen/Eigen/src/Core/arch/SSE/MathFunctions.h @@ -126,7 +126,7 @@ Packet4f pexp(const Packet4f& _x) _EIGEN_DECLARE_CONST_Packet4f(cephes_exp_p4, 1.6666665459E-1f); _EIGEN_DECLARE_CONST_Packet4f(cephes_exp_p5, 5.0000001201E-1f); - Packet4f tmp = _mm_setzero_ps(), fx; + Packet4f tmp, fx; Packet4i emm0; // clamp x @@ -195,7 +195,7 @@ Packet2d pexp(const Packet2d& _x) _EIGEN_DECLARE_CONST_Packet2d(cephes_exp_C2, 1.42860682030941723212e-6); static const __m128i p4i_1023_0 = _mm_setr_epi32(1023, 1023, 0, 0); - Packet2d tmp = _mm_setzero_pd(), fx; + Packet2d tmp, fx; Packet4i emm0; // clamp x @@ -279,7 +279,7 @@ Packet4f psin(const Packet4f& _x) _EIGEN_DECLARE_CONST_Packet4f(coscof_p2, 4.166664568298827E-002f); _EIGEN_DECLARE_CONST_Packet4f(cephes_FOPI, 1.27323954473516f); // 4 / M_PI - Packet4f xmm1, xmm2 = _mm_setzero_ps(), xmm3, sign_bit, y; + Packet4f xmm1, xmm2, xmm3, sign_bit, y; Packet4i emm0, emm2; sign_bit = x; @@ -378,7 +378,7 @@ Packet4f pcos(const Packet4f& _x) _EIGEN_DECLARE_CONST_Packet4f(coscof_p2, 4.166664568298827E-002f); _EIGEN_DECLARE_CONST_Packet4f(cephes_FOPI, 1.27323954473516f); // 4 / M_PI - Packet4f xmm1, xmm2 = _mm_setzero_ps(), xmm3, y; + Packet4f xmm1, xmm2, xmm3, y; Packet4i emm0, emm2; x = pabs(x); diff --git a/gtsam/3rdparty/Eigen/Eigen/src/Core/products/CoeffBasedProduct.h b/gtsam/3rdparty/Eigen/Eigen/src/Core/products/CoeffBasedProduct.h index 421f925e1..2a9d65b94 100644 --- a/gtsam/3rdparty/Eigen/Eigen/src/Core/products/CoeffBasedProduct.h +++ b/gtsam/3rdparty/Eigen/Eigen/src/Core/products/CoeffBasedProduct.h @@ -134,7 +134,7 @@ class CoeffBasedProduct }; typedef internal::product_coeff_impl ScalarCoeffImpl; typedef CoeffBasedProduct LazyCoeffBasedProductType; @@ -185,7 +185,7 @@ class CoeffBasedProduct { PacketScalar res; internal::product_packet_impl ::run(row, col, m_lhs, m_rhs, res); return res; @@ -243,7 +243,17 @@ struct product_coeff_impl static EIGEN_STRONG_INLINE void run(Index row, Index col, const Lhs& lhs, const Rhs& rhs, RetScalar &res) { product_coeff_impl::run(row, col, lhs, rhs, res); - res += lhs.coeff(row, UnrollingIndex) * rhs.coeff(UnrollingIndex, col); + res += lhs.coeff(row, UnrollingIndex-1) * rhs.coeff(UnrollingIndex-1, col); + } +}; + +template +struct product_coeff_impl +{ + typedef typename Lhs::Index Index; + static EIGEN_STRONG_INLINE void run(Index row, Index col, const Lhs& lhs, const Rhs& rhs, RetScalar &res) + { + res = lhs.coeff(row, 0) * rhs.coeff(0, col); } }; @@ -251,9 +261,9 @@ template struct product_coeff_impl { typedef typename Lhs::Index Index; - static EIGEN_STRONG_INLINE void run(Index row, Index col, const Lhs& lhs, const Rhs& rhs, RetScalar &res) + static EIGEN_STRONG_INLINE void run(Index /*row*/, Index /*col*/, const Lhs& /*lhs*/, const Rhs& /*rhs*/, RetScalar &res) { - res = lhs.coeff(row, 0) * rhs.coeff(0, col); + res = RetScalar(0); } }; @@ -293,6 +303,16 @@ struct product_coeff_vectorized_unroller<0, Lhs, Rhs, Packet> } }; +template +struct product_coeff_impl +{ + typedef typename Lhs::Index Index; + static EIGEN_STRONG_INLINE void run(Index /*row*/, Index /*col*/, const Lhs& /*lhs*/, const Rhs& /*rhs*/, RetScalar &res) + { + res = 0; + } +}; + template struct product_coeff_impl { @@ -302,8 +322,7 @@ struct product_coeff_impl::run(row, col, lhs, rhs, pres); - product_coeff_impl::run(row, col, lhs, rhs, res); + product_coeff_vectorized_unroller::run(row, col, lhs, rhs, pres); res = predux(pres); } }; @@ -371,7 +390,7 @@ struct product_packet_impl static EIGEN_STRONG_INLINE void run(Index row, Index col, const Lhs& lhs, const Rhs& rhs, Packet &res) { product_packet_impl::run(row, col, lhs, rhs, res); - res = pmadd(pset1(lhs.coeff(row, UnrollingIndex)), rhs.template packet(UnrollingIndex, col), res); + res = pmadd(pset1(lhs.coeff(row, UnrollingIndex-1)), rhs.template packet(UnrollingIndex-1, col), res); } }; @@ -382,12 +401,12 @@ struct product_packet_impl static EIGEN_STRONG_INLINE void run(Index row, Index col, const Lhs& lhs, const Rhs& rhs, Packet &res) { product_packet_impl::run(row, col, lhs, rhs, res); - res = pmadd(lhs.template packet(row, UnrollingIndex), pset1(rhs.coeff(UnrollingIndex, col)), res); + res = pmadd(lhs.template packet(row, UnrollingIndex-1), pset1(rhs.coeff(UnrollingIndex-1, col)), res); } }; template -struct product_packet_impl +struct product_packet_impl { typedef typename Lhs::Index Index; static EIGEN_STRONG_INLINE void run(Index row, Index col, const Lhs& lhs, const Rhs& rhs, Packet &res) @@ -397,7 +416,7 @@ struct product_packet_impl }; template -struct product_packet_impl +struct product_packet_impl { typedef typename Lhs::Index Index; static EIGEN_STRONG_INLINE void run(Index row, Index col, const Lhs& lhs, const Rhs& rhs, Packet &res) @@ -406,16 +425,35 @@ struct product_packet_impl } }; +template +struct product_packet_impl +{ + typedef typename Lhs::Index Index; + static EIGEN_STRONG_INLINE void run(Index /*row*/, Index /*col*/, const Lhs& /*lhs*/, const Rhs& /*rhs*/, Packet &res) + { + res = pset1(0); + } +}; + +template +struct product_packet_impl +{ + typedef typename Lhs::Index Index; + static EIGEN_STRONG_INLINE void run(Index /*row*/, Index /*col*/, const Lhs& /*lhs*/, const Rhs& /*rhs*/, Packet &res) + { + res = pset1(0); + } +}; + template struct product_packet_impl { typedef typename Lhs::Index Index; static EIGEN_STRONG_INLINE void run(Index row, Index col, const Lhs& lhs, const Rhs& rhs, Packet& res) { - eigen_assert(lhs.cols()>0 && "you are using a non initialized matrix"); - res = pmul(pset1(lhs.coeff(row, 0)),rhs.template packet(0, col)); - for(Index i = 1; i < lhs.cols(); ++i) - res = pmadd(pset1(lhs.coeff(row, i)), rhs.template packet(i, col), res); + res = pset1(0); + for(Index i = 0; i < lhs.cols(); ++i) + res = pmadd(pset1(lhs.coeff(row, i)), rhs.template packet(i, col), res); } }; @@ -425,10 +463,9 @@ struct product_packet_impl typedef typename Lhs::Index Index; static EIGEN_STRONG_INLINE void run(Index row, Index col, const Lhs& lhs, const Rhs& rhs, Packet& res) { - eigen_assert(lhs.cols()>0 && "you are using a non initialized matrix"); - res = pmul(lhs.template packet(row, 0), pset1(rhs.coeff(0, col))); - for(Index i = 1; i < lhs.cols(); ++i) - res = pmadd(lhs.template packet(row, i), pset1(rhs.coeff(i, col)), res); + res = pset1(0); + for(Index i = 0; i < lhs.cols(); ++i) + res = pmadd(lhs.template packet(row, i), pset1(rhs.coeff(i, col)), res); } }; diff --git a/gtsam/3rdparty/Eigen/Eigen/src/Core/products/Parallelizer.h b/gtsam/3rdparty/Eigen/Eigen/src/Core/products/Parallelizer.h index 5c3e9b7ac..6937ee332 100644 --- a/gtsam/3rdparty/Eigen/Eigen/src/Core/products/Parallelizer.h +++ b/gtsam/3rdparty/Eigen/Eigen/src/Core/products/Parallelizer.h @@ -125,19 +125,22 @@ void parallelize_gemm(const Functor& func, Index rows, Index cols, bool transpos if(transpose) std::swap(rows,cols); - Index blockCols = (cols / threads) & ~Index(0x3); - Index blockRows = (rows / threads) & ~Index(0x7); - GemmParallelInfo* info = new GemmParallelInfo[threads]; - #pragma omp parallel for schedule(static,1) num_threads(threads) - for(Index i=0; i class Rotation2D; template class AngleAxis; template class Translation; +// Sparse module: +template class SparseMatrixBase; + #ifdef EIGEN2_SUPPORT template class eigen2_RotationBase; template class eigen2_Cross; diff --git a/gtsam/3rdparty/Eigen/Eigen/src/Core/util/MKL_support.h b/gtsam/3rdparty/Eigen/Eigen/src/Core/util/MKL_support.h index 8acca9c8c..1ef3b61db 100644 --- a/gtsam/3rdparty/Eigen/Eigen/src/Core/util/MKL_support.h +++ b/gtsam/3rdparty/Eigen/Eigen/src/Core/util/MKL_support.h @@ -76,6 +76,38 @@ #include #define EIGEN_MKL_VML_THRESHOLD 128 +/* MKL_DOMAIN_BLAS, etc are defined only in 10.3 update 7 */ +/* MKL_BLAS, etc are not defined in 11.2 */ +#ifdef MKL_DOMAIN_ALL +#define EIGEN_MKL_DOMAIN_ALL MKL_DOMAIN_ALL +#else +#define EIGEN_MKL_DOMAIN_ALL MKL_ALL +#endif + +#ifdef MKL_DOMAIN_BLAS +#define EIGEN_MKL_DOMAIN_BLAS MKL_DOMAIN_BLAS +#else +#define EIGEN_MKL_DOMAIN_BLAS MKL_BLAS +#endif + +#ifdef MKL_DOMAIN_FFT +#define EIGEN_MKL_DOMAIN_FFT MKL_DOMAIN_FFT +#else +#define EIGEN_MKL_DOMAIN_FFT MKL_FFT +#endif + +#ifdef MKL_DOMAIN_VML +#define EIGEN_MKL_DOMAIN_VML MKL_DOMAIN_VML +#else +#define EIGEN_MKL_DOMAIN_VML MKL_VML +#endif + +#ifdef MKL_DOMAIN_PARDISO +#define EIGEN_MKL_DOMAIN_PARDISO MKL_DOMAIN_PARDISO +#else +#define EIGEN_MKL_DOMAIN_PARDISO MKL_PARDISO +#endif + namespace Eigen { typedef std::complex dcomplex; diff --git a/gtsam/3rdparty/Eigen/Eigen/src/Core/util/Macros.h b/gtsam/3rdparty/Eigen/Eigen/src/Core/util/Macros.h index 6d1e6c133..53fb5fae4 100644 --- a/gtsam/3rdparty/Eigen/Eigen/src/Core/util/Macros.h +++ b/gtsam/3rdparty/Eigen/Eigen/src/Core/util/Macros.h @@ -13,7 +13,7 @@ #define EIGEN_WORLD_VERSION 3 #define EIGEN_MAJOR_VERSION 2 -#define EIGEN_MINOR_VERSION 4 +#define EIGEN_MINOR_VERSION 7 #define EIGEN_VERSION_AT_LEAST(x,y,z) (EIGEN_WORLD_VERSION>x || (EIGEN_WORLD_VERSION>=x && \ (EIGEN_MAJOR_VERSION>y || (EIGEN_MAJOR_VERSION>=y && \ @@ -96,6 +96,20 @@ #define EIGEN_DEFAULT_DENSE_INDEX_TYPE std::ptrdiff_t #endif +// A Clang feature extension to determine compiler features. +// We use it to determine 'cxx_rvalue_references' +#ifndef __has_feature +# define __has_feature(x) 0 +#endif + +// Do we support r-value references? +#if (__has_feature(cxx_rvalue_references) || \ + defined(__GXX_EXPERIMENTAL_CXX0X__) || \ + (defined(_MSC_VER) && _MSC_VER >= 1600)) + #define EIGEN_HAVE_RVALUE_REFERENCES +#endif + + // Cross compiler wrapper around LLVM's __has_builtin #ifdef __has_builtin # define EIGEN_HAS_BUILTIN(x) __has_builtin(x) @@ -278,6 +292,7 @@ namespace Eigen { #error Please tell me what is the equivalent of __attribute__((aligned(n))) for your compiler #endif +#define EIGEN_ALIGN8 EIGEN_ALIGN_TO_BOUNDARY(8) #define EIGEN_ALIGN16 EIGEN_ALIGN_TO_BOUNDARY(16) #if EIGEN_ALIGN_STATICALLY @@ -332,8 +347,11 @@ namespace Eigen { } #endif -#define EIGEN_INHERIT_ASSIGNMENT_OPERATORS(Derived) \ - EIGEN_INHERIT_ASSIGNMENT_EQUAL_OPERATOR(Derived) +/** \internal + * \brief Macro to manually inherit assignment operators. + * This is necessary, because the implicitly defined assignment operator gets deleted when a custom operator= is defined. + */ +#define EIGEN_INHERIT_ASSIGNMENT_OPERATORS(Derived) EIGEN_INHERIT_ASSIGNMENT_EQUAL_OPERATOR(Derived) /** * Just a side note. Commenting within defines works only by documenting @@ -405,6 +423,8 @@ namespace Eigen { #define EIGEN_SIZE_MAX(a,b) (((int)a == Dynamic || (int)b == Dynamic) ? Dynamic \ : ((int)a >= (int)b) ? (int)a : (int)b) +#define EIGEN_ADD_COST(a,b) int(a)==Dynamic || int(b)==Dynamic ? Dynamic : int(a)+int(b) + #define EIGEN_LOGICAL_XOR(a,b) (((a) || (b)) && !((a) && (b))) #define EIGEN_IMPLIES(a,b) (!(a) || (b)) diff --git a/gtsam/3rdparty/Eigen/Eigen/src/Core/util/Memory.h b/gtsam/3rdparty/Eigen/Eigen/src/Core/util/Memory.h index 41dd7db06..bc1ea69ed 100644 --- a/gtsam/3rdparty/Eigen/Eigen/src/Core/util/Memory.h +++ b/gtsam/3rdparty/Eigen/Eigen/src/Core/util/Memory.h @@ -523,7 +523,7 @@ template struct smart_copy_helper { // you can overwrite Eigen's default behavior regarding alloca by defining EIGEN_ALLOCA // to the appropriate stack allocation function #ifndef EIGEN_ALLOCA - #if (defined __linux__) + #if (defined __linux__) || (defined __APPLE__) || (defined alloca) #define EIGEN_ALLOCA alloca #elif defined(_MSC_VER) #define EIGEN_ALLOCA _alloca diff --git a/gtsam/3rdparty/Eigen/Eigen/src/Core/util/XprHelper.h b/gtsam/3rdparty/Eigen/Eigen/src/Core/util/XprHelper.h index 781965d2c..d05f8e5f6 100644 --- a/gtsam/3rdparty/Eigen/Eigen/src/Core/util/XprHelper.h +++ b/gtsam/3rdparty/Eigen/Eigen/src/Core/util/XprHelper.h @@ -366,17 +366,17 @@ struct dense_xpr_base /** \internal Helper base class to add a scalar multiple operator * overloads for complex types */ -template::value > -struct special_scalar_op_base : public DenseCoeffsBase +struct special_scalar_op_base : public BaseType { // dummy operator* so that the // "using special_scalar_op_base::operator*" compiles void operator*() const; }; -template -struct special_scalar_op_base : public DenseCoeffsBase +template +struct special_scalar_op_base : public BaseType { const CwiseUnaryOp, Derived> operator*(const OtherScalar& scalar) const diff --git a/gtsam/3rdparty/Eigen/Eigen/src/Eigenvalues/ComplexEigenSolver.h b/gtsam/3rdparty/Eigen/Eigen/src/Eigenvalues/ComplexEigenSolver.h index af434bc9b..417c72944 100644 --- a/gtsam/3rdparty/Eigen/Eigen/src/Eigenvalues/ComplexEigenSolver.h +++ b/gtsam/3rdparty/Eigen/Eigen/src/Eigenvalues/ComplexEigenSolver.h @@ -234,6 +234,12 @@ template class ComplexEigenSolver } protected: + + static void check_template_parameters() + { + EIGEN_STATIC_ASSERT_NON_INTEGER(Scalar); + } + EigenvectorType m_eivec; EigenvalueType m_eivalues; ComplexSchur m_schur; @@ -251,6 +257,8 @@ template ComplexEigenSolver& ComplexEigenSolver::compute(const MatrixType& matrix, bool computeEigenvectors) { + check_template_parameters(); + // this code is inspired from Jampack eigen_assert(matrix.cols() == matrix.rows()); diff --git a/gtsam/3rdparty/Eigen/Eigen/src/Eigenvalues/EigenSolver.h b/gtsam/3rdparty/Eigen/Eigen/src/Eigenvalues/EigenSolver.h index 6e7150685..20c59a7a2 100644 --- a/gtsam/3rdparty/Eigen/Eigen/src/Eigenvalues/EigenSolver.h +++ b/gtsam/3rdparty/Eigen/Eigen/src/Eigenvalues/EigenSolver.h @@ -298,6 +298,13 @@ template class EigenSolver void doComputeEigenvectors(); protected: + + static void check_template_parameters() + { + EIGEN_STATIC_ASSERT_NON_INTEGER(Scalar); + EIGEN_STATIC_ASSERT(!NumTraits::IsComplex, NUMERIC_TYPE_MUST_BE_REAL); + } + MatrixType m_eivec; EigenvalueType m_eivalues; bool m_isInitialized; @@ -364,6 +371,8 @@ template EigenSolver& EigenSolver::compute(const MatrixType& matrix, bool computeEigenvectors) { + check_template_parameters(); + using std::sqrt; using std::abs; eigen_assert(matrix.cols() == matrix.rows()); diff --git a/gtsam/3rdparty/Eigen/Eigen/src/Eigenvalues/GeneralizedEigenSolver.h b/gtsam/3rdparty/Eigen/Eigen/src/Eigenvalues/GeneralizedEigenSolver.h index dc240e13e..956e80d9e 100644 --- a/gtsam/3rdparty/Eigen/Eigen/src/Eigenvalues/GeneralizedEigenSolver.h +++ b/gtsam/3rdparty/Eigen/Eigen/src/Eigenvalues/GeneralizedEigenSolver.h @@ -263,6 +263,13 @@ template class GeneralizedEigenSolver } protected: + + static void check_template_parameters() + { + EIGEN_STATIC_ASSERT_NON_INTEGER(Scalar); + EIGEN_STATIC_ASSERT(!NumTraits::IsComplex, NUMERIC_TYPE_MUST_BE_REAL); + } + MatrixType m_eivec; ComplexVectorType m_alphas; VectorType m_betas; @@ -290,6 +297,8 @@ template GeneralizedEigenSolver& GeneralizedEigenSolver::compute(const MatrixType& A, const MatrixType& B, bool computeEigenvectors) { + check_template_parameters(); + using std::sqrt; using std::abs; eigen_assert(A.cols() == A.rows() && B.cols() == A.rows() && B.cols() == B.rows()); diff --git a/gtsam/3rdparty/Eigen/Eigen/src/Eigenvalues/RealQZ.h b/gtsam/3rdparty/Eigen/Eigen/src/Eigenvalues/RealQZ.h index 4f36091db..aa3833eba 100644 --- a/gtsam/3rdparty/Eigen/Eigen/src/Eigenvalues/RealQZ.h +++ b/gtsam/3rdparty/Eigen/Eigen/src/Eigenvalues/RealQZ.h @@ -240,10 +240,10 @@ namespace Eigen { m_S.coeffRef(i,j) = Scalar(0.0); m_S.rightCols(dim-j-1).applyOnTheLeft(i-1,i,G.adjoint()); m_T.rightCols(dim-i+1).applyOnTheLeft(i-1,i,G.adjoint()); + // update Q + if (m_computeQZ) + m_Q.applyOnTheRight(i-1,i,G); } - // update Q - if (m_computeQZ) - m_Q.applyOnTheRight(i-1,i,G); // kill T(i,i-1) if(m_T.coeff(i,i-1)!=Scalar(0)) { @@ -251,10 +251,10 @@ namespace Eigen { m_T.coeffRef(i,i-1) = Scalar(0.0); m_S.applyOnTheRight(i,i-1,G); m_T.topRows(i).applyOnTheRight(i,i-1,G); + // update Z + if (m_computeQZ) + m_Z.applyOnTheLeft(i,i-1,G.adjoint()); } - // update Z - if (m_computeQZ) - m_Z.applyOnTheLeft(i,i-1,G.adjoint()); } } } diff --git a/gtsam/3rdparty/Eigen/Eigen/src/Eigenvalues/RealSchur.h b/gtsam/3rdparty/Eigen/Eigen/src/Eigenvalues/RealSchur.h index 64d136341..16d387537 100644 --- a/gtsam/3rdparty/Eigen/Eigen/src/Eigenvalues/RealSchur.h +++ b/gtsam/3rdparty/Eigen/Eigen/src/Eigenvalues/RealSchur.h @@ -234,7 +234,7 @@ template class RealSchur typedef Matrix Vector3s; Scalar computeNormOfT(); - Index findSmallSubdiagEntry(Index iu, const Scalar& norm); + Index findSmallSubdiagEntry(Index iu); void splitOffTwoRows(Index iu, bool computeU, const Scalar& exshift); void computeShift(Index iu, Index iter, Scalar& exshift, Vector3s& shiftInfo); void initFrancisQRStep(Index il, Index iu, const Vector3s& shiftInfo, Index& im, Vector3s& firstHouseholderVector); @@ -286,7 +286,7 @@ RealSchur& RealSchur::computeFromHessenberg(const HessMa { while (iu >= 0) { - Index il = findSmallSubdiagEntry(iu, norm); + Index il = findSmallSubdiagEntry(iu); // Check for convergence if (il == iu) // One root found @@ -343,16 +343,14 @@ inline typename MatrixType::Scalar RealSchur::computeNormOfT() /** \internal Look for single small sub-diagonal element and returns its index */ template -inline typename MatrixType::Index RealSchur::findSmallSubdiagEntry(Index iu, const Scalar& norm) +inline typename MatrixType::Index RealSchur::findSmallSubdiagEntry(Index iu) { using std::abs; Index res = iu; while (res > 0) { Scalar s = abs(m_matT.coeff(res-1,res-1)) + abs(m_matT.coeff(res,res)); - if (s == 0.0) - s = norm; - if (abs(m_matT.coeff(res,res-1)) < NumTraits::epsilon() * s) + if (abs(m_matT.coeff(res,res-1)) <= NumTraits::epsilon() * s) break; res--; } @@ -457,9 +455,7 @@ inline void RealSchur::initFrancisQRStep(Index il, Index iu, const V const Scalar lhs = m_matT.coeff(im,im-1) * (abs(v.coeff(1)) + abs(v.coeff(2))); const Scalar rhs = v.coeff(0) * (abs(m_matT.coeff(im-1,im-1)) + abs(Tmm) + abs(m_matT.coeff(im+1,im+1))); if (abs(lhs) < NumTraits::epsilon() * rhs) - { break; - } } } diff --git a/gtsam/3rdparty/Eigen/Eigen/src/Eigenvalues/SelfAdjointEigenSolver.h b/gtsam/3rdparty/Eigen/Eigen/src/Eigenvalues/SelfAdjointEigenSolver.h index be89de4a9..1131c8af8 100644 --- a/gtsam/3rdparty/Eigen/Eigen/src/Eigenvalues/SelfAdjointEigenSolver.h +++ b/gtsam/3rdparty/Eigen/Eigen/src/Eigenvalues/SelfAdjointEigenSolver.h @@ -80,6 +80,8 @@ template class SelfAdjointEigenSolver /** \brief Scalar type for matrices of type \p _MatrixType. */ typedef typename MatrixType::Scalar Scalar; typedef typename MatrixType::Index Index; + + typedef Matrix EigenvectorsType; /** \brief Real scalar type for \p _MatrixType. * @@ -225,7 +227,7 @@ template class SelfAdjointEigenSolver * * \sa eigenvalues() */ - const MatrixType& eigenvectors() const + const EigenvectorsType& eigenvectors() const { eigen_assert(m_isInitialized && "SelfAdjointEigenSolver is not initialized."); eigen_assert(m_eigenvectorsOk && "The eigenvectors have not been computed together with the eigenvalues."); @@ -351,7 +353,12 @@ template class SelfAdjointEigenSolver #endif // EIGEN2_SUPPORT protected: - MatrixType m_eivec; + static void check_template_parameters() + { + EIGEN_STATIC_ASSERT_NON_INTEGER(Scalar); + } + + EigenvectorsType m_eivec; RealVectorType m_eivalues; typename TridiagonalizationType::SubDiagonalType m_subdiag; ComputationInfo m_info; @@ -376,7 +383,7 @@ template class SelfAdjointEigenSolver * "implicit symmetric QR step with Wilkinson shift" */ namespace internal { -template +template static void tridiagonal_qr_step(RealScalar* diag, RealScalar* subdiag, Index start, Index end, Scalar* matrixQ, Index n); } @@ -384,6 +391,8 @@ template SelfAdjointEigenSolver& SelfAdjointEigenSolver ::compute(const MatrixType& matrix, int options) { + check_template_parameters(); + using std::abs; eigen_assert(matrix.cols() == matrix.rows()); eigen_assert((options&~(EigVecMask|GenEigMask))==0 @@ -406,7 +415,7 @@ SelfAdjointEigenSolver& SelfAdjointEigenSolver // declare some aliases RealVectorType& diag = m_eivalues; - MatrixType& mat = m_eivec; + EigenvectorsType& mat = m_eivec; // map the matrix coefficients to [-1:1] to avoid over- and underflow. mat = matrix.template triangularView(); @@ -442,7 +451,7 @@ SelfAdjointEigenSolver& SelfAdjointEigenSolver while (start>0 && m_subdiag[start-1]!=0) start--; - internal::tridiagonal_qr_step(diag.data(), m_subdiag.data(), start, end, computeEigenvectors ? m_eivec.data() : (Scalar*)0, n); + internal::tridiagonal_qr_step(diag.data(), m_subdiag.data(), start, end, computeEigenvectors ? m_eivec.data() : (Scalar*)0, n); } if (iter <= m_maxIterations * n) @@ -490,7 +499,13 @@ template struct direct_selfadjoint_eigenvalues struct direct_selfadjoint_eigenvalues Scalar(0)) + Scalar a_over_3 = (c2*c2_over_3 - c1)*s_inv3; + if(a_over_3 Scalar(0)) + Scalar q = a_over_3*a_over_3*a_over_3 - half_b*half_b; + if(q 0, atan2 is in [0, pi] and theta is in [0, pi/3] Scalar cos_theta = cos(theta); Scalar sin_theta = sin(theta); - roots(0) = c2_over_3 + Scalar(2)*rho*cos_theta; - roots(1) = c2_over_3 - rho*(cos_theta + s_sqrt3*sin_theta); - roots(2) = c2_over_3 - rho*(cos_theta - s_sqrt3*sin_theta); - - // Sort in increasing order. - if (roots(0) >= roots(1)) - std::swap(roots(0),roots(1)); - if (roots(1) >= roots(2)) - { - std::swap(roots(1),roots(2)); - if (roots(0) >= roots(1)) - std::swap(roots(0),roots(1)); - } + // roots are already sorted, since cos is monotonically decreasing on [0, pi] + roots(0) = c2_over_3 - rho*(cos_theta + s_sqrt3*sin_theta); // == 2*rho*cos(theta+2pi/3) + roots(1) = c2_over_3 - rho*(cos_theta - s_sqrt3*sin_theta); // == 2*rho*cos(theta+ pi/3) + roots(2) = c2_over_3 + Scalar(2)*rho*cos_theta; } - + + static inline bool extract_kernel(MatrixType& mat, Ref res, Ref representative) + { + using std::abs; + Index i0; + // Find non-zero column i0 (by construction, there must exist a non zero coefficient on the diagonal): + mat.diagonal().cwiseAbs().maxCoeff(&i0); + // mat.col(i0) is a good candidate for an orthogonal vector to the current eigenvector, + // so let's save it: + representative = mat.col(i0); + Scalar n0, n1; + VectorType c0, c1; + n0 = (c0 = representative.cross(mat.col((i0+1)%3))).squaredNorm(); + n1 = (c1 = representative.cross(mat.col((i0+2)%3))).squaredNorm(); + if(n0>n1) res = c0/std::sqrt(n0); + else res = c1/std::sqrt(n1); + + return true; + } + static inline void run(SolverType& solver, const MatrixType& mat, int options) { - using std::sqrt; eigen_assert(mat.cols() == 3 && mat.cols() == mat.rows()); eigen_assert((options&~(EigVecMask|GenEigMask))==0 && (options&EigVecMask)!=EigVecMask && "invalid option parameter"); bool computeEigenvectors = (options&ComputeEigenvectors)==ComputeEigenvectors; - MatrixType& eivecs = solver.m_eivec; + EigenvectorsType& eivecs = solver.m_eivec; VectorType& eivals = solver.m_eivalues; - // map the matrix coefficients to [-1:1] to avoid over- and underflow. - Scalar scale = mat.cwiseAbs().maxCoeff(); - MatrixType scaledMat = mat / scale; + // Shift the matrix to the mean eigenvalue and map the matrix coefficients to [-1:1] to avoid over- and underflow. + Scalar shift = mat.trace() / Scalar(3); + // TODO Avoid this copy. Currently it is necessary to suppress bogus values when determining maxCoeff and for computing the eigenvectors later + MatrixType scaledMat = mat.template selfadjointView(); + scaledMat.diagonal().array() -= shift; + Scalar scale = scaledMat.cwiseAbs().maxCoeff(); + if(scale > 0) scaledMat /= scale; // TODO for scale==0 we could save the remaining operations // compute the eigenvalues computeRoots(scaledMat,eivals); - // compute the eigen vectors + // compute the eigenvectors if(computeEigenvectors) { - Scalar safeNorm2 = Eigen::NumTraits::epsilon(); if((eivals(2)-eivals(0))<=Eigen::NumTraits::epsilon()) { + // All three eigenvalues are numerically the same eivecs.setIdentity(); } else { - scaledMat = scaledMat.template selfadjointView(); MatrixType tmp; tmp = scaledMat; + // Compute the eigenvector of the most distinct eigenvalue Scalar d0 = eivals(2) - eivals(1); Scalar d1 = eivals(1) - eivals(0); - int k = d0 > d1 ? 2 : 0; - d0 = d0 > d1 ? d0 : d1; - - tmp.diagonal().array () -= eivals(k); - VectorType cross; - Scalar n; - n = (cross = tmp.row(0).cross(tmp.row(1))).squaredNorm(); - - if(n>safeNorm2) + Index k(0), l(2); + if(d0 > d1) { - eivecs.col(k) = cross / sqrt(n); + std::swap(k,l); + d0 = d1; + } + + // Compute the eigenvector of index k + { + tmp.diagonal().array () -= eivals(k); + // By construction, 'tmp' is of rank 2, and its kernel corresponds to the respective eigenvector. + extract_kernel(tmp, eivecs.col(k), eivecs.col(l)); + } + + // Compute eigenvector of index l + if(d0<=2*Eigen::NumTraits::epsilon()*d1) + { + // If d0 is too small, then the two other eigenvalues are numerically the same, + // and thus we only have to ortho-normalize the near orthogonal vector we saved above. + eivecs.col(l) -= eivecs.col(k).dot(eivecs.col(l))*eivecs.col(l); + eivecs.col(l).normalize(); } else { - n = (cross = tmp.row(0).cross(tmp.row(2))).squaredNorm(); + tmp = scaledMat; + tmp.diagonal().array () -= eivals(l); - if(n>safeNorm2) - { - eivecs.col(k) = cross / sqrt(n); - } - else - { - n = (cross = tmp.row(1).cross(tmp.row(2))).squaredNorm(); - - if(n>safeNorm2) - { - eivecs.col(k) = cross / sqrt(n); - } - else - { - // the input matrix and/or the eigenvaues probably contains some inf/NaN, - // => exit - // scale back to the original size. - eivals *= scale; - - solver.m_info = NumericalIssue; - solver.m_isInitialized = true; - solver.m_eigenvectorsOk = computeEigenvectors; - return; - } - } + VectorType dummy; + extract_kernel(tmp, eivecs.col(l), dummy); } - tmp = scaledMat; - tmp.diagonal().array() -= eivals(1); - - if(d0<=Eigen::NumTraits::epsilon()) - { - eivecs.col(1) = eivecs.col(k).unitOrthogonal(); - } - else - { - n = (cross = eivecs.col(k).cross(tmp.row(0))).squaredNorm(); - if(n>safeNorm2) - { - eivecs.col(1) = cross / sqrt(n); - } - else - { - n = (cross = eivecs.col(k).cross(tmp.row(1))).squaredNorm(); - if(n>safeNorm2) - eivecs.col(1) = cross / sqrt(n); - else - { - n = (cross = eivecs.col(k).cross(tmp.row(2))).squaredNorm(); - if(n>safeNorm2) - eivecs.col(1) = cross / sqrt(n); - else - { - // we should never reach this point, - // if so the last two eigenvalues are likely to be very close to each other - eivecs.col(1) = eivecs.col(k).unitOrthogonal(); - } - } - } - - // make sure that eivecs[1] is orthogonal to eivecs[2] - // FIXME: this step should not be needed - Scalar d = eivecs.col(1).dot(eivecs.col(k)); - eivecs.col(1) = (eivecs.col(1) - d * eivecs.col(k)).normalized(); - } - - eivecs.col(k==2 ? 0 : 2) = eivecs.col(k).cross(eivecs.col(1)).normalized(); + // Compute last eigenvector from the other two + eivecs.col(1) = eivecs.col(2).cross(eivecs.col(0)).normalized(); } } + // Rescale back to the original size. eivals *= scale; + eivals.array() += shift; solver.m_info = Success; solver.m_isInitialized = true; @@ -675,11 +655,12 @@ template struct direct_selfadjoint_eigenvalues struct direct_selfadjoint_eigenvalues struct direct_selfadjoint_eigenvaluesc2) + if((eivals(1)-eivals(0))<=abs(eivals(1))*Eigen::NumTraits::epsilon()) { - eivecs.col(1) << -scaledMat(1,0), scaledMat(0,0); - eivecs.col(1) /= sqrt(a2+b2); + eivecs.setIdentity(); } else { - eivecs.col(1) << -scaledMat(1,1), scaledMat(1,0); - eivecs.col(1) /= sqrt(c2+b2); - } + scaledMat.diagonal().array () -= eivals(1); + Scalar a2 = numext::abs2(scaledMat(0,0)); + Scalar c2 = numext::abs2(scaledMat(1,1)); + Scalar b2 = numext::abs2(scaledMat(1,0)); + if(a2>c2) + { + eivecs.col(1) << -scaledMat(1,0), scaledMat(0,0); + eivecs.col(1) /= sqrt(a2+b2); + } + else + { + eivecs.col(1) << -scaledMat(1,1), scaledMat(1,0); + eivecs.col(1) /= sqrt(c2+b2); + } - eivecs.col(0) << eivecs.col(1).unitOrthogonal(); + eivecs.col(0) << eivecs.col(1).unitOrthogonal(); + } } // Rescale back to the original size. @@ -746,7 +736,7 @@ SelfAdjointEigenSolver& SelfAdjointEigenSolver } namespace internal { -template +template static void tridiagonal_qr_step(RealScalar* diag, RealScalar* subdiag, Index start, Index end, Scalar* matrixQ, Index n) { using std::abs; @@ -798,8 +788,7 @@ static void tridiagonal_qr_step(RealScalar* diag, RealScalar* subdiag, Index sta // apply the givens rotation to the unit matrix Q = Q * G if (matrixQ) { - // FIXME if StorageOrder == RowMajor this operation is not very efficient - Map > q(matrixQ,n,n); + Map > q(matrixQ,n,n); q.applyOnTheRight(k,k+1,rot); } } diff --git a/gtsam/3rdparty/Eigen/Eigen/src/Geometry/AlignedBox.h b/gtsam/3rdparty/Eigen/Eigen/src/Geometry/AlignedBox.h index 8e186d57a..7e1cd9eb7 100644 --- a/gtsam/3rdparty/Eigen/Eigen/src/Geometry/AlignedBox.h +++ b/gtsam/3rdparty/Eigen/Eigen/src/Geometry/AlignedBox.h @@ -19,10 +19,12 @@ namespace Eigen { * * \brief An axis aligned box * - * \param _Scalar the type of the scalar coefficients - * \param _AmbientDim the dimension of the ambient space, can be a compile time value or Dynamic. + * \tparam _Scalar the type of the scalar coefficients + * \tparam _AmbientDim the dimension of the ambient space, can be a compile time value or Dynamic. * * This class represents an axis aligned box as a pair of the minimal and maximal corners. + * \warning The result of most methods is undefined when applied to an empty box. You can check for empty boxes using isEmpty(). + * \sa alignedboxtypedefs */ template class AlignedBox @@ -40,18 +42,21 @@ EIGEN_MAKE_ALIGNED_OPERATOR_NEW_IF_VECTORIZABLE_FIXED_SIZE(_Scalar,_AmbientDim) /** Define constants to name the corners of a 1D, 2D or 3D axis aligned bounding box */ enum CornerType { - /** 1D names */ + /** 1D names @{ */ Min=0, Max=1, + /** @} */ - /** Added names for 2D */ + /** Identifier for 2D corner @{ */ BottomLeft=0, BottomRight=1, TopLeft=2, TopRight=3, + /** @} */ - /** Added names for 3D */ + /** Identifier for 3D corner @{ */ BottomLeftFloor=0, BottomRightFloor=1, TopLeftFloor=2, TopRightFloor=3, BottomLeftCeil=4, BottomRightCeil=5, TopLeftCeil=6, TopRightCeil=7 + /** @} */ }; @@ -63,34 +68,33 @@ EIGEN_MAKE_ALIGNED_OPERATOR_NEW_IF_VECTORIZABLE_FIXED_SIZE(_Scalar,_AmbientDim) inline explicit AlignedBox(Index _dim) : m_min(_dim), m_max(_dim) { setEmpty(); } - /** Constructs a box with extremities \a _min and \a _max. */ + /** Constructs a box with extremities \a _min and \a _max. + * \warning If either component of \a _min is larger than the same component of \a _max, the constructed box is empty. */ template inline AlignedBox(const OtherVectorType1& _min, const OtherVectorType2& _max) : m_min(_min), m_max(_max) {} /** Constructs a box containing a single point \a p. */ template - inline explicit AlignedBox(const MatrixBase& a_p) - { - typename internal::nested::type p(a_p.derived()); - m_min = p; - m_max = p; - } + inline explicit AlignedBox(const MatrixBase& p) : m_min(p), m_max(m_min) + { } ~AlignedBox() {} /** \returns the dimension in which the box holds */ inline Index dim() const { return AmbientDimAtCompileTime==Dynamic ? m_min.size() : Index(AmbientDimAtCompileTime); } - /** \deprecated use isEmpty */ + /** \deprecated use isEmpty() */ inline bool isNull() const { return isEmpty(); } - /** \deprecated use setEmpty */ + /** \deprecated use setEmpty() */ inline void setNull() { setEmpty(); } - /** \returns true if the box is empty. */ + /** \returns true if the box is empty. + * \sa setEmpty */ inline bool isEmpty() const { return (m_min.array() > m_max.array()).any(); } - /** Makes \c *this an empty box. */ + /** Makes \c *this an empty box. + * \sa isEmpty */ inline void setEmpty() { m_min.setConstant( ScalarTraits::highest() ); @@ -159,7 +163,7 @@ EIGEN_MAKE_ALIGNED_OPERATOR_NEW_IF_VECTORIZABLE_FIXED_SIZE(_Scalar,_AmbientDim) * a uniform distribution */ inline VectorType sample() const { - VectorType r; + VectorType r(dim()); for(Index d=0; d - inline bool contains(const MatrixBase& a_p) const + inline bool contains(const MatrixBase& p) const { - typename internal::nested::type p(a_p.derived()); - return (m_min.array()<=p.array()).all() && (p.array()<=m_max.array()).all(); + typename internal::nested::type p_n(p.derived()); + return (m_min.array()<=p_n.array()).all() && (p_n.array()<=m_max.array()).all(); } /** \returns true if the box \a b is entirely inside the box \c *this. */ inline bool contains(const AlignedBox& b) const { return (m_min.array()<=(b.min)().array()).all() && ((b.max)().array()<=m_max.array()).all(); } - /** Extends \c *this such that it contains the point \a p and returns a reference to \c *this. */ + /** \returns true if the box \a b is intersecting the box \c *this. + * \sa intersection, clamp */ + inline bool intersects(const AlignedBox& b) const + { return (m_min.array()<=(b.max)().array()).all() && ((b.min)().array()<=m_max.array()).all(); } + + /** Extends \c *this such that it contains the point \a p and returns a reference to \c *this. + * \sa extend(const AlignedBox&) */ template - inline AlignedBox& extend(const MatrixBase& a_p) + inline AlignedBox& extend(const MatrixBase& p) { - typename internal::nested::type p(a_p.derived()); - m_min = m_min.cwiseMin(p); - m_max = m_max.cwiseMax(p); + typename internal::nested::type p_n(p.derived()); + m_min = m_min.cwiseMin(p_n); + m_max = m_max.cwiseMax(p_n); return *this; } - /** Extends \c *this such that it contains the box \a b and returns a reference to \c *this. */ + /** Extends \c *this such that it contains the box \a b and returns a reference to \c *this. + * \sa merged, extend(const MatrixBase&) */ inline AlignedBox& extend(const AlignedBox& b) { m_min = m_min.cwiseMin(b.m_min); @@ -203,7 +214,9 @@ EIGEN_MAKE_ALIGNED_OPERATOR_NEW_IF_VECTORIZABLE_FIXED_SIZE(_Scalar,_AmbientDim) return *this; } - /** Clamps \c *this by the box \a b and returns a reference to \c *this. */ + /** Clamps \c *this by the box \a b and returns a reference to \c *this. + * \note If the boxes don't intersect, the resulting box is empty. + * \sa intersection(), intersects() */ inline AlignedBox& clamp(const AlignedBox& b) { m_min = m_min.cwiseMax(b.m_min); @@ -211,11 +224,15 @@ EIGEN_MAKE_ALIGNED_OPERATOR_NEW_IF_VECTORIZABLE_FIXED_SIZE(_Scalar,_AmbientDim) return *this; } - /** Returns an AlignedBox that is the intersection of \a b and \c *this */ + /** Returns an AlignedBox that is the intersection of \a b and \c *this + * \note If the boxes don't intersect, the resulting box is empty. + * \sa intersects(), clamp, contains() */ inline AlignedBox intersection(const AlignedBox& b) const {return AlignedBox(m_min.cwiseMax(b.m_min), m_max.cwiseMin(b.m_max)); } - /** Returns an AlignedBox that is the union of \a b and \c *this */ + /** Returns an AlignedBox that is the union of \a b and \c *this. + * \note Merging with an empty box may result in a box bigger than \c *this. + * \sa extend(const AlignedBox&) */ inline AlignedBox merged(const AlignedBox& b) const { return AlignedBox(m_min.cwiseMin(b.m_min), m_max.cwiseMax(b.m_max)); } @@ -231,20 +248,20 @@ EIGEN_MAKE_ALIGNED_OPERATOR_NEW_IF_VECTORIZABLE_FIXED_SIZE(_Scalar,_AmbientDim) /** \returns the squared distance between the point \a p and the box \c *this, * and zero if \a p is inside the box. - * \sa exteriorDistance() + * \sa exteriorDistance(const MatrixBase&), squaredExteriorDistance(const AlignedBox&) */ template - inline Scalar squaredExteriorDistance(const MatrixBase& a_p) const; + inline Scalar squaredExteriorDistance(const MatrixBase& p) const; /** \returns the squared distance between the boxes \a b and \c *this, * and zero if the boxes intersect. - * \sa exteriorDistance() + * \sa exteriorDistance(const AlignedBox&), squaredExteriorDistance(const MatrixBase&) */ inline Scalar squaredExteriorDistance(const AlignedBox& b) const; /** \returns the distance between the point \a p and the box \c *this, * and zero if \a p is inside the box. - * \sa squaredExteriorDistance() + * \sa squaredExteriorDistance(const MatrixBase&), exteriorDistance(const AlignedBox&) */ template inline NonInteger exteriorDistance(const MatrixBase& p) const @@ -252,7 +269,7 @@ EIGEN_MAKE_ALIGNED_OPERATOR_NEW_IF_VECTORIZABLE_FIXED_SIZE(_Scalar,_AmbientDim) /** \returns the distance between the boxes \a b and \c *this, * and zero if the boxes intersect. - * \sa squaredExteriorDistance() + * \sa squaredExteriorDistance(const AlignedBox&), exteriorDistance(const MatrixBase&) */ inline NonInteger exteriorDistance(const AlignedBox& b) const { using std::sqrt; return sqrt(NonInteger(squaredExteriorDistance(b))); } diff --git a/gtsam/3rdparty/Eigen/Eigen/src/Geometry/AngleAxis.h b/gtsam/3rdparty/Eigen/Eigen/src/Geometry/AngleAxis.h index 553d38c74..bbf6a7ed8 100644 --- a/gtsam/3rdparty/Eigen/Eigen/src/Geometry/AngleAxis.h +++ b/gtsam/3rdparty/Eigen/Eigen/src/Geometry/AngleAxis.h @@ -131,7 +131,7 @@ public: m_angle = Scalar(other.angle()); } - static inline const AngleAxis Identity() { return AngleAxis(0, Vector3::UnitX()); } + static inline const AngleAxis Identity() { return AngleAxis(Scalar(0), Vector3::UnitX()); } /** \returns \c true if \c *this is approximately equal to \a other, within the precision * determined by \a prec. @@ -165,8 +165,8 @@ AngleAxis& AngleAxis::operator=(const QuaternionBase::dummy_precision()*NumTraits::dummy_precision()) { - m_angle = 0; - m_axis << 1, 0, 0; + m_angle = Scalar(0); + m_axis << Scalar(1), Scalar(0), Scalar(0); } else { diff --git a/gtsam/3rdparty/Eigen/Eigen/src/Geometry/Homogeneous.h b/gtsam/3rdparty/Eigen/Eigen/src/Geometry/Homogeneous.h index 00e71d190..372e422b9 100644 --- a/gtsam/3rdparty/Eigen/Eigen/src/Geometry/Homogeneous.h +++ b/gtsam/3rdparty/Eigen/Eigen/src/Geometry/Homogeneous.h @@ -79,7 +79,7 @@ template class Homogeneous { if( (int(Direction)==Vertical && row==m_matrix.rows()) || (int(Direction)==Horizontal && col==m_matrix.cols())) - return 1; + return Scalar(1); return m_matrix.coeff(row, col); } diff --git a/gtsam/3rdparty/Eigen/Eigen/src/Geometry/Quaternion.h b/gtsam/3rdparty/Eigen/Eigen/src/Geometry/Quaternion.h index f06653f1c..25ed17bb6 100644 --- a/gtsam/3rdparty/Eigen/Eigen/src/Geometry/Quaternion.h +++ b/gtsam/3rdparty/Eigen/Eigen/src/Geometry/Quaternion.h @@ -102,11 +102,11 @@ public: /** \returns a quaternion representing an identity rotation * \sa MatrixBase::Identity() */ - static inline Quaternion Identity() { return Quaternion(1, 0, 0, 0); } + static inline Quaternion Identity() { return Quaternion(Scalar(1), Scalar(0), Scalar(0), Scalar(0)); } /** \sa QuaternionBase::Identity(), MatrixBase::setIdentity() */ - inline QuaternionBase& setIdentity() { coeffs() << 0, 0, 0, 1; return *this; } + inline QuaternionBase& setIdentity() { coeffs() << Scalar(0), Scalar(0), Scalar(0), Scalar(1); return *this; } /** \returns the squared norm of the quaternion's coefficients * \sa QuaternionBase::norm(), MatrixBase::squaredNorm() @@ -161,7 +161,7 @@ public: { return coeffs().isApprox(other.coeffs(), prec); } /** return the result vector of \a v through the rotation*/ - EIGEN_STRONG_INLINE Vector3 _transformVector(Vector3 v) const; + EIGEN_STRONG_INLINE Vector3 _transformVector(const Vector3& v) const; /** \returns \c *this with scalar type casted to \a NewScalarType * @@ -231,7 +231,7 @@ class Quaternion : public QuaternionBase > public: typedef _Scalar Scalar; - EIGEN_INHERIT_ASSIGNMENT_EQUAL_OPERATOR(Quaternion) + EIGEN_INHERIT_ASSIGNMENT_OPERATORS(Quaternion) using Base::operator*=; typedef typename internal::traits::Coefficients Coefficients; @@ -341,7 +341,7 @@ class Map, _Options > public: typedef _Scalar Scalar; typedef typename internal::traits::Coefficients Coefficients; - EIGEN_INHERIT_ASSIGNMENT_EQUAL_OPERATOR(Map) + EIGEN_INHERIT_ASSIGNMENT_OPERATORS(Map) using Base::operator*=; /** Constructs a Mapped Quaternion object from the pointer \a coeffs @@ -378,7 +378,7 @@ class Map, _Options > public: typedef _Scalar Scalar; typedef typename internal::traits::Coefficients Coefficients; - EIGEN_INHERIT_ASSIGNMENT_EQUAL_OPERATOR(Map) + EIGEN_INHERIT_ASSIGNMENT_OPERATORS(Map) using Base::operator*=; /** Constructs a Mapped Quaternion object from the pointer \a coeffs @@ -461,7 +461,7 @@ EIGEN_STRONG_INLINE Derived& QuaternionBase::operator*= (const Quaterni */ template EIGEN_STRONG_INLINE typename QuaternionBase::Vector3 -QuaternionBase::_transformVector(Vector3 v) const +QuaternionBase::_transformVector(const Vector3& v) const { // Note that this algorithm comes from the optimization by hand // of the conversion to a Matrix followed by a Matrix/Vector product. @@ -637,7 +637,7 @@ inline Quaternion::Scalar> QuaternionBasesquaredNorm(); - if (n2 > 0) + if (n2 > Scalar(0)) return Quaternion(conjugate().coeffs() / n2); else { @@ -667,12 +667,10 @@ template inline typename internal::traits::Scalar QuaternionBase::angularDistance(const QuaternionBase& other) const { - using std::acos; + using std::atan2; using std::abs; - Scalar d = abs(this->dot(other)); - if (d>=Scalar(1)) - return Scalar(0); - return Scalar(2) * acos(d); + Quaternion d = (*this) * other.conjugate(); + return Scalar(2) * atan2( d.vec().norm(), abs(d.w()) ); } @@ -712,7 +710,7 @@ QuaternionBase::slerp(const Scalar& t, const QuaternionBase(scale0 * coeffs() + scale1 * other.coeffs()); } diff --git a/gtsam/3rdparty/Eigen/Eigen/src/IterativeLinearSolvers/BasicPreconditioners.h b/gtsam/3rdparty/Eigen/Eigen/src/IterativeLinearSolvers/BasicPreconditioners.h index 73ca9bfde..1f3c060d0 100644 --- a/gtsam/3rdparty/Eigen/Eigen/src/IterativeLinearSolvers/BasicPreconditioners.h +++ b/gtsam/3rdparty/Eigen/Eigen/src/IterativeLinearSolvers/BasicPreconditioners.h @@ -65,10 +65,10 @@ class DiagonalPreconditioner { typename MatType::InnerIterator it(mat,j); while(it && it.index()!=j) ++it; - if(it && it.index()==j) + if(it && it.index()==j && it.value()!=Scalar(0)) m_invdiag(j) = Scalar(1)/it.value(); else - m_invdiag(j) = 0; + m_invdiag(j) = Scalar(1); } m_isInitialized = true; return *this; diff --git a/gtsam/3rdparty/Eigen/Eigen/src/IterativeLinearSolvers/BiCGSTAB.h b/gtsam/3rdparty/Eigen/Eigen/src/IterativeLinearSolvers/BiCGSTAB.h index dd135c21f..551221907 100644 --- a/gtsam/3rdparty/Eigen/Eigen/src/IterativeLinearSolvers/BiCGSTAB.h +++ b/gtsam/3rdparty/Eigen/Eigen/src/IterativeLinearSolvers/BiCGSTAB.h @@ -151,20 +151,7 @@ struct traits > * \endcode * * By default the iterations start with x=0 as an initial guess of the solution. - * One can control the start using the solveWithGuess() method. Here is a step by - * step execution example starting with a random guess and printing the evolution - * of the estimated error: - * * \code - * x = VectorXd::Random(n); - * solver.setMaxIterations(1); - * int i = 0; - * do { - * x = solver.solveWithGuess(b,x); - * std::cout << i << " : " << solver.error() << std::endl; - * ++i; - * } while (solver.info()!=Success && i<100); - * \endcode - * Note that such a step by step excution is slightly slower. + * One can control the start using the solveWithGuess() method. * * \sa class SimplicialCholesky, DiagonalPreconditioner, IdentityPreconditioner */ @@ -199,7 +186,8 @@ public: * this class becomes invalid. Call compute() to update it with the new * matrix A, or modify a copy of A. */ - BiCGSTAB(const MatrixType& A) : Base(A) {} + template + explicit BiCGSTAB(const EigenBase& A) : Base(A.derived()) {} ~BiCGSTAB() {} diff --git a/gtsam/3rdparty/Eigen/Eigen/src/IterativeLinearSolvers/ConjugateGradient.h b/gtsam/3rdparty/Eigen/Eigen/src/IterativeLinearSolvers/ConjugateGradient.h index a74a8155e..1a7e569c8 100644 --- a/gtsam/3rdparty/Eigen/Eigen/src/IterativeLinearSolvers/ConjugateGradient.h +++ b/gtsam/3rdparty/Eigen/Eigen/src/IterativeLinearSolvers/ConjugateGradient.h @@ -112,9 +112,9 @@ struct traits > * This class allows to solve for A.x = b sparse linear problems using a conjugate gradient algorithm. * The sparse matrix A must be selfadjoint. The vectors x and b can be either dense or sparse. * - * \tparam _MatrixType the type of the sparse matrix A, can be a dense or a sparse matrix. - * \tparam _UpLo the triangular part that will be used for the computations. It can be Lower - * or Upper. Default is Lower. + * \tparam _MatrixType the type of the matrix A, can be a dense or a sparse matrix. + * \tparam _UpLo the triangular part that will be used for the computations. It can be Lower, + * Upper, or Lower|Upper in which the full matrix entries will be considered. Default is Lower. * \tparam _Preconditioner the type of the preconditioner. Default is DiagonalPreconditioner * * The maximal number of iterations and tolerance value can be controlled via the setMaxIterations() @@ -137,20 +137,7 @@ struct traits > * \endcode * * By default the iterations start with x=0 as an initial guess of the solution. - * One can control the start using the solveWithGuess() method. Here is a step by - * step execution example starting with a random guess and printing the evolution - * of the estimated error: - * * \code - * x = VectorXd::Random(n); - * cg.setMaxIterations(1); - * int i = 0; - * do { - * x = cg.solveWithGuess(b,x); - * std::cout << i << " : " << cg.error() << std::endl; - * ++i; - * } while (cg.info()!=Success && i<100); - * \endcode - * Note that such a step by step excution is slightly slower. + * One can control the start using the solveWithGuess() method. * * \sa class SimplicialCholesky, DiagonalPreconditioner, IdentityPreconditioner */ @@ -189,7 +176,8 @@ public: * this class becomes invalid. Call compute() to update it with the new * matrix A, or modify a copy of A. */ - ConjugateGradient(const MatrixType& A) : Base(A) {} + template + explicit ConjugateGradient(const EigenBase& A) : Base(A.derived()) {} ~ConjugateGradient() {} @@ -213,6 +201,10 @@ public: template void _solveWithGuess(const Rhs& b, Dest& x) const { + typedef typename internal::conditional + >::type MatrixWrapperType; m_iterations = Base::maxIterations(); m_error = Base::m_tolerance; @@ -222,8 +214,7 @@ public: m_error = Base::m_tolerance; typename Dest::ColXpr xj(x,j); - internal::conjugate_gradient(mp_matrix->template selfadjointView(), b.col(j), xj, - Base::m_preconditioner, m_iterations, m_error); + internal::conjugate_gradient(MatrixWrapperType(*mp_matrix), b.col(j), xj, Base::m_preconditioner, m_iterations, m_error); } m_isInitialized = true; @@ -234,7 +225,7 @@ public: template void _solve(const Rhs& b, Dest& x) const { - x.setOnes(); + x.setZero(); _solveWithGuess(b,x); } diff --git a/gtsam/3rdparty/Eigen/Eigen/src/IterativeLinearSolvers/IncompleteLUT.h b/gtsam/3rdparty/Eigen/Eigen/src/IterativeLinearSolvers/IncompleteLUT.h index b55afc136..d3f37fea2 100644 --- a/gtsam/3rdparty/Eigen/Eigen/src/IterativeLinearSolvers/IncompleteLUT.h +++ b/gtsam/3rdparty/Eigen/Eigen/src/IterativeLinearSolvers/IncompleteLUT.h @@ -150,7 +150,6 @@ class IncompleteLUT : internal::noncopyable { analyzePattern(amat); factorize(amat); - m_isInitialized = m_factorizationIsOk; return *this; } @@ -160,7 +159,7 @@ class IncompleteLUT : internal::noncopyable template void _solve(const Rhs& b, Dest& x) const { - x = m_Pinv * b; + x = m_Pinv * b; x = m_lu.template triangularView().solve(x); x = m_lu.template triangularView().solve(x); x = m_P * x; @@ -223,18 +222,29 @@ template void IncompleteLUT::analyzePattern(const _MatrixType& amat) { // Compute the Fill-reducing permutation + // Since ILUT does not perform any numerical pivoting, + // it is highly preferable to keep the diagonal through symmetric permutations. +#ifndef EIGEN_MPL2_ONLY + // To this end, let's symmetrize the pattern and perform AMD on it. SparseMatrix mat1 = amat; SparseMatrix mat2 = amat.transpose(); - // Symmetrize the pattern // FIXME for a matrix with nearly symmetric pattern, mat2+mat1 is the appropriate choice. // on the other hand for a really non-symmetric pattern, mat2*mat1 should be prefered... SparseMatrix AtA = mat2 + mat1; - AtA.prune(keep_diag()); - internal::minimum_degree_ordering(AtA, m_P); // Then compute the AMD ordering... - - m_Pinv = m_P.inverse(); // ... and the inverse permutation + AMDOrdering ordering; + ordering(AtA,m_P); + m_Pinv = m_P.inverse(); // cache the inverse permutation +#else + // If AMD is not available, (MPL2-only), then let's use the slower COLAMD routine. + SparseMatrix mat1 = amat; + COLAMDOrdering ordering; + ordering(mat1,m_Pinv); + m_P = m_Pinv.inverse(); +#endif m_analysisIsOk = true; + m_factorizationIsOk = false; + m_isInitialized = false; } template @@ -442,6 +452,7 @@ void IncompleteLUT::factorize(const _MatrixType& amat) m_lu.makeCompressed(); m_factorizationIsOk = true; + m_isInitialized = m_factorizationIsOk; m_info = Success; } diff --git a/gtsam/3rdparty/Eigen/Eigen/src/IterativeLinearSolvers/IterativeSolverBase.h b/gtsam/3rdparty/Eigen/Eigen/src/IterativeLinearSolvers/IterativeSolverBase.h index 2036922d6..501ef2f8d 100644 --- a/gtsam/3rdparty/Eigen/Eigen/src/IterativeLinearSolvers/IterativeSolverBase.h +++ b/gtsam/3rdparty/Eigen/Eigen/src/IterativeLinearSolvers/IterativeSolverBase.h @@ -49,10 +49,11 @@ public: * this class becomes invalid. Call compute() to update it with the new * matrix A, or modify a copy of A. */ - IterativeSolverBase(const MatrixType& A) + template + IterativeSolverBase(const EigenBase& A) { init(); - compute(A); + compute(A.derived()); } ~IterativeSolverBase() {} @@ -62,9 +63,11 @@ public: * Currently, this function mostly call analyzePattern on the preconditioner. In the future * we might, for instance, implement column reodering for faster matrix vector products. */ - Derived& analyzePattern(const MatrixType& A) + template + Derived& analyzePattern(const EigenBase& A) { - m_preconditioner.analyzePattern(A); + grabInput(A.derived()); + m_preconditioner.analyzePattern(*mp_matrix); m_isInitialized = true; m_analysisIsOk = true; m_info = Success; @@ -80,11 +83,12 @@ public: * this class becomes invalid. Call compute() to update it with the new * matrix A, or modify a copy of A. */ - Derived& factorize(const MatrixType& A) + template + Derived& factorize(const EigenBase& A) { + grabInput(A.derived()); eigen_assert(m_analysisIsOk && "You must first call analyzePattern()"); - mp_matrix = &A; - m_preconditioner.factorize(A); + m_preconditioner.factorize(*mp_matrix); m_factorizationIsOk = true; m_info = Success; return derived(); @@ -100,10 +104,11 @@ public: * this class becomes invalid. Call compute() to update it with the new * matrix A, or modify a copy of A. */ - Derived& compute(const MatrixType& A) + template + Derived& compute(const EigenBase& A) { - mp_matrix = &A; - m_preconditioner.compute(A); + grabInput(A.derived()); + m_preconditioner.compute(*mp_matrix); m_isInitialized = true; m_analysisIsOk = true; m_factorizationIsOk = true; @@ -212,6 +217,28 @@ public: } protected: + + template + void grabInput(const EigenBase& A) + { + // we const cast to prevent the creation of a MatrixType temporary by the compiler. + grabInput_impl(A.const_cast_derived()); + } + + template + void grabInput_impl(const EigenBase& A) + { + m_copyMatrix = A; + mp_matrix = &m_copyMatrix; + } + + void grabInput_impl(MatrixType& A) + { + if(MatrixType::RowsAtCompileTime==Dynamic && MatrixType::ColsAtCompileTime==Dynamic) + m_copyMatrix.resize(0,0); + mp_matrix = &A; + } + void init() { m_isInitialized = false; @@ -220,6 +247,7 @@ protected: m_maxIterations = -1; m_tolerance = NumTraits::epsilon(); } + MatrixType m_copyMatrix; const MatrixType* mp_matrix; Preconditioner m_preconditioner; diff --git a/gtsam/3rdparty/Eigen/Eigen/src/LU/FullPivLU.h b/gtsam/3rdparty/Eigen/Eigen/src/LU/FullPivLU.h index 79ab6a8c8..26bc71447 100644 --- a/gtsam/3rdparty/Eigen/Eigen/src/LU/FullPivLU.h +++ b/gtsam/3rdparty/Eigen/Eigen/src/LU/FullPivLU.h @@ -374,6 +374,12 @@ template class FullPivLU inline Index cols() const { return m_lu.cols(); } protected: + + static void check_template_parameters() + { + EIGEN_STATIC_ASSERT_NON_INTEGER(Scalar); + } + MatrixType m_lu; PermutationPType m_p; PermutationQType m_q; @@ -418,6 +424,8 @@ FullPivLU::FullPivLU(const MatrixType& matrix) template FullPivLU& FullPivLU::compute(const MatrixType& matrix) { + check_template_parameters(); + // the permutations are stored as int indices, so just to be sure: eigen_assert(matrix.rows()<=NumTraits::highest() && matrix.cols()<=NumTraits::highest()); diff --git a/gtsam/3rdparty/Eigen/Eigen/src/LU/PartialPivLU.h b/gtsam/3rdparty/Eigen/Eigen/src/LU/PartialPivLU.h index 740ee694c..7d1db948c 100644 --- a/gtsam/3rdparty/Eigen/Eigen/src/LU/PartialPivLU.h +++ b/gtsam/3rdparty/Eigen/Eigen/src/LU/PartialPivLU.h @@ -171,6 +171,12 @@ template class PartialPivLU inline Index cols() const { return m_lu.cols(); } protected: + + static void check_template_parameters() + { + EIGEN_STATIC_ASSERT_NON_INTEGER(Scalar); + } + MatrixType m_lu; PermutationType m_p; TranspositionType m_rowsTranspositions; @@ -386,6 +392,8 @@ void partial_lu_inplace(MatrixType& lu, TranspositionType& row_transpositions, t template PartialPivLU& PartialPivLU::compute(const MatrixType& matrix) { + check_template_parameters(); + // the row permutation is stored as int indices, so just to be sure: eigen_assert(matrix.rows()::highest()); diff --git a/gtsam/3rdparty/Eigen/Eigen/src/OrderingMethods/Amd.h b/gtsam/3rdparty/Eigen/Eigen/src/OrderingMethods/Amd.h index 41b4fd7e3..70550b8a9 100644 --- a/gtsam/3rdparty/Eigen/Eigen/src/OrderingMethods/Amd.h +++ b/gtsam/3rdparty/Eigen/Eigen/src/OrderingMethods/Amd.h @@ -137,22 +137,27 @@ void minimum_degree_ordering(SparseMatrix& C, Permutation degree[i] = len[i]; // degree of node i } mark = internal::cs_wclear(0, 0, w, n); /* clear w */ - elen[n] = -2; /* n is a dead element */ - Cp[n] = -1; /* n is a root of assembly tree */ - w[n] = 0; /* n is a dead element */ /* --- Initialize degree lists ------------------------------------------ */ for(i = 0; i < n; i++) { + bool has_diag = false; + for(p = Cp[i]; p dense) /* node i is dense */ + else if(d > dense || !has_diag) /* node i is dense or has no structural diagonal element */ { nv[i] = 0; /* absorb i into element n */ elen[i] = -1; /* node i is dead */ @@ -168,6 +173,10 @@ void minimum_degree_ordering(SparseMatrix& C, Permutation } } + elen[n] = -2; /* n is a dead element */ + Cp[n] = -1; /* n is a root of assembly tree */ + w[n] = 0; /* n is a dead element */ + while (nel < n) /* while (selecting pivots) do */ { /* --- Select node of minimum approximate degree -------------------- */ diff --git a/gtsam/3rdparty/Eigen/Eigen/src/QR/ColPivHouseholderQR.h b/gtsam/3rdparty/Eigen/Eigen/src/QR/ColPivHouseholderQR.h index 773d1df8f..567eab7cd 100644 --- a/gtsam/3rdparty/Eigen/Eigen/src/QR/ColPivHouseholderQR.h +++ b/gtsam/3rdparty/Eigen/Eigen/src/QR/ColPivHouseholderQR.h @@ -384,6 +384,12 @@ template class ColPivHouseholderQR } protected: + + static void check_template_parameters() + { + EIGEN_STATIC_ASSERT_NON_INTEGER(Scalar); + } + MatrixType m_qr; HCoeffsType m_hCoeffs; PermutationType m_colsPermutation; @@ -422,6 +428,8 @@ typename MatrixType::RealScalar ColPivHouseholderQR::logAbsDetermina template ColPivHouseholderQR& ColPivHouseholderQR::compute(const MatrixType& matrix) { + check_template_parameters(); + using std::abs; Index rows = matrix.rows(); Index cols = matrix.cols(); @@ -463,20 +471,10 @@ ColPivHouseholderQR& ColPivHouseholderQR::compute(const // we store that back into our table: it can't hurt to correct our table. m_colSqNorms.coeffRef(biggest_col_index) = biggest_col_sq_norm; - // if the current biggest column is smaller than epsilon times the initial biggest column, - // terminate to avoid generating nan/inf values. - // Note that here, if we test instead for "biggest == 0", we get a failure every 1000 (or so) - // repetitions of the unit test, with the result of solve() filled with large values of the order - // of 1/(size*epsilon). - if(biggest_col_sq_norm < threshold_helper * RealScalar(rows-k)) - { + // Track the number of meaningful pivots but do not stop the decomposition to make + // sure that the initial matrix is properly reproduced. See bug 941. + if(m_nonzero_pivots==size && biggest_col_sq_norm < threshold_helper * RealScalar(rows-k)) m_nonzero_pivots = k; - m_hCoeffs.tail(size-k).setZero(); - m_qr.bottomRightCorner(rows-k,cols-k) - .template triangularView() - .setZero(); - break; - } // apply the transposition to the columns m_colsTranspositions.coeffRef(k) = biggest_col_index; @@ -505,7 +503,7 @@ ColPivHouseholderQR& ColPivHouseholderQR::compute(const } m_colsPermutation.setIdentity(PermIndexType(cols)); - for(PermIndexType k = 0; k < m_nonzero_pivots; ++k) + for(PermIndexType k = 0; k < size/*m_nonzero_pivots*/; ++k) m_colsPermutation.applyTranspositionOnTheRight(k, PermIndexType(m_colsTranspositions.coeff(k))); m_det_pq = (number_of_transpositions%2) ? -1 : 1; @@ -555,13 +553,15 @@ struct solve_retval, Rhs> } // end namespace internal -/** \returns the matrix Q as a sequence of householder transformations */ +/** \returns the matrix Q as a sequence of householder transformations. + * You can extract the meaningful part only by using: + * \code qr.householderQ().setLength(qr.nonzeroPivots()) \endcode*/ template typename ColPivHouseholderQR::HouseholderSequenceType ColPivHouseholderQR ::householderQ() const { eigen_assert(m_isInitialized && "ColPivHouseholderQR is not initialized."); - return HouseholderSequenceType(m_qr, m_hCoeffs.conjugate()).setLength(m_nonzero_pivots); + return HouseholderSequenceType(m_qr, m_hCoeffs.conjugate()); } /** \return the column-pivoting Householder QR decomposition of \c *this. diff --git a/gtsam/3rdparty/Eigen/Eigen/src/QR/ColPivHouseholderQR_MKL.h b/gtsam/3rdparty/Eigen/Eigen/src/QR/ColPivHouseholderQR_MKL.h index e66196b1d..b1332be5e 100644 --- a/gtsam/3rdparty/Eigen/Eigen/src/QR/ColPivHouseholderQR_MKL.h +++ b/gtsam/3rdparty/Eigen/Eigen/src/QR/ColPivHouseholderQR_MKL.h @@ -63,12 +63,12 @@ ColPivHouseholderQR class FullPivHouseholderQR RealScalar maxPivot() const { return m_maxpivot; } protected: + + static void check_template_parameters() + { + EIGEN_STATIC_ASSERT_NON_INTEGER(Scalar); + } + MatrixType m_qr; HCoeffsType m_hCoeffs; IntDiagSizeVectorType m_rows_transpositions; @@ -407,6 +413,8 @@ typename MatrixType::RealScalar FullPivHouseholderQR::logAbsDetermin template FullPivHouseholderQR& FullPivHouseholderQR::compute(const MatrixType& matrix) { + check_template_parameters(); + using std::abs; Index rows = matrix.rows(); Index cols = matrix.cols(); diff --git a/gtsam/3rdparty/Eigen/Eigen/src/QR/HouseholderQR.h b/gtsam/3rdparty/Eigen/Eigen/src/QR/HouseholderQR.h index 3a94a3c34..343a66499 100644 --- a/gtsam/3rdparty/Eigen/Eigen/src/QR/HouseholderQR.h +++ b/gtsam/3rdparty/Eigen/Eigen/src/QR/HouseholderQR.h @@ -189,6 +189,12 @@ template class HouseholderQR const HCoeffsType& hCoeffs() const { return m_hCoeffs; } protected: + + static void check_template_parameters() + { + EIGEN_STATIC_ASSERT_NON_INTEGER(Scalar); + } + MatrixType m_qr; HCoeffsType m_hCoeffs; RowVectorType m_temp; @@ -349,6 +355,8 @@ struct solve_retval, Rhs> template HouseholderQR& HouseholderQR::compute(const MatrixType& matrix) { + check_template_parameters(); + Index rows = matrix.rows(); Index cols = matrix.cols(); Index size = (std::min)(rows,cols); diff --git a/gtsam/3rdparty/Eigen/Eigen/src/SPQRSupport/SuiteSparseQRSupport.h b/gtsam/3rdparty/Eigen/Eigen/src/SPQRSupport/SuiteSparseQRSupport.h index a2cc2a9e2..36138101d 100644 --- a/gtsam/3rdparty/Eigen/Eigen/src/SPQRSupport/SuiteSparseQRSupport.h +++ b/gtsam/3rdparty/Eigen/Eigen/src/SPQRSupport/SuiteSparseQRSupport.h @@ -47,7 +47,7 @@ namespace Eigen { * You can then apply it to a vector. * * R is the sparse triangular factor. Use matrixQR() to get it as SparseMatrix. - * NOTE : The Index type of R is always UF_long. You can get it with SPQR::Index + * NOTE : The Index type of R is always SuiteSparse_long. You can get it with SPQR::Index * * \tparam _MatrixType The type of the sparse matrix A, must be a column-major SparseMatrix<> * NOTE @@ -59,24 +59,18 @@ class SPQR public: typedef typename _MatrixType::Scalar Scalar; typedef typename _MatrixType::RealScalar RealScalar; - typedef UF_long Index ; + typedef SuiteSparse_long Index ; typedef SparseMatrix MatrixType; typedef PermutationMatrix PermutationType; public: SPQR() - : m_isInitialized(false), - m_ordering(SPQR_ORDERING_DEFAULT), - m_allow_tol(SPQR_DEFAULT_TOL), - m_tolerance (NumTraits::epsilon()) + : m_isInitialized(false), m_ordering(SPQR_ORDERING_DEFAULT), m_allow_tol(SPQR_DEFAULT_TOL), m_tolerance (NumTraits::epsilon()), m_useDefaultThreshold(true) { cholmod_l_start(&m_cc); } - SPQR(const _MatrixType& matrix) - : m_isInitialized(false), - m_ordering(SPQR_ORDERING_DEFAULT), - m_allow_tol(SPQR_DEFAULT_TOL), - m_tolerance (NumTraits::epsilon()) + SPQR(const _MatrixType& matrix) + : m_isInitialized(false), m_ordering(SPQR_ORDERING_DEFAULT), m_allow_tol(SPQR_DEFAULT_TOL), m_tolerance (NumTraits::epsilon()), m_useDefaultThreshold(true) { cholmod_l_start(&m_cc); compute(matrix); @@ -101,10 +95,26 @@ class SPQR if(m_isInitialized) SPQR_free(); MatrixType mat(matrix); + + /* Compute the default threshold as in MatLab, see: + * Tim Davis, "Algorithm 915, SuiteSparseQR: Multifrontal Multithreaded Rank-Revealing + * Sparse QR Factorization, ACM Trans. on Math. Soft. 38(1), 2011, Page 8:3 + */ + RealScalar pivotThreshold = m_tolerance; + if(m_useDefaultThreshold) + { + using std::max; + RealScalar max2Norm = 0.0; + for (int j = 0; j < mat.cols(); j++) max2Norm = (max)(max2Norm, mat.col(j).norm()); + if(max2Norm==RealScalar(0)) + max2Norm = RealScalar(1); + pivotThreshold = 20 * (mat.rows() + mat.cols()) * max2Norm * NumTraits::epsilon(); + } + cholmod_sparse A; A = viewAsCholmod(mat); Index col = matrix.cols(); - m_rank = SuiteSparseQR(m_ordering, m_tolerance, col, &A, + m_rank = SuiteSparseQR(m_ordering, pivotThreshold, col, &A, &m_cR, &m_E, &m_H, &m_HPinv, &m_HTau, &m_cc); if (!m_cR) @@ -120,7 +130,7 @@ class SPQR /** * Get the number of rows of the input matrix and the Q matrix */ - inline Index rows() const {return m_H->nrow; } + inline Index rows() const {return m_cR->nrow; } /** * Get the number of columns of the input matrix. @@ -145,16 +155,25 @@ class SPQR { eigen_assert(m_isInitialized && " The QR factorization should be computed first, call compute()"); eigen_assert(b.cols()==1 && "This method is for vectors only"); - + //Compute Q^T * b - typename Dest::PlainObject y; + typename Dest::PlainObject y, y2; y = matrixQ().transpose() * b; - // Solves with the triangular matrix R + + // Solves with the triangular matrix R Index rk = this->rank(); - y.topRows(rk) = this->matrixR().topLeftCorner(rk, rk).template triangularView().solve(y.topRows(rk)); - y.bottomRows(cols()-rk).setZero(); + y2 = y; + y.resize((std::max)(cols(),Index(y.rows())),y.cols()); + y.topRows(rk) = this->matrixR().topLeftCorner(rk, rk).template triangularView().solve(y2.topRows(rk)); + // Apply the column permutation - dest.topRows(cols()) = colsPermutation() * y.topRows(cols()); + // colsPermutation() performs a copy of the permutation, + // so let's apply it manually: + for(Index i = 0; i < rk; ++i) dest.row(m_E[i]) = y.row(i); + for(Index i = rk; i < cols(); ++i) dest.row(m_E[i]).setZero(); + +// y.bottomRows(y.rows()-rk).setZero(); +// dest = colsPermutation() * y.topRows(cols()); m_info = Success; } @@ -197,7 +216,11 @@ class SPQR /// Set the fill-reducing ordering method to be used void setSPQROrdering(int ord) { m_ordering = ord;} /// Set the tolerance tol to treat columns with 2-norm < =tol as zero - void setPivotThreshold(const RealScalar& tol) { m_tolerance = tol; } + void setPivotThreshold(const RealScalar& tol) + { + m_useDefaultThreshold = false; + m_tolerance = tol; + } /** \returns a pointer to the SPQR workspace */ cholmod_common *cholmodCommon() const { return &m_cc; } @@ -230,6 +253,7 @@ class SPQR mutable cholmod_dense *m_HTau; // The Householder coefficients mutable Index m_rank; // The rank of the matrix mutable cholmod_common m_cc; // Workspace and parameters + bool m_useDefaultThreshold; // Use default threshold template friend struct SPQR_QProduct; }; diff --git a/gtsam/3rdparty/Eigen/Eigen/src/SVD/JacobiSVD.h b/gtsam/3rdparty/Eigen/Eigen/src/SVD/JacobiSVD.h index c57f2974c..1b2977419 100644 --- a/gtsam/3rdparty/Eigen/Eigen/src/SVD/JacobiSVD.h +++ b/gtsam/3rdparty/Eigen/Eigen/src/SVD/JacobiSVD.h @@ -742,6 +742,11 @@ template class JacobiSVD private: void allocate(Index rows, Index cols, unsigned int computationOptions); + + static void check_template_parameters() + { + EIGEN_STATIC_ASSERT_NON_INTEGER(Scalar); + } protected: MatrixUType m_matrixU; @@ -818,6 +823,8 @@ template JacobiSVD& JacobiSVD::compute(const MatrixType& matrix, unsigned int computationOptions) { + check_template_parameters(); + using std::abs; allocate(matrix.rows(), matrix.cols(), computationOptions); diff --git a/gtsam/3rdparty/Eigen/Eigen/src/SparseCore/SparseBlock.h b/gtsam/3rdparty/Eigen/Eigen/src/SparseCore/SparseBlock.h index 0ede034ba..0c90bafbe 100644 --- a/gtsam/3rdparty/Eigen/Eigen/src/SparseCore/SparseBlock.h +++ b/gtsam/3rdparty/Eigen/Eigen/src/SparseCore/SparseBlock.h @@ -57,6 +57,16 @@ public: inline BlockImpl(const XprType& xpr, int startRow, int startCol, int blockRows, int blockCols) : m_matrix(xpr), m_outerStart(IsRowMajor ? startRow : startCol), m_outerSize(IsRowMajor ? blockRows : blockCols) {} + + inline const Scalar coeff(int row, int col) const + { + return m_matrix.coeff(row + IsRowMajor ? m_outerStart : 0, col +IsRowMajor ? 0 : m_outerStart); + } + + inline const Scalar coeff(int index) const + { + return m_matrix.coeff(IsRowMajor ? m_outerStart : index, IsRowMajor ? index : m_outerStart); + } EIGEN_STRONG_INLINE Index rows() const { return IsRowMajor ? m_outerSize.value() : m_matrix.rows(); } EIGEN_STRONG_INLINE Index cols() const { return IsRowMajor ? m_matrix.cols() : m_outerSize.value(); } @@ -226,6 +236,21 @@ public: else return Map >(m_matrix.innerNonZeroPtr()+m_outerStart, m_outerSize.value()).sum(); } + + inline Scalar& coeffRef(int row, int col) + { + return m_matrix.const_cast_derived().coeffRef(row + (IsRowMajor ? m_outerStart : 0), col + (IsRowMajor ? 0 : m_outerStart)); + } + + inline const Scalar coeff(int row, int col) const + { + return m_matrix.coeff(row + (IsRowMajor ? m_outerStart : 0), col + (IsRowMajor ? 0 : m_outerStart)); + } + + inline const Scalar coeff(int index) const + { + return m_matrix.coeff(IsRowMajor ? m_outerStart : index, IsRowMajor ? index : m_outerStart); + } const Scalar& lastCoeff() const { @@ -313,6 +338,16 @@ public: else return Map >(m_matrix.innerNonZeroPtr()+m_outerStart, m_outerSize.value()).sum(); } + + inline const Scalar coeff(int row, int col) const + { + return m_matrix.coeff(row + (IsRowMajor ? m_outerStart : 0), col + (IsRowMajor ? 0 : m_outerStart)); + } + + inline const Scalar coeff(int index) const + { + return m_matrix.coeff(IsRowMajor ? m_outerStart : index, IsRowMajor ? index : m_outerStart); + } const Scalar& lastCoeff() const { @@ -355,7 +390,8 @@ const typename SparseMatrixBase::ConstInnerVectorReturnType SparseMatri * is col-major (resp. row-major). */ template -Block SparseMatrixBase::innerVectors(Index outerStart, Index outerSize) +typename SparseMatrixBase::InnerVectorsReturnType +SparseMatrixBase::innerVectors(Index outerStart, Index outerSize) { return Block(derived(), IsRowMajor ? outerStart : 0, IsRowMajor ? 0 : outerStart, @@ -367,7 +403,8 @@ Block SparseMatrixBase::innerVectors(Inde * is col-major (resp. row-major). Read-only. */ template -const Block SparseMatrixBase::innerVectors(Index outerStart, Index outerSize) const +const typename SparseMatrixBase::ConstInnerVectorsReturnType +SparseMatrixBase::innerVectors(Index outerStart, Index outerSize) const { return Block(derived(), IsRowMajor ? outerStart : 0, IsRowMajor ? 0 : outerStart, @@ -394,8 +431,8 @@ public: : m_matrix(xpr), m_startRow( (BlockRows==1) && (BlockCols==XprType::ColsAtCompileTime) ? i : 0), m_startCol( (BlockRows==XprType::RowsAtCompileTime) && (BlockCols==1) ? i : 0), - m_blockRows(xpr.rows()), - m_blockCols(xpr.cols()) + m_blockRows(BlockRows==1 ? 1 : xpr.rows()), + m_blockCols(BlockCols==1 ? 1 : xpr.cols()) {} /** Dynamic-size constructor @@ -497,3 +534,4 @@ public: } // end namespace Eigen #endif // EIGEN_SPARSE_BLOCK_H + diff --git a/gtsam/3rdparty/Eigen/Eigen/src/SparseCore/SparseCwiseBinaryOp.h b/gtsam/3rdparty/Eigen/Eigen/src/SparseCore/SparseCwiseBinaryOp.h index 60ca7690c..4ca912833 100644 --- a/gtsam/3rdparty/Eigen/Eigen/src/SparseCore/SparseCwiseBinaryOp.h +++ b/gtsam/3rdparty/Eigen/Eigen/src/SparseCore/SparseCwiseBinaryOp.h @@ -314,10 +314,10 @@ SparseMatrixBase::operator+=(const SparseMatrixBase& othe template template -EIGEN_STRONG_INLINE const EIGEN_SPARSE_CWISE_PRODUCT_RETURN_TYPE +EIGEN_STRONG_INLINE const typename SparseMatrixBase::template CwiseProductDenseReturnType::Type SparseMatrixBase::cwiseProduct(const MatrixBase &other) const { - return EIGEN_SPARSE_CWISE_PRODUCT_RETURN_TYPE(derived(), other.derived()); + return typename CwiseProductDenseReturnType::Type(derived(), other.derived()); } } // end namespace Eigen diff --git a/gtsam/3rdparty/Eigen/Eigen/src/SparseCore/SparseDenseProduct.h b/gtsam/3rdparty/Eigen/Eigen/src/SparseCore/SparseDenseProduct.h index a9084192e..ccb6ae7b7 100644 --- a/gtsam/3rdparty/Eigen/Eigen/src/SparseCore/SparseDenseProduct.h +++ b/gtsam/3rdparty/Eigen/Eigen/src/SparseCore/SparseDenseProduct.h @@ -180,7 +180,7 @@ struct sparse_time_dense_product_impl >(&this->m_data.index(0), rows()).setLinSpaced(0, rows()-1); Eigen::Map >(&this->m_data.value(0), rows()).setOnes(); Eigen::Map >(this->m_outerIndex, rows()+1).setLinSpaced(0, rows()); + std::free(m_innerNonZeros); + m_innerNonZeros = 0; } inline SparseMatrix& operator=(const SparseMatrix& other) { diff --git a/gtsam/3rdparty/Eigen/Eigen/src/SparseCore/SparseMatrixBase.h b/gtsam/3rdparty/Eigen/Eigen/src/SparseCore/SparseMatrixBase.h index 485e85bec..9341d9ad2 100644 --- a/gtsam/3rdparty/Eigen/Eigen/src/SparseCore/SparseMatrixBase.h +++ b/gtsam/3rdparty/Eigen/Eigen/src/SparseCore/SparseMatrixBase.h @@ -23,7 +23,14 @@ namespace Eigen { * This class can be extended with the help of the plugin mechanism described on the page * \ref TopicCustomizingEigen by defining the preprocessor symbol \c EIGEN_SPARSEMATRIXBASE_PLUGIN. */ -template class SparseMatrixBase : public EigenBase +template class SparseMatrixBase +#ifndef EIGEN_PARSED_BY_DOXYGEN + : public internal::special_scalar_op_base::Scalar, + typename NumTraits::Scalar>::Real, + EigenBase > +#else + : public EigenBase +#endif // not EIGEN_PARSED_BY_DOXYGEN { public: @@ -36,7 +43,6 @@ template class SparseMatrixBase : public EigenBase >::type PacketReturnType; typedef SparseMatrixBase StorageBaseType; - typedef EigenBase Base; template Derived& operator=(const EigenBase &other) @@ -132,6 +138,9 @@ template class SparseMatrixBase : public EigenBase inline Derived& derived() { return *static_cast(this); } inline Derived& const_cast_derived() const { return *static_cast(const_cast(this)); } + + typedef internal::special_scalar_op_base > Base; + using Base::operator*; #endif // not EIGEN_PARSED_BY_DOXYGEN #define EIGEN_CURRENT_STORAGE_BASE_CLASS Eigen::SparseMatrixBase @@ -317,20 +326,18 @@ template class SparseMatrixBase : public EigenBase Derived& operator*=(const Scalar& other); Derived& operator/=(const Scalar& other); - #define EIGEN_SPARSE_CWISE_PRODUCT_RETURN_TYPE \ - CwiseBinaryOp< \ - internal::scalar_product_op< \ - typename internal::scalar_product_traits< \ - typename internal::traits::Scalar, \ - typename internal::traits::Scalar \ - >::ReturnType \ - >, \ - const Derived, \ - const OtherDerived \ - > + template struct CwiseProductDenseReturnType { + typedef CwiseBinaryOp::Scalar, + typename internal::traits::Scalar + >::ReturnType>, + const Derived, + const OtherDerived + > Type; + }; template - EIGEN_STRONG_INLINE const EIGEN_SPARSE_CWISE_PRODUCT_RETURN_TYPE + EIGEN_STRONG_INLINE const typename CwiseProductDenseReturnType::Type cwiseProduct(const MatrixBase &other) const; // sparse * sparse @@ -404,8 +411,10 @@ template class SparseMatrixBase : public EigenBase const ConstInnerVectorReturnType innerVector(Index outer) const; // set of inner-vectors - Block innerVectors(Index outerStart, Index outerSize); - const Block innerVectors(Index outerStart, Index outerSize) const; + typedef Block InnerVectorsReturnType; + typedef Block ConstInnerVectorsReturnType; + InnerVectorsReturnType innerVectors(Index outerStart, Index outerSize); + const ConstInnerVectorsReturnType innerVectors(Index outerStart, Index outerSize) const; /** \internal use operator= */ template diff --git a/gtsam/3rdparty/Eigen/Eigen/src/SparseCore/SparseUtil.h b/gtsam/3rdparty/Eigen/Eigen/src/SparseCore/SparseUtil.h index 0ba471320..d627546de 100644 --- a/gtsam/3rdparty/Eigen/Eigen/src/SparseCore/SparseUtil.h +++ b/gtsam/3rdparty/Eigen/Eigen/src/SparseCore/SparseUtil.h @@ -67,7 +67,6 @@ const int InnerRandomAccessPattern = 0x2 | CoherentAccessPattern; const int OuterRandomAccessPattern = 0x4 | CoherentAccessPattern; const int RandomAccessPattern = 0x8 | OuterRandomAccessPattern | InnerRandomAccessPattern; -template class SparseMatrixBase; template class SparseMatrix; template class DynamicSparseMatrix; template class SparseVector; diff --git a/gtsam/3rdparty/Eigen/Eigen/src/SparseCore/SparseVector.h b/gtsam/3rdparty/Eigen/Eigen/src/SparseCore/SparseVector.h index 7e15c814b..49865d0e7 100644 --- a/gtsam/3rdparty/Eigen/Eigen/src/SparseCore/SparseVector.h +++ b/gtsam/3rdparty/Eigen/Eigen/src/SparseCore/SparseVector.h @@ -158,6 +158,7 @@ class SparseVector Index inner = IsColVector ? row : col; Index outer = IsColVector ? col : row; + EIGEN_ONLY_USED_FOR_DEBUG(outer); eigen_assert(outer==0); return insert(inner); } diff --git a/gtsam/3rdparty/Eigen/Eigen/src/SparseCore/TriangularSolver.h b/gtsam/3rdparty/Eigen/Eigen/src/SparseCore/TriangularSolver.h index cb8ad82b4..ccc12af79 100644 --- a/gtsam/3rdparty/Eigen/Eigen/src/SparseCore/TriangularSolver.h +++ b/gtsam/3rdparty/Eigen/Eigen/src/SparseCore/TriangularSolver.h @@ -69,7 +69,7 @@ struct sparse_solve_triangular_selector for(int i=lhs.rows()-1 ; i>=0 ; --i) { Scalar tmp = other.coeff(i,col); - Scalar l_ii = 0; + Scalar l_ii(0); typename Lhs::InnerIterator it(lhs, i); while(it && it.index()cols(); ++j) + { + for (typename SCMatrix::InnerIterator it(m_Lstore, j); it; ++it) + { + if(it.index() == j) + { + if(it.value()<0) + det = -det; + else if(it.value()==0) + return 0; + break; + } + } + } + return det * m_detPermR * m_detPermC; + } + + /** \returns The determinant of the matrix. + * + * \sa absDeterminant(), logAbsDeterminant() + */ + Scalar determinant() + { + eigen_assert(m_factorizationIsOk && "The matrix should be factorized first."); + // Initialize with the determinant of the row matrix + Scalar det = Scalar(1.); + // Note that the diagonal blocks of U are stored in supernodes, + // which are available in the L part :) + for (Index j = 0; j < this->cols(); ++j) + { + for (typename SCMatrix::InnerIterator it(m_Lstore, j); it; ++it) + { + if(it.index() == j) + { + det *= it.value(); + break; + } + } + } + return det * Scalar(m_detPermR * m_detPermC); + } protected: // Functions void initperfvalues() { - m_perfv.panel_size = 1; + m_perfv.panel_size = 16; m_perfv.relax = 1; m_perfv.maxsuper = 128; m_perfv.rowblk = 16; @@ -345,8 +390,8 @@ class SparseLU : public internal::SparseLUImpl m_perfv; RealScalar m_diagpivotthresh; // Specifies the threshold used for a diagonal entry to be an acceptable pivot - Index m_nnzL, m_nnzU; // Nonzeros in L and U factors - Index m_detPermR; // Determinant of the coefficient matrix + Index m_nnzL, m_nnzU; // Nonzeros in L and U factors + Index m_detPermR, m_detPermC; // Determinants of the permutation matrices private: // Disable copy constructor SparseLU (const SparseLU& ); @@ -622,7 +667,8 @@ void SparseLU::factorize(const MatrixType& matrix) } // Update the determinant of the row permutation matrix - if (pivrow != jj) m_detPermR *= -1; + // FIXME: the following test is not correct, we should probably take iperm_c into account and pivrow is not directly the row pivot. + if (pivrow != jj) m_detPermR = -m_detPermR; // Prune columns (0:jj-1) using column jj Base::pruneL(jj, m_perm_r.indices(), pivrow, nseg, segrep, repfnz_k, xprune, m_glu); @@ -637,10 +683,13 @@ void SparseLU::factorize(const MatrixType& matrix) jcol += panel_size; // Move to the next panel } // end for -- end elimination + m_detPermR = m_perm_r.determinant(); + m_detPermC = m_perm_c.determinant(); + // Count the number of nonzeros in factors Base::countnz(n, m_nnzL, m_nnzU, m_glu); // Apply permutation to the L subscripts - Base::fixupL(n, m_perm_r.indices(), m_glu); + Base::fixupL(n, m_perm_r.indices(), m_glu); // Create supernode matrix L m_Lstore.setInfos(m, n, m_glu.lusup, m_glu.xlusup, m_glu.lsub, m_glu.xlsub, m_glu.supno, m_glu.xsup); @@ -700,8 +749,8 @@ struct SparseLUMatrixUReturnType : internal::no_assignment_operator } else { - Map, 0, OuterStride<> > A( &(m_mapL.valuePtr()[luptr]), nsupc, nsupc, OuterStride<>(lda) ); - Map< Matrix, 0, OuterStride<> > U (&(X(fsupc,0)), nsupc, nrhs, OuterStride<>(n) ); + Map, 0, OuterStride<> > A( &(m_mapL.valuePtr()[luptr]), nsupc, nsupc, OuterStride<>(lda) ); + Map< Matrix, 0, OuterStride<> > U (&(X(fsupc,0)), nsupc, nrhs, OuterStride<>(n) ); U = A.template triangularView().solve(U); } diff --git a/gtsam/3rdparty/Eigen/Eigen/src/SparseLU/SparseLUImpl.h b/gtsam/3rdparty/Eigen/Eigen/src/SparseLU/SparseLUImpl.h index 14d70897d..99d651e40 100644 --- a/gtsam/3rdparty/Eigen/Eigen/src/SparseLU/SparseLUImpl.h +++ b/gtsam/3rdparty/Eigen/Eigen/src/SparseLU/SparseLUImpl.h @@ -21,6 +21,8 @@ class SparseLUImpl { public: typedef Matrix ScalarVector; + typedef Matrix ScalarMatrix; + typedef Map > MappedMatrixBlock; typedef Matrix IndexVector; typedef typename ScalarVector::RealScalar RealScalar; typedef Ref > BlockScalarVector; diff --git a/gtsam/3rdparty/Eigen/Eigen/src/SparseLU/SparseLU_Memory.h b/gtsam/3rdparty/Eigen/Eigen/src/SparseLU/SparseLU_Memory.h index 1ffa7d54e..45f96d16a 100644 --- a/gtsam/3rdparty/Eigen/Eigen/src/SparseLU/SparseLU_Memory.h +++ b/gtsam/3rdparty/Eigen/Eigen/src/SparseLU/SparseLU_Memory.h @@ -153,8 +153,8 @@ Index SparseLUImpl::memInit(Index m, Index n, Index annz, Index lw { Index& num_expansions = glu.num_expansions; //No memory expansions so far num_expansions = 0; - glu.nzumax = glu.nzlumax = (std::min)(fillratio * annz / n, m) * n; // estimated number of nonzeros in U - glu.nzlmax = (std::max)(Index(4), fillratio) * annz / 4; // estimated nnz in L factor + glu.nzumax = glu.nzlumax = (std::min)(fillratio * (annz+1) / n, m) * n; // estimated number of nonzeros in U + glu.nzlmax = (std::max)(Index(4), fillratio) * (annz+1) / 4; // estimated nnz in L factor // Return the estimated size to the user if necessary Index tempSpace; tempSpace = (2*panel_size + 4 + LUNoMarker) * m * sizeof(Index) + (panel_size + 1) * m * sizeof(Scalar); diff --git a/gtsam/3rdparty/Eigen/Eigen/src/SparseLU/SparseLU_SupernodalMatrix.h b/gtsam/3rdparty/Eigen/Eigen/src/SparseLU/SparseLU_SupernodalMatrix.h index b16afd6a4..54a569408 100644 --- a/gtsam/3rdparty/Eigen/Eigen/src/SparseLU/SparseLU_SupernodalMatrix.h +++ b/gtsam/3rdparty/Eigen/Eigen/src/SparseLU/SparseLU_SupernodalMatrix.h @@ -236,7 +236,7 @@ void MappedSuperNodalMatrix::solveInPlace( MatrixBase&X) con Index n = X.rows(); Index nrhs = X.cols(); const Scalar * Lval = valuePtr(); // Nonzero values - Matrix work(n, nrhs); // working vector + Matrix work(n, nrhs); // working vector work.setZero(); for (Index k = 0; k <= nsuper(); k ++) { @@ -267,12 +267,12 @@ void MappedSuperNodalMatrix::solveInPlace( MatrixBase&X) con Index lda = colIndexPtr()[fsupc+1] - luptr; // Triangular solve - Map, 0, OuterStride<> > A( &(Lval[luptr]), nsupc, nsupc, OuterStride<>(lda) ); - Map< Matrix, 0, OuterStride<> > U (&(X(fsupc,0)), nsupc, nrhs, OuterStride<>(n) ); + Map, 0, OuterStride<> > A( &(Lval[luptr]), nsupc, nsupc, OuterStride<>(lda) ); + Map< Matrix, 0, OuterStride<> > U (&(X(fsupc,0)), nsupc, nrhs, OuterStride<>(n) ); U = A.template triangularView().solve(U); // Matrix-vector product - new (&A) Map, 0, OuterStride<> > ( &(Lval[luptr+nsupc]), nrow, nsupc, OuterStride<>(lda) ); + new (&A) Map, 0, OuterStride<> > ( &(Lval[luptr+nsupc]), nrow, nsupc, OuterStride<>(lda) ); work.block(0, 0, nrow, nrhs) = A * U; //Begin Scatter diff --git a/gtsam/3rdparty/Eigen/Eigen/src/SparseLU/SparseLU_column_bmod.h b/gtsam/3rdparty/Eigen/Eigen/src/SparseLU/SparseLU_column_bmod.h index f24bd87d3..cacc7e987 100644 --- a/gtsam/3rdparty/Eigen/Eigen/src/SparseLU/SparseLU_column_bmod.h +++ b/gtsam/3rdparty/Eigen/Eigen/src/SparseLU/SparseLU_column_bmod.h @@ -162,11 +162,11 @@ Index SparseLUImpl::column_bmod(const Index jcol, const Index nseg // points to the beginning of jcol in snode L\U(jsupno) ufirst = glu.xlusup(jcol) + d_fsupc; Index lda = glu.xlusup(jcol+1) - glu.xlusup(jcol); - Map, 0, OuterStride<> > A( &(glu.lusup.data()[luptr]), nsupc, nsupc, OuterStride<>(lda) ); + MappedMatrixBlock A( &(glu.lusup.data()[luptr]), nsupc, nsupc, OuterStride<>(lda) ); VectorBlock u(glu.lusup, ufirst, nsupc); u = A.template triangularView().solve(u); - new (&A) Map, 0, OuterStride<> > ( &(glu.lusup.data()[luptr+nsupc]), nrow, nsupc, OuterStride<>(lda) ); + new (&A) MappedMatrixBlock ( &(glu.lusup.data()[luptr+nsupc]), nrow, nsupc, OuterStride<>(lda) ); VectorBlock l(glu.lusup, ufirst+nsupc, nrow); l.noalias() -= A * u; diff --git a/gtsam/3rdparty/Eigen/Eigen/src/SparseLU/SparseLU_kernel_bmod.h b/gtsam/3rdparty/Eigen/Eigen/src/SparseLU/SparseLU_kernel_bmod.h index 0d0283b13..6af026754 100644 --- a/gtsam/3rdparty/Eigen/Eigen/src/SparseLU/SparseLU_kernel_bmod.h +++ b/gtsam/3rdparty/Eigen/Eigen/src/SparseLU/SparseLU_kernel_bmod.h @@ -56,7 +56,7 @@ EIGEN_DONT_INLINE void LU_kernel_bmod::run(const int segsi // Dense triangular solve -- start effective triangle luptr += lda * no_zeros + no_zeros; // Form Eigen matrix and vector - Map, 0, OuterStride<> > A( &(lusup.data()[luptr]), segsize, segsize, OuterStride<>(lda) ); + Map, 0, OuterStride<> > A( &(lusup.data()[luptr]), segsize, segsize, OuterStride<>(lda) ); Map > u(tempv.data(), segsize); u = A.template triangularView().solve(u); @@ -65,7 +65,7 @@ EIGEN_DONT_INLINE void LU_kernel_bmod::run(const int segsi luptr += segsize; const Index PacketSize = internal::packet_traits::size; Index ldl = internal::first_multiple(nrow, PacketSize); - Map, 0, OuterStride<> > B( &(lusup.data()[luptr]), nrow, segsize, OuterStride<>(lda) ); + Map, 0, OuterStride<> > B( &(lusup.data()[luptr]), nrow, segsize, OuterStride<>(lda) ); Index aligned_offset = internal::first_aligned(tempv.data()+segsize, PacketSize); Index aligned_with_B_offset = (PacketSize-internal::first_aligned(B.data(), PacketSize))%PacketSize; Map, 0, OuterStride<> > l(tempv.data()+segsize+aligned_offset+aligned_with_B_offset, nrow, OuterStride<>(ldl) ); diff --git a/gtsam/3rdparty/Eigen/Eigen/src/SparseLU/SparseLU_panel_bmod.h b/gtsam/3rdparty/Eigen/Eigen/src/SparseLU/SparseLU_panel_bmod.h index da0e0fc3c..9d2ff2906 100644 --- a/gtsam/3rdparty/Eigen/Eigen/src/SparseLU/SparseLU_panel_bmod.h +++ b/gtsam/3rdparty/Eigen/Eigen/src/SparseLU/SparseLU_panel_bmod.h @@ -102,7 +102,7 @@ void SparseLUImpl::panel_bmod(const Index m, const Index w, const if(nsupc >= 2) { Index ldu = internal::first_multiple(u_rows, PacketSize); - Map, Aligned, OuterStride<> > U(tempv.data(), u_rows, u_cols, OuterStride<>(ldu)); + Map > U(tempv.data(), u_rows, u_cols, OuterStride<>(ldu)); // gather U Index u_col = 0; @@ -136,17 +136,17 @@ void SparseLUImpl::panel_bmod(const Index m, const Index w, const Index lda = glu.xlusup(fsupc+1) - glu.xlusup(fsupc); no_zeros = (krep - u_rows + 1) - fsupc; luptr += lda * no_zeros + no_zeros; - Map, 0, OuterStride<> > A(glu.lusup.data()+luptr, u_rows, u_rows, OuterStride<>(lda) ); + MappedMatrixBlock A(glu.lusup.data()+luptr, u_rows, u_rows, OuterStride<>(lda) ); U = A.template triangularView().solve(U); // update luptr += u_rows; - Map, 0, OuterStride<> > B(glu.lusup.data()+luptr, nrow, u_rows, OuterStride<>(lda) ); + MappedMatrixBlock B(glu.lusup.data()+luptr, nrow, u_rows, OuterStride<>(lda) ); eigen_assert(tempv.size()>w*ldu + nrow*w + 1); Index ldl = internal::first_multiple(nrow, PacketSize); Index offset = (PacketSize-internal::first_aligned(B.data(), PacketSize)) % PacketSize; - Map, 0, OuterStride<> > L(tempv.data()+w*ldu+offset, nrow, u_cols, OuterStride<>(ldl)); + MappedMatrixBlock L(tempv.data()+w*ldu+offset, nrow, u_cols, OuterStride<>(ldl)); L.setZero(); internal::sparselu_gemm(L.rows(), L.cols(), B.cols(), B.data(), B.outerStride(), U.data(), U.outerStride(), L.data(), L.outerStride()); diff --git a/gtsam/3rdparty/Eigen/Eigen/src/SparseLU/SparseLU_pivotL.h b/gtsam/3rdparty/Eigen/Eigen/src/SparseLU/SparseLU_pivotL.h index ddcd4ec98..2e49ef667 100644 --- a/gtsam/3rdparty/Eigen/Eigen/src/SparseLU/SparseLU_pivotL.h +++ b/gtsam/3rdparty/Eigen/Eigen/src/SparseLU/SparseLU_pivotL.h @@ -71,13 +71,14 @@ Index SparseLUImpl::pivotL(const Index jcol, const RealScalar& dia // Determine the largest abs numerical value for partial pivoting Index diagind = iperm_c(jcol); // diagonal index - RealScalar pivmax = 0.0; + RealScalar pivmax(-1.0); Index pivptr = nsupc; Index diag = emptyIdxLU; RealScalar rtemp; Index isub, icol, itemp, k; for (isub = nsupc; isub < nsupr; ++isub) { - rtemp = std::abs(lu_col_ptr[isub]); + using std::abs; + rtemp = abs(lu_col_ptr[isub]); if (rtemp > pivmax) { pivmax = rtemp; pivptr = isub; @@ -86,8 +87,9 @@ Index SparseLUImpl::pivotL(const Index jcol, const RealScalar& dia } // Test for singularity - if ( pivmax == 0.0 ) { - pivrow = lsub_ptr[pivptr]; + if ( pivmax <= RealScalar(0.0) ) { + // if pivmax == -1, the column is structurally empty, otherwise it is only numerically zero + pivrow = pivmax < RealScalar(0.0) ? diagind : lsub_ptr[pivptr]; perm_r(pivrow) = jcol; return (jcol+1); } @@ -101,7 +103,8 @@ Index SparseLUImpl::pivotL(const Index jcol, const RealScalar& dia if (diag >= 0 ) { // Diagonal element exists - rtemp = std::abs(lu_col_ptr[diag]); + using std::abs; + rtemp = abs(lu_col_ptr[diag]); if (rtemp != 0.0 && rtemp >= thresh) pivptr = diag; } pivrow = lsub_ptr[pivptr]; diff --git a/gtsam/3rdparty/Eigen/Eigen/src/plugins/ArrayCwiseBinaryOps.h b/gtsam/3rdparty/Eigen/Eigen/src/plugins/ArrayCwiseBinaryOps.h index 5c8c476ee..1951286f3 100644 --- a/gtsam/3rdparty/Eigen/Eigen/src/plugins/ArrayCwiseBinaryOps.h +++ b/gtsam/3rdparty/Eigen/Eigen/src/plugins/ArrayCwiseBinaryOps.h @@ -70,6 +70,43 @@ max return (max)(Derived::PlainObject::Constant(rows(), cols(), other)); } + +#define EIGEN_MAKE_CWISE_COMP_OP(OP, COMPARATOR) \ +template \ +EIGEN_STRONG_INLINE const CwiseBinaryOp, const Derived, const OtherDerived> \ +OP(const EIGEN_CURRENT_STORAGE_BASE_CLASS &other) const \ +{ \ + return CwiseBinaryOp, const Derived, const OtherDerived>(derived(), other.derived()); \ +}\ +typedef CwiseBinaryOp, const Derived, const CwiseNullaryOp, PlainObject> > Cmp ## COMPARATOR ## ReturnType; \ +typedef CwiseBinaryOp, const CwiseNullaryOp, PlainObject>, const Derived > RCmp ## COMPARATOR ## ReturnType; \ +EIGEN_STRONG_INLINE const Cmp ## COMPARATOR ## ReturnType \ +OP(const Scalar& s) const { \ + return this->OP(Derived::PlainObject::Constant(rows(), cols(), s)); \ +} \ +friend EIGEN_STRONG_INLINE const RCmp ## COMPARATOR ## ReturnType \ +OP(const Scalar& s, const Derived& d) { \ + return Derived::PlainObject::Constant(d.rows(), d.cols(), s).OP(d); \ +} + +#define EIGEN_MAKE_CWISE_COMP_R_OP(OP, R_OP, RCOMPARATOR) \ +template \ +EIGEN_STRONG_INLINE const CwiseBinaryOp, const OtherDerived, const Derived> \ +OP(const EIGEN_CURRENT_STORAGE_BASE_CLASS &other) const \ +{ \ + return CwiseBinaryOp, const OtherDerived, const Derived>(other.derived(), derived()); \ +} \ +\ +inline const RCmp ## RCOMPARATOR ## ReturnType \ +OP(const Scalar& s) const { \ + return Derived::PlainObject::Constant(rows(), cols(), s).R_OP(*this); \ +} \ +friend inline const Cmp ## RCOMPARATOR ## ReturnType \ +OP(const Scalar& s, const Derived& d) { \ + return d.R_OP(Derived::PlainObject::Constant(d.rows(), d.cols(), s)); \ +} + + /** \returns an expression of the coefficient-wise \< operator of *this and \a other * * Example: \include Cwise_less.cpp @@ -77,7 +114,7 @@ max * * \sa all(), any(), operator>(), operator<=() */ -EIGEN_MAKE_CWISE_BINARY_OP(operator<,std::less) +EIGEN_MAKE_CWISE_COMP_OP(operator<, LT) /** \returns an expression of the coefficient-wise \<= operator of *this and \a other * @@ -86,7 +123,7 @@ EIGEN_MAKE_CWISE_BINARY_OP(operator<,std::less) * * \sa all(), any(), operator>=(), operator<() */ -EIGEN_MAKE_CWISE_BINARY_OP(operator<=,std::less_equal) +EIGEN_MAKE_CWISE_COMP_OP(operator<=, LE) /** \returns an expression of the coefficient-wise \> operator of *this and \a other * @@ -95,7 +132,7 @@ EIGEN_MAKE_CWISE_BINARY_OP(operator<=,std::less_equal) * * \sa all(), any(), operator>=(), operator<() */ -EIGEN_MAKE_CWISE_BINARY_OP(operator>,std::greater) +EIGEN_MAKE_CWISE_COMP_R_OP(operator>, operator<, LT) /** \returns an expression of the coefficient-wise \>= operator of *this and \a other * @@ -104,7 +141,7 @@ EIGEN_MAKE_CWISE_BINARY_OP(operator>,std::greater) * * \sa all(), any(), operator>(), operator<=() */ -EIGEN_MAKE_CWISE_BINARY_OP(operator>=,std::greater_equal) +EIGEN_MAKE_CWISE_COMP_R_OP(operator>=, operator<=, LE) /** \returns an expression of the coefficient-wise == operator of *this and \a other * @@ -118,7 +155,7 @@ EIGEN_MAKE_CWISE_BINARY_OP(operator>=,std::greater_equal) * * \sa all(), any(), isApprox(), isMuchSmallerThan() */ -EIGEN_MAKE_CWISE_BINARY_OP(operator==,std::equal_to) +EIGEN_MAKE_CWISE_COMP_OP(operator==, EQ) /** \returns an expression of the coefficient-wise != operator of *this and \a other * @@ -132,7 +169,10 @@ EIGEN_MAKE_CWISE_BINARY_OP(operator==,std::equal_to) * * \sa all(), any(), isApprox(), isMuchSmallerThan() */ -EIGEN_MAKE_CWISE_BINARY_OP(operator!=,std::not_equal_to) +EIGEN_MAKE_CWISE_COMP_OP(operator!=, NEQ) + +#undef EIGEN_MAKE_CWISE_COMP_OP +#undef EIGEN_MAKE_CWISE_COMP_R_OP // scalar addition @@ -209,3 +249,5 @@ operator||(const EIGEN_CURRENT_STORAGE_BASE_CLASS &other) const THIS_METHOD_IS_ONLY_FOR_EXPRESSIONS_OF_BOOL); return CwiseBinaryOp(derived(),other.derived()); } + + diff --git a/gtsam/3rdparty/Eigen/Eigen/src/plugins/ArrayCwiseUnaryOps.h b/gtsam/3rdparty/Eigen/Eigen/src/plugins/ArrayCwiseUnaryOps.h index a59636790..1c3ed3fcd 100644 --- a/gtsam/3rdparty/Eigen/Eigen/src/plugins/ArrayCwiseUnaryOps.h +++ b/gtsam/3rdparty/Eigen/Eigen/src/plugins/ArrayCwiseUnaryOps.h @@ -185,19 +185,3 @@ cube() const { return derived(); } - -#define EIGEN_MAKE_SCALAR_CWISE_UNARY_OP(METHOD_NAME,FUNCTOR) \ - inline const CwiseUnaryOp >, const Derived> \ - METHOD_NAME(const Scalar& s) const { \ - return CwiseUnaryOp >, const Derived> \ - (derived(), std::bind2nd(FUNCTOR(), s)); \ - } - -EIGEN_MAKE_SCALAR_CWISE_UNARY_OP(operator==, std::equal_to) -EIGEN_MAKE_SCALAR_CWISE_UNARY_OP(operator!=, std::not_equal_to) -EIGEN_MAKE_SCALAR_CWISE_UNARY_OP(operator<, std::less) -EIGEN_MAKE_SCALAR_CWISE_UNARY_OP(operator<=, std::less_equal) -EIGEN_MAKE_SCALAR_CWISE_UNARY_OP(operator>, std::greater) -EIGEN_MAKE_SCALAR_CWISE_UNARY_OP(operator>=, std::greater_equal) - - diff --git a/gtsam/3rdparty/Eigen/Eigen/src/plugins/MatrixCwiseBinaryOps.h b/gtsam/3rdparty/Eigen/Eigen/src/plugins/MatrixCwiseBinaryOps.h index 7f62149e0..c4a042b70 100644 --- a/gtsam/3rdparty/Eigen/Eigen/src/plugins/MatrixCwiseBinaryOps.h +++ b/gtsam/3rdparty/Eigen/Eigen/src/plugins/MatrixCwiseBinaryOps.h @@ -124,3 +124,20 @@ cwiseQuotient(const EIGEN_CURRENT_STORAGE_BASE_CLASS &other) const { return CwiseBinaryOp, const Derived, const OtherDerived>(derived(), other.derived()); } + +typedef CwiseBinaryOp, const Derived, const ConstantReturnType> CwiseScalarEqualReturnType; + +/** \returns an expression of the coefficient-wise == operator of \c *this and a scalar \a s + * + * \warning this performs an exact comparison, which is generally a bad idea with floating-point types. + * In order to check for equality between two vectors or matrices with floating-point coefficients, it is + * generally a far better idea to use a fuzzy comparison as provided by isApprox() and + * isMuchSmallerThan(). + * + * \sa cwiseEqual(const MatrixBase &) const + */ +inline const CwiseScalarEqualReturnType +cwiseEqual(const Scalar& s) const +{ + return CwiseScalarEqualReturnType(derived(), Derived::Constant(rows(), cols(), s), internal::scalar_cmp_op()); +} diff --git a/gtsam/3rdparty/Eigen/Eigen/src/plugins/MatrixCwiseUnaryOps.h b/gtsam/3rdparty/Eigen/Eigen/src/plugins/MatrixCwiseUnaryOps.h index 0cf0640ba..8de10935d 100644 --- a/gtsam/3rdparty/Eigen/Eigen/src/plugins/MatrixCwiseUnaryOps.h +++ b/gtsam/3rdparty/Eigen/Eigen/src/plugins/MatrixCwiseUnaryOps.h @@ -50,18 +50,3 @@ cwiseSqrt() const { return derived(); } inline const CwiseUnaryOp, const Derived> cwiseInverse() const { return derived(); } -/** \returns an expression of the coefficient-wise == operator of \c *this and a scalar \a s - * - * \warning this performs an exact comparison, which is generally a bad idea with floating-point types. - * In order to check for equality between two vectors or matrices with floating-point coefficients, it is - * generally a far better idea to use a fuzzy comparison as provided by isApprox() and - * isMuchSmallerThan(). - * - * \sa cwiseEqual(const MatrixBase &) const - */ -inline const CwiseUnaryOp >, const Derived> -cwiseEqual(const Scalar& s) const -{ - return CwiseUnaryOp >,const Derived> - (derived(), std::bind1st(std::equal_to(), s)); -} diff --git a/gtsam/3rdparty/Eigen/blas/xerbla.cpp b/gtsam/3rdparty/Eigen/blas/xerbla.cpp index 0d57710fe..dd39a5244 100644 --- a/gtsam/3rdparty/Eigen/blas/xerbla.cpp +++ b/gtsam/3rdparty/Eigen/blas/xerbla.cpp @@ -1,7 +1,7 @@ #include -#if (defined __GNUC__) +#if (defined __GNUC__) && (!defined __MINGW32__) && (!defined __CYGWIN__) #define EIGEN_WEAK_LINKING __attribute__ ((weak)) #else #define EIGEN_WEAK_LINKING diff --git a/gtsam/3rdparty/Eigen/cmake/EigenConfigureTesting.cmake b/gtsam/3rdparty/Eigen/cmake/EigenConfigureTesting.cmake index 11ecc9585..2b11d8360 100644 --- a/gtsam/3rdparty/Eigen/cmake/EigenConfigureTesting.cmake +++ b/gtsam/3rdparty/Eigen/cmake/EigenConfigureTesting.cmake @@ -26,29 +26,18 @@ include(CTest) set(EIGEN_TEST_BUILD_FLAGS " " CACHE STRING "Options passed to the build command of unit tests") -# overwrite default DartConfiguration.tcl -# The worarounds are different for each version of the MSVC IDE -if(MSVC_IDE) - if(CMAKE_MAKE_PROGRAM_SAVE MATCHES "devenv") # devenv - set(EIGEN_MAKECOMMAND_PLACEHOLDER "${CMAKE_MAKE_PROGRAM_SAVE} Eigen.sln /build \"Release\" /project buildtests ${EIGEN_TEST_BUILD_FLAGS} \n# ") - else() # msbuild - set(EIGEN_MAKECOMMAND_PLACEHOLDER "${CMAKE_MAKE_PROGRAM_SAVE} buildtests.vcxproj /p:Configuration=\${CTEST_CONFIGURATION_TYPE} ${EIGEN_TEST_BUILD_FLAGS}\n# ") - endif() -else() - # for make and nmake - set(EIGEN_MAKECOMMAND_PLACEHOLDER "${CMAKE_MAKE_PROGRAM_SAVE} buildtests ${EIGEN_TEST_BUILD_FLAGS}") +# Overwrite default DartConfiguration.tcl such that ctest can build our unit tests. +# Recall that our unit tests are not in the "all" target, so we have to explicitely ask ctest to build our custom 'buildtests' target. +# At this stage, we can also add custom flags to the build tool through the user defined EIGEN_TEST_BUILD_FLAGS variable. +file(READ "${CMAKE_CURRENT_BINARY_DIR}/DartConfiguration.tcl" EIGEN_DART_CONFIG_FILE) +# try to grab the default flags +string(REGEX MATCH "MakeCommand:.*-- (.*)\nDefaultCTestConfigurationType" EIGEN_DUMMY ${EIGEN_DART_CONFIG_FILE}) +if(NOT CMAKE_MATCH_1) +string(REGEX MATCH "MakeCommand:.*[^c]make (.*)\nDefaultCTestConfigurationType" EIGEN_DUMMY ${EIGEN_DART_CONFIG_FILE}) endif() - -# copy ctest properties, which currently -# o raise the warning levels -configure_file(${CMAKE_CURRENT_BINARY_DIR}/DartConfiguration.tcl ${CMAKE_BINARY_DIR}/DartConfiguration.tcl) - -# restore default CMAKE_MAKE_PROGRAM -set(CMAKE_MAKE_PROGRAM ${CMAKE_MAKE_PROGRAM_SAVE}) -# un-set temporary variables so that it is like they never existed. -# CMake 2.6.3 introduces the more logical unset() syntax for this. -set(CMAKE_MAKE_PROGRAM_SAVE) -set(EIGEN_MAKECOMMAND_PLACEHOLDER) +string(REGEX REPLACE "MakeCommand:.*DefaultCTestConfigurationType" "MakeCommand: ${CMAKE_COMMAND} --build . --target buildtests --config \"\${CTEST_CONFIGURATION_TYPE}\" -- ${CMAKE_MATCH_1} ${EIGEN_TEST_BUILD_FLAGS}\nDefaultCTestConfigurationType" + EIGEN_DART_CONFIG_FILE2 ${EIGEN_DART_CONFIG_FILE}) +file(WRITE "${CMAKE_CURRENT_BINARY_DIR}/DartConfiguration.tcl" ${EIGEN_DART_CONFIG_FILE2}) configure_file(${CMAKE_CURRENT_SOURCE_DIR}/CTestCustom.cmake.in ${CMAKE_BINARY_DIR}/CTestCustom.cmake) diff --git a/gtsam/3rdparty/Eigen/cmake/EigenTesting.cmake b/gtsam/3rdparty/Eigen/cmake/EigenTesting.cmake index 80b2841df..cbe12d51b 100644 --- a/gtsam/3rdparty/Eigen/cmake/EigenTesting.cmake +++ b/gtsam/3rdparty/Eigen/cmake/EigenTesting.cmake @@ -322,22 +322,21 @@ macro(ei_get_compilerver VAR) endif() else() # on all other system we rely on ${CMAKE_CXX_COMPILER} - # supporting a "--version" flag + # supporting a "--version" or "/version" flag - # check whether the head command exists - find_program(HEAD_EXE head NO_CMAKE_ENVIRONMENT_PATH NO_CMAKE_PATH NO_CMAKE_SYSTEM_PATH) - if(HEAD_EXE) - execute_process(COMMAND ${CMAKE_CXX_COMPILER} --version - COMMAND head -n 1 - OUTPUT_VARIABLE eigen_cxx_compiler_version_string OUTPUT_STRIP_TRAILING_WHITESPACE) + if(WIN32 AND ${CMAKE_CXX_COMPILER_ID} EQUAL "Intel") + set(EIGEN_CXX_FLAG_VERSION "/version") else() - execute_process(COMMAND ${CMAKE_CXX_COMPILER} --version - OUTPUT_VARIABLE eigen_cxx_compiler_version_string OUTPUT_STRIP_TRAILING_WHITESPACE) - string(REGEX REPLACE "[\n\r].*" "" eigen_cxx_compiler_version_string ${eigen_cxx_compiler_version_string}) + set(EIGEN_CXX_FLAG_VERSION "--version") endif() + execute_process(COMMAND ${CMAKE_CXX_COMPILER} ${EIGEN_CXX_FLAG_VERSION} + OUTPUT_VARIABLE eigen_cxx_compiler_version_string OUTPUT_STRIP_TRAILING_WHITESPACE) + string(REGEX REPLACE "[\n\r].*" "" eigen_cxx_compiler_version_string ${eigen_cxx_compiler_version_string}) + ei_get_compilerver_from_cxx_version_string("${eigen_cxx_compiler_version_string}" CNAME CVER) set(${VAR} "${CNAME}-${CVER}") + endif() endmacro(ei_get_compilerver) diff --git a/gtsam/3rdparty/Eigen/cmake/FindMetis.cmake b/gtsam/3rdparty/Eigen/cmake/FindMetis.cmake index e0040d320..6a0ce790c 100644 --- a/gtsam/3rdparty/Eigen/cmake/FindMetis.cmake +++ b/gtsam/3rdparty/Eigen/cmake/FindMetis.cmake @@ -26,7 +26,7 @@ macro(_metis_check_version) string(REGEX MATCH "define[ \t]+METIS_VER_SUBMINOR[ \t]+([0-9]+)" _metis_subminor_version_match "${_metis_version_header}") set(METIS_SUBMINOR_VERSION "${CMAKE_MATCH_1}") if(NOT METIS_MAJOR_VERSION) - message(WARNING "Could not determine Metis version. Assuming version 4.0.0") + message(STATUS "Could not determine Metis version. Assuming version 4.0.0") set(METIS_VERSION 4.0.0) else() set(METIS_VERSION ${METIS_MAJOR_VERSION}.${METIS_MINOR_VERSION}.${METIS_SUBMINOR_VERSION}) diff --git a/gtsam/3rdparty/Eigen/cmake/FindSPQR.cmake b/gtsam/3rdparty/Eigen/cmake/FindSPQR.cmake index 794c212af..1e958c3c1 100644 --- a/gtsam/3rdparty/Eigen/cmake/FindSPQR.cmake +++ b/gtsam/3rdparty/Eigen/cmake/FindSPQR.cmake @@ -26,7 +26,12 @@ if(SPQR_LIBRARIES) find_library(SUITESPARSE_LIBRARY SuiteSparse PATHS $ENV{SPQRDIR} ${LIB_INSTALL_DIR}) if (SUITESPARSE_LIBRARY) set(SPQR_LIBRARIES ${SPQR_LIBRARIES} ${SUITESPARSE_LIBRARY}) - endif (SUITESPARSE_LIBRARY) + endif() + + find_library(CHOLMOD_LIBRARY cholmod PATHS $ENV{UMFPACK_LIBDIR} $ENV{UMFPACKDIR} ${LIB_INSTALL_DIR}) + if(CHOLMOD_LIBRARY) + set(SPQR_LIBRARIES ${SPQR_LIBRARIES} ${CHOLMOD_LIBRARY}) + endif() endif(SPQR_LIBRARIES) diff --git a/gtsam/3rdparty/Eigen/cmake/FindUmfpack.cmake b/gtsam/3rdparty/Eigen/cmake/FindUmfpack.cmake index 16b046cd6..53cf0b49b 100644 --- a/gtsam/3rdparty/Eigen/cmake/FindUmfpack.cmake +++ b/gtsam/3rdparty/Eigen/cmake/FindUmfpack.cmake @@ -20,24 +20,29 @@ find_library(UMFPACK_LIBRARIES umfpack PATHS $ENV{UMFPACKDIR} ${LIB_INSTALL_DIR} if(UMFPACK_LIBRARIES) - if (NOT UMFPACK_LIBDIR) + if(NOT UMFPACK_LIBDIR) get_filename_component(UMFPACK_LIBDIR ${UMFPACK_LIBRARIES} PATH) endif(NOT UMFPACK_LIBDIR) find_library(COLAMD_LIBRARY colamd PATHS ${UMFPACK_LIBDIR} $ENV{UMFPACKDIR} ${LIB_INSTALL_DIR}) - if (COLAMD_LIBRARY) + if(COLAMD_LIBRARY) set(UMFPACK_LIBRARIES ${UMFPACK_LIBRARIES} ${COLAMD_LIBRARY}) - endif (COLAMD_LIBRARY) + endif () find_library(AMD_LIBRARY amd PATHS ${UMFPACK_LIBDIR} $ENV{UMFPACKDIR} ${LIB_INSTALL_DIR}) - if (AMD_LIBRARY) + if(AMD_LIBRARY) set(UMFPACK_LIBRARIES ${UMFPACK_LIBRARIES} ${AMD_LIBRARY}) - endif (AMD_LIBRARY) + endif () find_library(SUITESPARSE_LIBRARY SuiteSparse PATHS ${UMFPACK_LIBDIR} $ENV{UMFPACKDIR} ${LIB_INSTALL_DIR}) - if (SUITESPARSE_LIBRARY) + if(SUITESPARSE_LIBRARY) set(UMFPACK_LIBRARIES ${UMFPACK_LIBRARIES} ${SUITESPARSE_LIBRARY}) - endif (SUITESPARSE_LIBRARY) + endif () + + find_library(CHOLMOD_LIBRARY cholmod PATHS $ENV{UMFPACK_LIBDIR} $ENV{UMFPACKDIR} ${LIB_INSTALL_DIR}) + if(CHOLMOD_LIBRARY) + set(UMFPACK_LIBRARIES ${UMFPACK_LIBRARIES} ${CHOLMOD_LIBRARY}) + endif() endif(UMFPACK_LIBRARIES) @@ -45,4 +50,4 @@ include(FindPackageHandleStandardArgs) find_package_handle_standard_args(UMFPACK DEFAULT_MSG UMFPACK_INCLUDES UMFPACK_LIBRARIES) -mark_as_advanced(UMFPACK_INCLUDES UMFPACK_LIBRARIES AMD_LIBRARY COLAMD_LIBRARY SUITESPARSE_LIBRARY) +mark_as_advanced(UMFPACK_INCLUDES UMFPACK_LIBRARIES AMD_LIBRARY COLAMD_LIBRARY CHOLMOD_LIBRARY SUITESPARSE_LIBRARY) diff --git a/gtsam/3rdparty/Eigen/doc/CMakeLists.txt b/gtsam/3rdparty/Eigen/doc/CMakeLists.txt index 8a493031c..2fc2a0dfc 100644 --- a/gtsam/3rdparty/Eigen/doc/CMakeLists.txt +++ b/gtsam/3rdparty/Eigen/doc/CMakeLists.txt @@ -91,7 +91,8 @@ add_custom_target(doc ALL COMMAND doxygen Doxyfile-unsupported COMMAND ${CMAKE_COMMAND} -E rename html eigen-doc COMMAND ${CMAKE_COMMAND} -E remove eigen-doc/eigen-doc.tgz - COMMAND ${CMAKE_COMMAND} -E tar cfz eigen-doc/eigen-doc.tgz eigen-doc + COMMAND ${CMAKE_COMMAND} -E tar cfz eigen-doc.tgz eigen-doc + COMMAND ${CMAKE_COMMAND} -E rename eigen-doc.tgz eigen-doc/eigen-doc.tgz COMMAND ${CMAKE_COMMAND} -E rename eigen-doc html WORKING_DIRECTORY ${Eigen_BINARY_DIR}/doc) diff --git a/gtsam/3rdparty/Eigen/doc/Doxyfile.in b/gtsam/3rdparty/Eigen/doc/Doxyfile.in index 1a2603b04..696dd2af1 100644 --- a/gtsam/3rdparty/Eigen/doc/Doxyfile.in +++ b/gtsam/3rdparty/Eigen/doc/Doxyfile.in @@ -222,7 +222,7 @@ ALIASES = "only_for_vectors=This is only for vectors (either row- "note_about_using_kernel_to_study_multiple_solutions=If you need a complete analysis of the space of solutions, take the one solution obtained by this method and add to it elements of the kernel, as determined by kernel()." \ "note_about_checking_solutions=This method just tries to find as good a solution as possible. If you want to check whether a solution exists or if it is accurate, just call this function to get a result and then compute the error of this result, or use MatrixBase::isApprox() directly, for instance like this: \code bool a_solution_exists = (A*result).isApprox(b, precision); \endcode This method avoids dividing by zero, so that the non-existence of a solution doesn't by itself mean that you'll get \c inf or \c nan values." \ "note_try_to_help_rvo=This function returns the result by value. In order to make that efficient, it is implemented as just a return statement using a special constructor, hopefully allowing the compiler to perform a RVO (return value optimization)." \ - "nonstableyet=\warning This is not considered to be part of the stable public API yet. Changes may happen in future releases. See \ref Experimental \"Experimental parts of Eigen\" + "nonstableyet=\warning This is not considered to be part of the stable public API yet. Changes may happen in future releases. See \ref Experimental \"Experimental parts of Eigen\"" ALIASES += "eigenAutoToc= " ALIASES += "eigenManualPage=\defgroup" @@ -315,7 +315,7 @@ IDL_PROPERTY_SUPPORT = YES # member in the group (if any) for the other members of the group. By default # all members of a group must be documented explicitly. -DISTRIBUTE_GROUP_DOC = NO +DISTRIBUTE_GROUP_DOC = YES # Set the SUBGROUPING tag to YES (the default) to allow class member groups of # the same type (for instance a group of public functions) to be put as a @@ -365,7 +365,7 @@ TYPEDEF_HIDES_STRUCT = NO # 2^(16+SYMBOL_CACHE_SIZE). The valid range is 0..9, the default is 0, # corresponding to a cache size of 2^16 = 65536 symbols. -SYMBOL_CACHE_SIZE = 0 +# SYMBOL_CACHE_SIZE = 0 # Similar to the SYMBOL_CACHE_SIZE the size of the symbol lookup cache can be # set using LOOKUP_CACHE_SIZE. This cache is used to resolve symbols given @@ -562,7 +562,7 @@ GENERATE_BUGLIST = NO # disable (NO) the deprecated list. This list is created by putting # \deprecated commands in the documentation. -GENERATE_DEPRECATEDLIST= NO +GENERATE_DEPRECATEDLIST= YES # The ENABLED_SECTIONS tag can be used to enable conditional # documentation sections, marked by \if sectionname ... \endif. @@ -1465,13 +1465,13 @@ XML_OUTPUT = xml # which can be used by a validating XML parser to check the # syntax of the XML files. -XML_SCHEMA = +# XML_SCHEMA = # The XML_DTD tag can be used to specify an XML DTD, # which can be used by a validating XML parser to check the # syntax of the XML files. -XML_DTD = +# XML_DTD = # If the XML_PROGRAMLISTING tag is set to YES Doxygen will # dump the program listings (including syntax highlighting @@ -1699,7 +1699,7 @@ DOT_NUM_THREADS = 0 # the DOTFONTPATH environment variable or by setting DOT_FONTPATH to the # directory containing the font. -DOT_FONTNAME = FreeSans +DOT_FONTNAME = # The DOT_FONTSIZE tag can be used to set the size of the font of dot graphs. # The default size is 10pt. diff --git a/gtsam/3rdparty/Eigen/doc/Manual.dox b/gtsam/3rdparty/Eigen/doc/Manual.dox index 3367982ca..55057d213 100644 --- a/gtsam/3rdparty/Eigen/doc/Manual.dox +++ b/gtsam/3rdparty/Eigen/doc/Manual.dox @@ -11,6 +11,7 @@ namespace Eigen { - \subpage TopicCustomizingEigen - \subpage TopicMultiThreading - \subpage TopicUsingIntelMKL + - \subpage TopicPitfalls - \subpage TopicTemplateKeyword - \subpage UserManual_UnderstandingEigen */ diff --git a/gtsam/3rdparty/Eigen/doc/Pitfalls.dox b/gtsam/3rdparty/Eigen/doc/Pitfalls.dox new file mode 100644 index 000000000..cf42effef --- /dev/null +++ b/gtsam/3rdparty/Eigen/doc/Pitfalls.dox @@ -0,0 +1,38 @@ +namespace Eigen { + +/** \page TopicPitfalls Common pitfalls + +\section TopicPitfalls_template_keyword Compilation error with template methods + +See this \link TopicTemplateKeyword page \endlink. + +\section TopicPitfalls_auto_keyword C++11 and the auto keyword + +In short: do not use the auto keywords with Eigen's expressions, unless you are 100% sure about what you are doing. In particular, do not use the auto keyword as a replacement for a Matrix<> type. Here is an example: + +\code +MatrixXd A, B; +auto C = A*B; +for(...) { ... w = C * v; ...} +\endcode + +In this example, the type of C is not a MatrixXd but an abstract expression representing a matrix product and storing references to A and B. Therefore, the product of A*B will be carried out multiple times, once per iteration of the for loop. Moreover, if the coefficients of A or B change during the iteration, then C will evaluate to different values. + +Here is another example leading to a segfault: +\code +auto C = ((A+B).eval()).transpose(); +// do something with C +\endcode +The problem is that eval() returns a temporary object (in this case a MatrixXd) which is then referenced by the Transpose<> expression. However, this temporary is deleted right after the first line, and there the C expression reference a dead object. The same issue might occur when sub expressions are automatically evaluated by Eigen as in the following example: +\code +VectorXd u, v; +auto C = u + (A*v).normalized(); +// do something with C +\endcode +where the normalized() method has to evaluate the expensive product A*v to avoid evaluating it twice. On the other hand, the following example is perfectly fine: +\code +auto C = (u + (A*v).normalized()).eval(); +\endcode +In this case, C will be a regular VectorXd object. +*/ +} diff --git a/gtsam/3rdparty/Eigen/doc/TopicMultithreading.dox b/gtsam/3rdparty/Eigen/doc/TopicMultithreading.dox index f7d082668..7db2b0e07 100644 --- a/gtsam/3rdparty/Eigen/doc/TopicMultithreading.dox +++ b/gtsam/3rdparty/Eigen/doc/TopicMultithreading.dox @@ -17,7 +17,7 @@ You can control the number of thread that will be used using either the OpenMP A Unless setNbThreads has been called, Eigen uses the number of threads specified by OpenMP. You can restore this bahavior by calling \code setNbThreads(0); \endcode You can query the number of threads that will be used with: \code -n = Eigen::nbThreads(n); +n = Eigen::nbThreads( ); \endcode You can disable Eigen's multi threading at compile time by defining the EIGEN_DONT_PARALLELIZE preprocessor token. diff --git a/gtsam/3rdparty/Eigen/doc/UsingIntelMKL.dox b/gtsam/3rdparty/Eigen/doc/UsingIntelMKL.dox index 4b624a156..84db992b6 100644 --- a/gtsam/3rdparty/Eigen/doc/UsingIntelMKL.dox +++ b/gtsam/3rdparty/Eigen/doc/UsingIntelMKL.dox @@ -40,7 +40,8 @@ Since Eigen version 3.1 and later, users can benefit from built-in Intel MKL opt Intel MKL provides highly optimized multi-threaded mathematical routines for x86-compatible architectures. Intel MKL is available on Linux, Mac and Windows for both Intel64 and IA32 architectures. -\warning Be aware that Intel® MKL is a proprietary software. It is the responsibility of the users to buy MKL licenses for their products. Moreover, the license of the user product has to allow linking to proprietary software that excludes any unmodified versions of the GPL. +\note +Intel® MKL is a proprietary software and it is the responsibility of users to buy or register for community (free) Intel MKL licenses for their products. Moreover, the license of the user product has to allow linking to proprietary software that excludes any unmodified versions of the GPL. Using Intel MKL through Eigen is easy: -# define the \c EIGEN_USE_MKL_ALL macro before including any Eigen's header diff --git a/gtsam/3rdparty/Eigen/doc/special_examples/CMakeLists.txt b/gtsam/3rdparty/Eigen/doc/special_examples/CMakeLists.txt index f8a0148c8..3ab75dbfe 100644 --- a/gtsam/3rdparty/Eigen/doc/special_examples/CMakeLists.txt +++ b/gtsam/3rdparty/Eigen/doc/special_examples/CMakeLists.txt @@ -10,9 +10,10 @@ if(QT4_FOUND) target_link_libraries(Tutorial_sparse_example ${EIGEN_STANDARD_LIBRARIES_TO_LINK_TO} ${QT_QTCORE_LIBRARY} ${QT_QTGUI_LIBRARY}) add_custom_command( - TARGET Tutorial_sparse_example - POST_BUILD - COMMAND Tutorial_sparse_example ARGS ${CMAKE_CURRENT_BINARY_DIR}/../html/Tutorial_sparse_example.jpeg + TARGET Tutorial_sparse_example + POST_BUILD + COMMAND ${CMAKE_COMMAND} -E make_directory ${CMAKE_CURRENT_BINARY_DIR}/../html/ + COMMAND Tutorial_sparse_example ARGS ${CMAKE_CURRENT_BINARY_DIR}/../html/Tutorial_sparse_example.jpeg ) add_dependencies(all_examples Tutorial_sparse_example) diff --git a/gtsam/3rdparty/Eigen/failtest/CMakeLists.txt b/gtsam/3rdparty/Eigen/failtest/CMakeLists.txt index 5c4860237..cadc6a255 100644 --- a/gtsam/3rdparty/Eigen/failtest/CMakeLists.txt +++ b/gtsam/3rdparty/Eigen/failtest/CMakeLists.txt @@ -32,6 +32,17 @@ ei_add_failtest("ref_3") ei_add_failtest("ref_4") ei_add_failtest("ref_5") +ei_add_failtest("partialpivlu_int") +ei_add_failtest("fullpivlu_int") +ei_add_failtest("llt_int") +ei_add_failtest("ldlt_int") +ei_add_failtest("qr_int") +ei_add_failtest("colpivqr_int") +ei_add_failtest("fullpivqr_int") +ei_add_failtest("jacobisvd_int") +ei_add_failtest("eigensolver_int") +ei_add_failtest("eigensolver_cplx") + if (EIGEN_FAILTEST_FAILURE_COUNT) message(FATAL_ERROR "${EIGEN_FAILTEST_FAILURE_COUNT} out of ${EIGEN_FAILTEST_COUNT} failtests FAILED. " diff --git a/gtsam/3rdparty/Eigen/failtest/colpivqr_int.cpp b/gtsam/3rdparty/Eigen/failtest/colpivqr_int.cpp new file mode 100644 index 000000000..db11910d4 --- /dev/null +++ b/gtsam/3rdparty/Eigen/failtest/colpivqr_int.cpp @@ -0,0 +1,14 @@ +#include "../Eigen/QR" + +#ifdef EIGEN_SHOULD_FAIL_TO_BUILD +#define SCALAR int +#else +#define SCALAR float +#endif + +using namespace Eigen; + +int main() +{ + ColPivHouseholderQR > qr(Matrix::Random(10,10)); +} diff --git a/gtsam/3rdparty/Eigen/failtest/eigensolver_cplx.cpp b/gtsam/3rdparty/Eigen/failtest/eigensolver_cplx.cpp new file mode 100644 index 000000000..c2e21e189 --- /dev/null +++ b/gtsam/3rdparty/Eigen/failtest/eigensolver_cplx.cpp @@ -0,0 +1,14 @@ +#include "../Eigen/Eigenvalues" + +#ifdef EIGEN_SHOULD_FAIL_TO_BUILD +#define SCALAR std::complex +#else +#define SCALAR float +#endif + +using namespace Eigen; + +int main() +{ + EigenSolver > eig(Matrix::Random(10,10)); +} diff --git a/gtsam/3rdparty/Eigen/failtest/eigensolver_int.cpp b/gtsam/3rdparty/Eigen/failtest/eigensolver_int.cpp new file mode 100644 index 000000000..eda8dc20b --- /dev/null +++ b/gtsam/3rdparty/Eigen/failtest/eigensolver_int.cpp @@ -0,0 +1,14 @@ +#include "../Eigen/Eigenvalues" + +#ifdef EIGEN_SHOULD_FAIL_TO_BUILD +#define SCALAR int +#else +#define SCALAR float +#endif + +using namespace Eigen; + +int main() +{ + EigenSolver > eig(Matrix::Random(10,10)); +} diff --git a/gtsam/3rdparty/Eigen/failtest/fullpivlu_int.cpp b/gtsam/3rdparty/Eigen/failtest/fullpivlu_int.cpp new file mode 100644 index 000000000..e9d2c6eb3 --- /dev/null +++ b/gtsam/3rdparty/Eigen/failtest/fullpivlu_int.cpp @@ -0,0 +1,14 @@ +#include "../Eigen/LU" + +#ifdef EIGEN_SHOULD_FAIL_TO_BUILD +#define SCALAR int +#else +#define SCALAR float +#endif + +using namespace Eigen; + +int main() +{ + FullPivLU > lu(Matrix::Random(10,10)); +} diff --git a/gtsam/3rdparty/Eigen/failtest/fullpivqr_int.cpp b/gtsam/3rdparty/Eigen/failtest/fullpivqr_int.cpp new file mode 100644 index 000000000..d182a7b6b --- /dev/null +++ b/gtsam/3rdparty/Eigen/failtest/fullpivqr_int.cpp @@ -0,0 +1,14 @@ +#include "../Eigen/QR" + +#ifdef EIGEN_SHOULD_FAIL_TO_BUILD +#define SCALAR int +#else +#define SCALAR float +#endif + +using namespace Eigen; + +int main() +{ + FullPivHouseholderQR > qr(Matrix::Random(10,10)); +} diff --git a/gtsam/3rdparty/Eigen/failtest/jacobisvd_int.cpp b/gtsam/3rdparty/Eigen/failtest/jacobisvd_int.cpp new file mode 100644 index 000000000..12790aef1 --- /dev/null +++ b/gtsam/3rdparty/Eigen/failtest/jacobisvd_int.cpp @@ -0,0 +1,14 @@ +#include "../Eigen/SVD" + +#ifdef EIGEN_SHOULD_FAIL_TO_BUILD +#define SCALAR int +#else +#define SCALAR float +#endif + +using namespace Eigen; + +int main() +{ + JacobiSVD > qr(Matrix::Random(10,10)); +} diff --git a/gtsam/3rdparty/Eigen/failtest/ldlt_int.cpp b/gtsam/3rdparty/Eigen/failtest/ldlt_int.cpp new file mode 100644 index 000000000..243e45746 --- /dev/null +++ b/gtsam/3rdparty/Eigen/failtest/ldlt_int.cpp @@ -0,0 +1,14 @@ +#include "../Eigen/Cholesky" + +#ifdef EIGEN_SHOULD_FAIL_TO_BUILD +#define SCALAR int +#else +#define SCALAR float +#endif + +using namespace Eigen; + +int main() +{ + LDLT > ldlt(Matrix::Random(10,10)); +} diff --git a/gtsam/3rdparty/Eigen/failtest/llt_int.cpp b/gtsam/3rdparty/Eigen/failtest/llt_int.cpp new file mode 100644 index 000000000..cb020650d --- /dev/null +++ b/gtsam/3rdparty/Eigen/failtest/llt_int.cpp @@ -0,0 +1,14 @@ +#include "../Eigen/Cholesky" + +#ifdef EIGEN_SHOULD_FAIL_TO_BUILD +#define SCALAR int +#else +#define SCALAR float +#endif + +using namespace Eigen; + +int main() +{ + LLT > llt(Matrix::Random(10,10)); +} diff --git a/gtsam/3rdparty/Eigen/failtest/partialpivlu_int.cpp b/gtsam/3rdparty/Eigen/failtest/partialpivlu_int.cpp new file mode 100644 index 000000000..98ef282ea --- /dev/null +++ b/gtsam/3rdparty/Eigen/failtest/partialpivlu_int.cpp @@ -0,0 +1,14 @@ +#include "../Eigen/LU" + +#ifdef EIGEN_SHOULD_FAIL_TO_BUILD +#define SCALAR int +#else +#define SCALAR float +#endif + +using namespace Eigen; + +int main() +{ + PartialPivLU > lu(Matrix::Random(10,10)); +} diff --git a/gtsam/3rdparty/Eigen/failtest/qr_int.cpp b/gtsam/3rdparty/Eigen/failtest/qr_int.cpp new file mode 100644 index 000000000..ce200e818 --- /dev/null +++ b/gtsam/3rdparty/Eigen/failtest/qr_int.cpp @@ -0,0 +1,14 @@ +#include "../Eigen/QR" + +#ifdef EIGEN_SHOULD_FAIL_TO_BUILD +#define SCALAR int +#else +#define SCALAR float +#endif + +using namespace Eigen; + +int main() +{ + HouseholderQR > qr(Matrix::Random(10,10)); +} diff --git a/gtsam/3rdparty/Eigen/failtest/ref_1.cpp b/gtsam/3rdparty/Eigen/failtest/ref_1.cpp new file mode 100644 index 000000000..8b798d53d --- /dev/null +++ b/gtsam/3rdparty/Eigen/failtest/ref_1.cpp @@ -0,0 +1,18 @@ +#include "../Eigen/Core" + +#ifdef EIGEN_SHOULD_FAIL_TO_BUILD +#define CV_QUALIFIER const +#else +#define CV_QUALIFIER +#endif + +using namespace Eigen; + +void call_ref(Ref a) { } + +int main() +{ + VectorXf a(10); + CV_QUALIFIER VectorXf& ac(a); + call_ref(ac); +} diff --git a/gtsam/3rdparty/Eigen/failtest/ref_2.cpp b/gtsam/3rdparty/Eigen/failtest/ref_2.cpp new file mode 100644 index 000000000..0b779ccf5 --- /dev/null +++ b/gtsam/3rdparty/Eigen/failtest/ref_2.cpp @@ -0,0 +1,15 @@ +#include "../Eigen/Core" + +using namespace Eigen; + +void call_ref(Ref a) { } + +int main() +{ + MatrixXf A(10,10); +#ifdef EIGEN_SHOULD_FAIL_TO_BUILD + call_ref(A.row(3)); +#else + call_ref(A.col(3)); +#endif +} diff --git a/gtsam/3rdparty/Eigen/failtest/ref_3.cpp b/gtsam/3rdparty/Eigen/failtest/ref_3.cpp new file mode 100644 index 000000000..f46027d48 --- /dev/null +++ b/gtsam/3rdparty/Eigen/failtest/ref_3.cpp @@ -0,0 +1,15 @@ +#include "../Eigen/Core" + +using namespace Eigen; + +#ifdef EIGEN_SHOULD_FAIL_TO_BUILD +void call_ref(Ref a) { } +#else +void call_ref(const Ref &a) { } +#endif + +int main() +{ + VectorXf a(10); + call_ref(a+a); +} diff --git a/gtsam/3rdparty/Eigen/failtest/ref_4.cpp b/gtsam/3rdparty/Eigen/failtest/ref_4.cpp new file mode 100644 index 000000000..6c11fa4cb --- /dev/null +++ b/gtsam/3rdparty/Eigen/failtest/ref_4.cpp @@ -0,0 +1,15 @@ +#include "../Eigen/Core" + +using namespace Eigen; + +void call_ref(Ref > a) {} + +int main() +{ + MatrixXf A(10,10); +#ifdef EIGEN_SHOULD_FAIL_TO_BUILD + call_ref(A.transpose()); +#else + call_ref(A); +#endif +} diff --git a/gtsam/3rdparty/Eigen/failtest/ref_5.cpp b/gtsam/3rdparty/Eigen/failtest/ref_5.cpp new file mode 100644 index 000000000..846d52795 --- /dev/null +++ b/gtsam/3rdparty/Eigen/failtest/ref_5.cpp @@ -0,0 +1,16 @@ +#include "../Eigen/Core" + +using namespace Eigen; + +void call_ref(Ref a) { } + +int main() +{ + VectorXf a(10); + DenseBase &ac(a); +#ifdef EIGEN_SHOULD_FAIL_TO_BUILD + call_ref(ac); +#else + call_ref(ac.derived()); +#endif +} diff --git a/gtsam/3rdparty/Eigen/test/CMakeLists.txt b/gtsam/3rdparty/Eigen/test/CMakeLists.txt index d32451df6..3739268d2 100644 --- a/gtsam/3rdparty/Eigen/test/CMakeLists.txt +++ b/gtsam/3rdparty/Eigen/test/CMakeLists.txt @@ -222,6 +222,8 @@ ei_add_test(sizeoverflow) ei_add_test(prec_inverse_4x4) ei_add_test(vectorwiseop) ei_add_test(special_numbers) +ei_add_test(rvalue_types) +ei_add_test(mpl2only) ei_add_test(simplicial_cholesky) ei_add_test(conjugate_gradient) @@ -283,3 +285,9 @@ mark_as_advanced(EIGEN_TEST_EIGEN2) if(EIGEN_TEST_EIGEN2) add_subdirectory(eigen2) endif() + + +option(EIGEN_TEST_BUILD_DOCUMENTATION "Test building the doxygen documentation" OFF) +IF(EIGEN_TEST_BUILD_DOCUMENTATION) + add_dependencies(buildtests doc) +ENDIF() diff --git a/gtsam/3rdparty/Eigen/test/array.cpp b/gtsam/3rdparty/Eigen/test/array.cpp index c607da631..68f6b3d7a 100644 --- a/gtsam/3rdparty/Eigen/test/array.cpp +++ b/gtsam/3rdparty/Eigen/test/array.cpp @@ -109,6 +109,8 @@ template void comparisons(const ArrayType& m) VERIFY(! (m1 < m3).all() ); VERIFY(! (m1 > m3).all() ); } + VERIFY(!(m1 > m2 && m1 < m2).any()); + VERIFY((m1 <= m2 || m1 >= m2).all()); // comparisons to scalar VERIFY( (m1 != (m1(r,c)+1) ).any() ); diff --git a/gtsam/3rdparty/Eigen/test/array_for_matrix.cpp b/gtsam/3rdparty/Eigen/test/array_for_matrix.cpp index 9a50f99ab..9667e1f14 100644 --- a/gtsam/3rdparty/Eigen/test/array_for_matrix.cpp +++ b/gtsam/3rdparty/Eigen/test/array_for_matrix.cpp @@ -102,6 +102,7 @@ template void comparisons(const MatrixType& m) VERIFY( (m1.array() > (m1(r,c)-1) ).any() ); VERIFY( (m1.array() < (m1(r,c)+1) ).any() ); VERIFY( (m1.array() == m1(r,c) ).any() ); + VERIFY( m1.cwiseEqual(m1(r,c)).any() ); // test Select VERIFY_IS_APPROX( (m1.array() void test_conjugate_gradient_T() { - ConjugateGradient, Lower> cg_colmajor_lower_diag; - ConjugateGradient, Upper> cg_colmajor_upper_diag; + ConjugateGradient, Lower > cg_colmajor_lower_diag; + ConjugateGradient, Upper > cg_colmajor_upper_diag; + ConjugateGradient, Lower|Upper> cg_colmajor_loup_diag; ConjugateGradient, Lower, IdentityPreconditioner> cg_colmajor_lower_I; ConjugateGradient, Upper, IdentityPreconditioner> cg_colmajor_upper_I; CALL_SUBTEST( check_sparse_spd_solving(cg_colmajor_lower_diag) ); CALL_SUBTEST( check_sparse_spd_solving(cg_colmajor_upper_diag) ); + CALL_SUBTEST( check_sparse_spd_solving(cg_colmajor_loup_diag) ); CALL_SUBTEST( check_sparse_spd_solving(cg_colmajor_lower_I) ); CALL_SUBTEST( check_sparse_spd_solving(cg_colmajor_upper_I) ); } diff --git a/gtsam/3rdparty/Eigen/test/geo_alignedbox.cpp b/gtsam/3rdparty/Eigen/test/geo_alignedbox.cpp index 8e36adbe3..84663ad1f 100644 --- a/gtsam/3rdparty/Eigen/test/geo_alignedbox.cpp +++ b/gtsam/3rdparty/Eigen/test/geo_alignedbox.cpp @@ -172,6 +172,8 @@ void test_geo_alignedbox() CALL_SUBTEST_9( alignedbox(AlignedBox1i()) ); CALL_SUBTEST_10( alignedbox(AlignedBox2i()) ); CALL_SUBTEST_11( alignedbox(AlignedBox3i()) ); + + CALL_SUBTEST_14( alignedbox(AlignedBox(4)) ); } CALL_SUBTEST_12( specificTest1() ); CALL_SUBTEST_13( specificTest2() ); diff --git a/gtsam/3rdparty/Eigen/test/lu.cpp b/gtsam/3rdparty/Eigen/test/lu.cpp index 25f86755a..374652694 100644 --- a/gtsam/3rdparty/Eigen/test/lu.cpp +++ b/gtsam/3rdparty/Eigen/test/lu.cpp @@ -100,7 +100,9 @@ template void lu_invertible() LU.h */ typedef typename NumTraits::Real RealScalar; - int size = internal::random(1,EIGEN_TEST_MAX_SIZE); + DenseIndex size = MatrixType::RowsAtCompileTime; + if( size==Dynamic) + size = internal::random(1,EIGEN_TEST_MAX_SIZE); MatrixType m1(size, size), m2(size, size), m3(size, size); FullPivLU lu; @@ -122,6 +124,10 @@ template void lu_invertible() m2 = lu.solve(m3); VERIFY_IS_APPROX(m3, m1*m2); VERIFY_IS_APPROX(m2, lu.inverse()*m3); + + // Regression test for Bug 302 + MatrixType m4 = MatrixType::Random(size,size); + VERIFY_IS_APPROX(lu.solve(m3*m4), lu.solve(m3)*m4); } template void lu_partial_piv() @@ -171,6 +177,7 @@ void test_lu() { for(int i = 0; i < g_repeat; i++) { CALL_SUBTEST_1( lu_non_invertible() ); + CALL_SUBTEST_1( lu_invertible() ); CALL_SUBTEST_1( lu_verify_assert() ); CALL_SUBTEST_2( (lu_non_invertible >()) ); diff --git a/gtsam/3rdparty/Eigen/test/mapped_matrix.cpp b/gtsam/3rdparty/Eigen/test/mapped_matrix.cpp index de9dbbde3..58904fa37 100644 --- a/gtsam/3rdparty/Eigen/test/mapped_matrix.cpp +++ b/gtsam/3rdparty/Eigen/test/mapped_matrix.cpp @@ -114,6 +114,28 @@ template void check_const_correctness(const PlainObjec VERIFY( !(Map::Flags & LvalueBit) ); } +template +void map_not_aligned_on_scalar() +{ + typedef Matrix MatrixType; + typedef typename MatrixType::Index Index; + Index size = 11; + Scalar* array1 = internal::aligned_new((size+1)*(size+1)+1); + Scalar* array2 = reinterpret_cast(sizeof(Scalar)/2+std::size_t(array1)); + Map > map2(array2, size, size, OuterStride<>(size+1)); + MatrixType m2 = MatrixType::Random(size,size); + map2 = m2; + VERIFY_IS_EQUAL(m2, map2); + + typedef Matrix VectorType; + Map map3(array2, size); + MatrixType v3 = VectorType::Random(size); + map3 = v3; + VERIFY_IS_EQUAL(v3, map3); + + internal::aligned_delete(array1, (size+1)*(size+1)+1); +} + void test_mapped_matrix() { for(int i = 0; i < g_repeat; i++) { @@ -137,5 +159,7 @@ void test_mapped_matrix() CALL_SUBTEST_8( map_static_methods(RowVector3d()) ); CALL_SUBTEST_9( map_static_methods(VectorXcd(8)) ); CALL_SUBTEST_10( map_static_methods(VectorXf(12)) ); + + CALL_SUBTEST_11( map_not_aligned_on_scalar() ); } } diff --git a/gtsam/3rdparty/Eigen/test/product_extra.cpp b/gtsam/3rdparty/Eigen/test/product_extra.cpp index 744a1ef7f..ea2486937 100644 --- a/gtsam/3rdparty/Eigen/test/product_extra.cpp +++ b/gtsam/3rdparty/Eigen/test/product_extra.cpp @@ -109,8 +109,67 @@ void mat_mat_scalar_scalar_product() double det = 6.0, wt = 0.5; VERIFY_IS_APPROX(dNdxy.transpose()*dNdxy*det*wt, det*wt*dNdxy.transpose()*dNdxy); } + +template +void zero_sized_objects(const MatrixType& m) +{ + typedef typename MatrixType::Scalar Scalar; + const int PacketSize = internal::packet_traits::size; + const int PacketSize1 = PacketSize>1 ? PacketSize-1 : 1; + DenseIndex rows = m.rows(); + DenseIndex cols = m.cols(); -void zero_sized_objects() + { + MatrixType res, a(rows,0), b(0,cols); + VERIFY_IS_APPROX( (res=a*b), MatrixType::Zero(rows,cols) ); + VERIFY_IS_APPROX( (res=a*a.transpose()), MatrixType::Zero(rows,rows) ); + VERIFY_IS_APPROX( (res=b.transpose()*b), MatrixType::Zero(cols,cols) ); + VERIFY_IS_APPROX( (res=b.transpose()*a.transpose()), MatrixType::Zero(cols,rows) ); + } + + { + MatrixType res, a(rows,cols), b(cols,0); + res = a*b; + VERIFY(res.rows()==rows && res.cols()==0); + b.resize(0,rows); + res = b*a; + VERIFY(res.rows()==0 && res.cols()==cols); + } + + { + Matrix a; + Matrix b; + Matrix res; + VERIFY_IS_APPROX( (res=a*b), MatrixType::Zero(PacketSize,1) ); + VERIFY_IS_APPROX( (res=a.lazyProduct(b)), MatrixType::Zero(PacketSize,1) ); + } + + { + Matrix a; + Matrix b; + Matrix res; + VERIFY_IS_APPROX( (res=a*b), MatrixType::Zero(PacketSize1,1) ); + VERIFY_IS_APPROX( (res=a.lazyProduct(b)), MatrixType::Zero(PacketSize1,1) ); + } + + { + Matrix a(PacketSize,0); + Matrix b(0,1); + Matrix res; + VERIFY_IS_APPROX( (res=a*b), MatrixType::Zero(PacketSize,1) ); + VERIFY_IS_APPROX( (res=a.lazyProduct(b)), MatrixType::Zero(PacketSize,1) ); + } + + { + Matrix a(PacketSize1,0); + Matrix b(0,1); + Matrix res; + VERIFY_IS_APPROX( (res=a*b), MatrixType::Zero(PacketSize1,1) ); + VERIFY_IS_APPROX( (res=a.lazyProduct(b)), MatrixType::Zero(PacketSize1,1) ); + } +} + +void bug_127() { // Bug 127 // @@ -171,7 +230,8 @@ void test_product_extra() CALL_SUBTEST_2( mat_mat_scalar_scalar_product() ); CALL_SUBTEST_3( product_extra(MatrixXcf(internal::random(1,EIGEN_TEST_MAX_SIZE/2), internal::random(1,EIGEN_TEST_MAX_SIZE/2))) ); CALL_SUBTEST_4( product_extra(MatrixXcd(internal::random(1,EIGEN_TEST_MAX_SIZE/2), internal::random(1,EIGEN_TEST_MAX_SIZE/2))) ); + CALL_SUBTEST_1( zero_sized_objects(MatrixXf(internal::random(1,EIGEN_TEST_MAX_SIZE), internal::random(1,EIGEN_TEST_MAX_SIZE))) ); } - CALL_SUBTEST_5( zero_sized_objects() ); + CALL_SUBTEST_5( bug_127() ); CALL_SUBTEST_6( unaligned_objects() ); } diff --git a/gtsam/3rdparty/Eigen/test/product_mmtr.cpp b/gtsam/3rdparty/Eigen/test/product_mmtr.cpp index 7d6746800..aeba009f4 100644 --- a/gtsam/3rdparty/Eigen/test/product_mmtr.cpp +++ b/gtsam/3rdparty/Eigen/test/product_mmtr.cpp @@ -24,8 +24,8 @@ template void mmtr(int size) DenseIndex othersize = internal::random(1,200); - MatrixColMaj matc(size, size); - MatrixRowMaj matr(size, size); + MatrixColMaj matc = MatrixColMaj::Zero(size, size); + MatrixRowMaj matr = MatrixRowMaj::Zero(size, size); MatrixColMaj ref1(size, size), ref2(size, size); MatrixColMaj soc(size,othersize); soc.setRandom(); diff --git a/gtsam/3rdparty/Eigen/test/real_qz.cpp b/gtsam/3rdparty/Eigen/test/real_qz.cpp index 7d743a734..a1766c6d9 100644 --- a/gtsam/3rdparty/Eigen/test/real_qz.cpp +++ b/gtsam/3rdparty/Eigen/test/real_qz.cpp @@ -25,6 +25,22 @@ template void real_qz(const MatrixType& m) MatrixType A = MatrixType::Random(dim,dim), B = MatrixType::Random(dim,dim); + + // Regression test for bug 985: Randomly set rows or columns to zero + Index k=internal::random(0, dim-1); + switch(internal::random(0,10)) { + case 0: + A.row(k).setZero(); break; + case 1: + A.col(k).setZero(); break; + case 2: + B.row(k).setZero(); break; + case 3: + B.col(k).setZero(); break; + default: + break; + } + RealQZ qz(A,B); VERIFY_IS_EQUAL(qz.info(), Success); diff --git a/gtsam/3rdparty/Eigen/test/redux.cpp b/gtsam/3rdparty/Eigen/test/redux.cpp index 0d176e500..50b473838 100644 --- a/gtsam/3rdparty/Eigen/test/redux.cpp +++ b/gtsam/3rdparty/Eigen/test/redux.cpp @@ -53,6 +53,14 @@ template void matrixRedux(const MatrixType& m) VERIFY_IS_APPROX(m1_for_prod.block(r0,c0,r1,c1).prod(), m1_for_prod.block(r0,c0,r1,c1).eval().prod()); VERIFY_IS_APPROX(m1.block(r0,c0,r1,c1).real().minCoeff(), m1.block(r0,c0,r1,c1).real().eval().minCoeff()); VERIFY_IS_APPROX(m1.block(r0,c0,r1,c1).real().maxCoeff(), m1.block(r0,c0,r1,c1).real().eval().maxCoeff()); + + // regression for bug 1090 + const int R1 = MatrixType::RowsAtCompileTime>=2 ? MatrixType::RowsAtCompileTime/2 : 6; + const int C1 = MatrixType::ColsAtCompileTime>=2 ? MatrixType::ColsAtCompileTime/2 : 6; + if(R1<=rows-r0 && C1<=cols-c0) + { + VERIFY_IS_APPROX( (m1.template block(r0,c0).sum()), m1.block(r0,c0,R1,C1).sum() ); + } // test empty objects VERIFY_IS_APPROX(m1.block(r0,c0,0,0).sum(), Scalar(0)); diff --git a/gtsam/3rdparty/Eigen/test/ref.cpp b/gtsam/3rdparty/Eigen/test/ref.cpp index 32eb31048..44bbd3bf1 100644 --- a/gtsam/3rdparty/Eigen/test/ref.cpp +++ b/gtsam/3rdparty/Eigen/test/ref.cpp @@ -229,6 +229,28 @@ void call_ref() VERIFY_EVALUATION_COUNT( call_ref_7(c,c), 0); } +typedef Matrix RowMatrixXd; +int test_ref_overload_fun1(Ref ) { return 1; } +int test_ref_overload_fun1(Ref ) { return 2; } +int test_ref_overload_fun1(Ref ) { return 3; } + +int test_ref_overload_fun2(Ref ) { return 4; } +int test_ref_overload_fun2(Ref ) { return 5; } + +// See also bug 969 +void test_ref_overloads() +{ + MatrixXd Ad, Bd; + RowMatrixXd rAd, rBd; + VERIFY( test_ref_overload_fun1(Ad)==1 ); + VERIFY( test_ref_overload_fun1(rAd)==2 ); + + MatrixXf Af, Bf; + VERIFY( test_ref_overload_fun2(Ad)==4 ); + VERIFY( test_ref_overload_fun2(Ad+Bd)==4 ); + VERIFY( test_ref_overload_fun2(Af+Bf)==5 ); +} + void test_ref() { for(int i = 0; i < g_repeat; i++) { @@ -249,4 +271,6 @@ void test_ref() CALL_SUBTEST_5( ref_matrix(MatrixXi(internal::random(1,10),internal::random(1,10))) ); CALL_SUBTEST_6( call_ref() ); } + + CALL_SUBTEST_7( test_ref_overloads() ); } diff --git a/gtsam/3rdparty/Eigen/test/sparse_basic.cpp b/gtsam/3rdparty/Eigen/test/sparse_basic.cpp index 498ecfe29..abe6a9d14 100644 --- a/gtsam/3rdparty/Eigen/test/sparse_basic.cpp +++ b/gtsam/3rdparty/Eigen/test/sparse_basic.cpp @@ -24,6 +24,7 @@ template void sparse_basic(const SparseMatrixType& re double density = (std::max)(8./(rows*cols), 0.01); typedef Matrix DenseMatrix; typedef Matrix DenseVector; + typedef Matrix RowDenseVector; Scalar eps = 1e-6; Scalar s1 = internal::random(); @@ -52,7 +53,7 @@ template void sparse_basic(const SparseMatrixType& re refMat.coeffRef(nonzeroCoords[0].x(), nonzeroCoords[0].y()) = Scalar(5); VERIFY_IS_APPROX(m, refMat); - /* + // test InnerIterators and Block expressions for (int t=0; t<10; ++t) { @@ -61,23 +62,54 @@ template void sparse_basic(const SparseMatrixType& re int w = internal::random(1,cols-j-1); int h = internal::random(1,rows-i-1); - // VERIFY_IS_APPROX(m.block(i,j,h,w), refMat.block(i,j,h,w)); + VERIFY_IS_APPROX(m.block(i,j,h,w), refMat.block(i,j,h,w)); for(int c=0; c void sparse_basic(const SparseMatrixType& re VERIFY_IS_APPROX(m.row(r) + m.row(r), (m + m).row(r)); VERIFY_IS_APPROX(m.row(r) + m.row(r), refMat.row(r) + refMat.row(r)); } - */ + // test assertion VERIFY_RAISES_ASSERT( m.coeffRef(-1,1) = 0 ); @@ -274,6 +306,8 @@ template void sparse_basic(const SparseMatrixType& re refM4.setRandom(); // sparse cwise* dense VERIFY_IS_APPROX(m3.cwiseProduct(refM4), refM3.cwiseProduct(refM4)); + // dense cwise* sparse + VERIFY_IS_APPROX(refM4.cwiseProduct(m3), refM4.cwiseProduct(refM3)); // VERIFY_IS_APPROX(m3.cwise()/refM4, refM3.cwise()/refM4); // test aliasing @@ -326,6 +360,15 @@ template void sparse_basic(const SparseMatrixType& re refMat2.col(i) = refMat2.col(i) * s1; VERIFY_IS_APPROX(m2,refMat2); } + + VERIFY_IS_APPROX(DenseVector(m2.col(j0)), refMat2.col(j0)); + VERIFY_IS_APPROX(m2.col(j0), refMat2.col(j0)); + + VERIFY_IS_APPROX(RowDenseVector(m2.row(j0)), refMat2.row(j0)); + VERIFY_IS_APPROX(m2.row(j0), refMat2.row(j0)); + + VERIFY_IS_APPROX(m2.block(j0,j1,n0,n0), refMat2.block(j0,j1,n0,n0)); + VERIFY_IS_APPROX((2*m2).block(j0,j1,n0,n0), (2*refMat2).block(j0,j1,n0,n0)); } // test prune @@ -488,6 +531,20 @@ template void sparse_basic(const SparseMatrixType& re SparseMatrixType m1(rows, rows); m1.setIdentity(); VERIFY_IS_APPROX(m1, refMat1); + for(int k=0; k(0,rows-1); + Index j = internal::random(0,rows-1); + Scalar v = internal::random(); + m1.coeffRef(i,j) = v; + refMat1.coeffRef(i,j) = v; + VERIFY_IS_APPROX(m1, refMat1); + if(internal::random(0,10)<2) + m1.makeCompressed(); + } + m1.setIdentity(); + refMat1.setIdentity(); + VERIFY_IS_APPROX(m1, refMat1); } } diff --git a/gtsam/3rdparty/Eigen/test/sparse_solver.h b/gtsam/3rdparty/Eigen/test/sparse_solver.h index 244e81c1b..e1619d62a 100644 --- a/gtsam/3rdparty/Eigen/test/sparse_solver.h +++ b/gtsam/3rdparty/Eigen/test/sparse_solver.h @@ -67,6 +67,22 @@ void check_sparse_solving(Solver& solver, const typename Solver::MatrixType& A, VERIFY(oldb.isApprox(db) && "sparse solver testing: the rhs should not be modified!"); VERIFY(x.isApprox(refX,test_precision())); } + + // if not too large, do some extra check: + if(A.rows()<2000) + { + + // test expression as input + { + solver.compute(0.5*(A+A)); + Rhs x = solver.solve(b); + VERIFY(x.isApprox(refX,test_precision())); + + Solver solver2(0.5*(A+A)); + Rhs x2 = solver2.solve(b); + VERIFY(x2.isApprox(refX,test_precision())); + } + } } template @@ -161,7 +177,10 @@ int generate_sparse_spd_problem(Solver& , typename Solver::MatrixType& A, typena dA = dM * dM.adjoint(); halfA.resize(size,size); - halfA.template selfadjointView().rankUpdate(M); + if(Solver::UpLo==(Lower|Upper)) + halfA = A; + else + halfA.template selfadjointView().rankUpdate(M); return size; } @@ -274,7 +293,17 @@ int generate_sparse_square_problem(Solver&, typename Solver::MatrixType& A, Dens return size; } -template void check_sparse_square_solving(Solver& solver) + +struct prune_column { + int m_col; + prune_column(int col) : m_col(col) {} + template + bool operator()(int, int col, const Scalar&) const { + return col != m_col; + } +}; + +template void check_sparse_square_solving(Solver& solver, bool checkDeficient = false) { typedef typename Solver::MatrixType Mat; typedef typename Mat::Scalar Scalar; @@ -306,6 +335,13 @@ template void check_sparse_square_solving(Solver& solver) b = DenseVector::Zero(size); check_sparse_solving(solver, A, b, dA, b); } + // regression test for Bug 792 (structurally rank deficient matrices): + if(checkDeficient && size>1) { + int col = internal::random(0,size-1); + A.prune(prune_column(col)); + solver.compute(A); + VERIFY_IS_EQUAL(solver.info(), NumericalIssue); + } } // First, get the folder diff --git a/gtsam/3rdparty/Eigen/test/sparselu.cpp b/gtsam/3rdparty/Eigen/test/sparselu.cpp index 52371cb12..b3d67aea8 100644 --- a/gtsam/3rdparty/Eigen/test/sparselu.cpp +++ b/gtsam/3rdparty/Eigen/test/sparselu.cpp @@ -41,12 +41,15 @@ template void test_sparselu_T() SparseLU, AMDOrdering > sparselu_amd; SparseLU, NaturalOrdering > sparselu_natural; - check_sparse_square_solving(sparselu_colamd); - check_sparse_square_solving(sparselu_amd); - check_sparse_square_solving(sparselu_natural); + check_sparse_square_solving(sparselu_colamd, true); + check_sparse_square_solving(sparselu_amd, true); + check_sparse_square_solving(sparselu_natural,true); check_sparse_square_abs_determinant(sparselu_colamd); check_sparse_square_abs_determinant(sparselu_amd); + + check_sparse_square_determinant(sparselu_colamd); + check_sparse_square_determinant(sparselu_amd); } void test_sparselu() diff --git a/gtsam/3rdparty/Eigen/test/vectorwiseop.cpp b/gtsam/3rdparty/Eigen/test/vectorwiseop.cpp index 6cd1acdda..d32fd10cc 100644 --- a/gtsam/3rdparty/Eigen/test/vectorwiseop.cpp +++ b/gtsam/3rdparty/Eigen/test/vectorwiseop.cpp @@ -111,6 +111,18 @@ template void vectorwiseop_array(const ArrayType& m) m2.rowwise() /= m2.colwise().sum(); VERIFY_IS_APPROX(m2, m1.rowwise() / m1.colwise().sum()); } + + // all/any + Array mb(rows,cols); + mb = (m1.real()<=0.7).colwise().all(); + VERIFY( (mb.col(c) == (m1.real().col(c)<=0.7).all()).all() ); + mb = (m1.real()<=0.7).rowwise().all(); + VERIFY( (mb.row(r) == (m1.real().row(r)<=0.7).all()).all() ); + + mb = (m1.real()>=0.7).colwise().any(); + VERIFY( (mb.col(c) == (m1.real().col(c)>=0.7).any()).all() ); + mb = (m1.real()>=0.7).rowwise().any(); + VERIFY( (mb.row(r) == (m1.real().row(r)>=0.7).any()).all() ); } template void vectorwiseop_matrix(const MatrixType& m) diff --git a/gtsam/3rdparty/Eigen/unsupported/Eigen/CMakeLists.txt b/gtsam/3rdparty/Eigen/unsupported/Eigen/CMakeLists.txt index e06f1238b..e1fbf97e2 100644 --- a/gtsam/3rdparty/Eigen/unsupported/Eigen/CMakeLists.txt +++ b/gtsam/3rdparty/Eigen/unsupported/Eigen/CMakeLists.txt @@ -1,6 +1,6 @@ -set(Eigen_HEADERS AdolcForward BVH IterativeSolvers MatrixFunctions MoreVectorization AutoDiff AlignedVector3 Polynomials - FFT NonLinearOptimization SparseExtra IterativeSolvers - NumericalDiff Skyline MPRealSupport OpenGLSupport KroneckerProduct Splines LevenbergMarquardt +set(Eigen_HEADERS AdolcForward AlignedVector3 ArpackSupport AutoDiff BVH FFT IterativeSolvers KroneckerProduct LevenbergMarquardt + MatrixFunctions MoreVectorization MPRealSupport NonLinearOptimization NumericalDiff OpenGLSupport Polynomials + Skyline SparseExtra Splines ) install(FILES diff --git a/gtsam/3rdparty/Eigen/unsupported/Eigen/src/AutoDiff/AutoDiffScalar.h b/gtsam/3rdparty/Eigen/unsupported/Eigen/src/AutoDiff/AutoDiffScalar.h index 8d42e69b9..fde3ff61a 100644 --- a/gtsam/3rdparty/Eigen/unsupported/Eigen/src/AutoDiff/AutoDiffScalar.h +++ b/gtsam/3rdparty/Eigen/unsupported/Eigen/src/AutoDiff/AutoDiffScalar.h @@ -631,7 +631,7 @@ template struct NumTraits > { typedef AutoDiffScalar::Real,DerType::RowsAtCompileTime,DerType::ColsAtCompileTime> > Real; typedef AutoDiffScalar NonInteger; - typedef AutoDiffScalar& Nested; + typedef AutoDiffScalar Nested; enum{ RequireInitialization = 1 }; diff --git a/gtsam/3rdparty/Eigen/unsupported/Eigen/src/CMakeLists.txt b/gtsam/3rdparty/Eigen/unsupported/Eigen/src/CMakeLists.txt index f3180b52b..d8b9f4068 100644 --- a/gtsam/3rdparty/Eigen/unsupported/Eigen/src/CMakeLists.txt +++ b/gtsam/3rdparty/Eigen/unsupported/Eigen/src/CMakeLists.txt @@ -1,7 +1,10 @@ ADD_SUBDIRECTORY(AutoDiff) ADD_SUBDIRECTORY(BVH) +ADD_SUBDIRECTORY(Eigenvalues) ADD_SUBDIRECTORY(FFT) ADD_SUBDIRECTORY(IterativeSolvers) +ADD_SUBDIRECTORY(KroneckerProduct) +ADD_SUBDIRECTORY(LevenbergMarquardt) ADD_SUBDIRECTORY(MatrixFunctions) ADD_SUBDIRECTORY(MoreVectorization) ADD_SUBDIRECTORY(NonLinearOptimization) @@ -9,5 +12,4 @@ ADD_SUBDIRECTORY(NumericalDiff) ADD_SUBDIRECTORY(Polynomials) ADD_SUBDIRECTORY(Skyline) ADD_SUBDIRECTORY(SparseExtra) -ADD_SUBDIRECTORY(KroneckerProduct) ADD_SUBDIRECTORY(Splines) diff --git a/gtsam/3rdparty/Eigen/unsupported/Eigen/src/IterativeSolvers/DGMRES.h b/gtsam/3rdparty/Eigen/unsupported/Eigen/src/IterativeSolvers/DGMRES.h index 9fcc8a8d9..68fc997f7 100644 --- a/gtsam/3rdparty/Eigen/unsupported/Eigen/src/IterativeSolvers/DGMRES.h +++ b/gtsam/3rdparty/Eigen/unsupported/Eigen/src/IterativeSolvers/DGMRES.h @@ -133,8 +133,8 @@ class DGMRES : public IterativeSolverBase > * this class becomes invalid. Call compute() to update it with the new * matrix A, or modify a copy of A. */ - DGMRES(const MatrixType& A) : Base(A),m_restart(30),m_neig(0),m_r(0),m_maxNeig(5),m_isDeflAllocated(false),m_isDeflInitialized(false) - {} + template + explicit DGMRES(const EigenBase& A) : Base(A.derived()), m_restart(30),m_neig(0),m_r(0),m_maxNeig(5),m_isDeflAllocated(false),m_isDeflInitialized(false) {} ~DGMRES() {} diff --git a/gtsam/3rdparty/Eigen/unsupported/Eigen/src/IterativeSolvers/GMRES.h b/gtsam/3rdparty/Eigen/unsupported/Eigen/src/IterativeSolvers/GMRES.h index c8c84069e..ea5deb26d 100644 --- a/gtsam/3rdparty/Eigen/unsupported/Eigen/src/IterativeSolvers/GMRES.h +++ b/gtsam/3rdparty/Eigen/unsupported/Eigen/src/IterativeSolvers/GMRES.h @@ -246,20 +246,7 @@ struct traits > * \endcode * * By default the iterations start with x=0 as an initial guess of the solution. - * One can control the start using the solveWithGuess() method. Here is a step by - * step execution example starting with a random guess and printing the evolution - * of the estimated error: - * * \code - * x = VectorXd::Random(n); - * solver.setMaxIterations(1); - * int i = 0; - * do { - * x = solver.solveWithGuess(b,x); - * std::cout << i << " : " << solver.error() << std::endl; - * ++i; - * } while (solver.info()!=Success && i<100); - * \endcode - * Note that such a step by step excution is slightly slower. + * One can control the start using the solveWithGuess() method. * * \sa class SimplicialCholesky, DiagonalPreconditioner, IdentityPreconditioner */ @@ -298,7 +285,8 @@ public: * this class becomes invalid. Call compute() to update it with the new * matrix A, or modify a copy of A. */ - GMRES(const MatrixType& A) : Base(A), m_restart(30) {} + template + explicit GMRES(const EigenBase& A) : Base(A.derived()), m_restart(30) {} ~GMRES() {} diff --git a/gtsam/3rdparty/Eigen/unsupported/Eigen/src/IterativeSolvers/MINRES.h b/gtsam/3rdparty/Eigen/unsupported/Eigen/src/IterativeSolvers/MINRES.h index 0e56342a8..670f274bb 100644 --- a/gtsam/3rdparty/Eigen/unsupported/Eigen/src/IterativeSolvers/MINRES.h +++ b/gtsam/3rdparty/Eigen/unsupported/Eigen/src/IterativeSolvers/MINRES.h @@ -37,22 +37,31 @@ namespace Eigen { typedef typename Dest::Scalar Scalar; typedef Matrix VectorType; + // Check for zero rhs + const RealScalar rhsNorm2(rhs.squaredNorm()); + if(rhsNorm2 == 0) + { + x.setZero(); + iters = 0; + tol_error = 0; + return; + } + // initialize const int maxIters(iters); // initialize maxIters to iters const int N(mat.cols()); // the size of the matrix - const RealScalar rhsNorm2(rhs.squaredNorm()); const RealScalar threshold2(tol_error*tol_error*rhsNorm2); // convergence threshold (compared to residualNorm2) // Initialize preconditioned Lanczos -// VectorType v_old(N); // will be initialized inside loop + VectorType v_old(N); // will be initialized inside loop VectorType v( VectorType::Zero(N) ); //initialize v VectorType v_new(rhs-mat*x); //initialize v_new RealScalar residualNorm2(v_new.squaredNorm()); -// VectorType w(N); // will be initialized inside loop + VectorType w(N); // will be initialized inside loop VectorType w_new(precond.solve(v_new)); // initialize w_new // RealScalar beta; // will be initialized inside loop RealScalar beta_new2(v_new.dot(w_new)); - eigen_assert(beta_new2 >= 0 && "PRECONDITIONER IS NOT POSITIVE DEFINITE"); + eigen_assert(beta_new2 >= 0.0 && "PRECONDITIONER IS NOT POSITIVE DEFINITE"); RealScalar beta_new(sqrt(beta_new2)); const RealScalar beta_one(beta_new); v_new /= beta_new; @@ -62,14 +71,14 @@ namespace Eigen { RealScalar c_old(1.0); RealScalar s(0.0); // the sine of the Givens rotation RealScalar s_old(0.0); // the sine of the Givens rotation -// VectorType p_oold(N); // will be initialized in loop + VectorType p_oold(N); // will be initialized in loop VectorType p_old(VectorType::Zero(N)); // initialize p_old=0 VectorType p(p_old); // initialize p=0 RealScalar eta(1.0); iters = 0; // reset iters - while ( iters < maxIters ){ - + while ( iters < maxIters ) + { // Preconditioned Lanczos /* Note that there are 4 variants on the Lanczos algorithm. These are * described in Paige, C. C. (1972). Computational variants of @@ -81,17 +90,17 @@ namespace Eigen { * A. Greenbaum, Iterative Methods for Solving Linear Systems, SIAM (1987). */ const RealScalar beta(beta_new); -// v_old = v; // update: at first time step, this makes v_old = 0 so value of beta doesn't matter - const VectorType v_old(v); // NOT SURE IF CREATING v_old EVERY ITERATION IS EFFICIENT + v_old = v; // update: at first time step, this makes v_old = 0 so value of beta doesn't matter +// const VectorType v_old(v); // NOT SURE IF CREATING v_old EVERY ITERATION IS EFFICIENT v = v_new; // update -// w = w_new; // update - const VectorType w(w_new); // NOT SURE IF CREATING w EVERY ITERATION IS EFFICIENT + w = w_new; // update +// const VectorType w(w_new); // NOT SURE IF CREATING w EVERY ITERATION IS EFFICIENT v_new.noalias() = mat*w - beta*v_old; // compute v_new const RealScalar alpha = v_new.dot(w); v_new -= alpha*v; // overwrite v_new w_new = precond.solve(v_new); // overwrite w_new beta_new2 = v_new.dot(w_new); // compute beta_new - eigen_assert(beta_new2 >= 0 && "PRECONDITIONER IS NOT POSITIVE DEFINITE"); + eigen_assert(beta_new2 >= 0.0 && "PRECONDITIONER IS NOT POSITIVE DEFINITE"); beta_new = sqrt(beta_new2); // compute beta_new v_new /= beta_new; // overwrite v_new for next iteration w_new /= beta_new; // overwrite w_new for next iteration @@ -107,21 +116,28 @@ namespace Eigen { s=beta_new/r1; // new sine // Update solution -// p_oold = p_old; - const VectorType p_oold(p_old); // NOT SURE IF CREATING p_oold EVERY ITERATION IS EFFICIENT + p_oold = p_old; +// const VectorType p_oold(p_old); // NOT SURE IF CREATING p_oold EVERY ITERATION IS EFFICIENT p_old = p; p.noalias()=(w-r2*p_old-r3*p_oold) /r1; // IS NOALIAS REQUIRED? x += beta_one*c*eta*p; + + /* Update the squared residual. Note that this is the estimated residual. + The real residual |Ax-b|^2 may be slightly larger */ residualNorm2 *= s*s; - if ( residualNorm2 < threshold2){ + if ( residualNorm2 < threshold2) + { break; } eta=-s*eta; // update eta iters++; // increment iteration number (for output purposes) } - tol_error = std::sqrt(residualNorm2 / rhsNorm2); // return error. Note that this is the estimated error. The real error |Ax-b|/|b| may be slightly larger + + /* Compute error. Note that this is the estimated error. The real + error |Ax-b|/|b| may be slightly larger */ + tol_error = std::sqrt(residualNorm2 / rhsNorm2); } } @@ -174,20 +190,7 @@ namespace Eigen { * \endcode * * By default the iterations start with x=0 as an initial guess of the solution. - * One can control the start using the solveWithGuess() method. Here is a step by - * step execution example starting with a random guess and printing the evolution - * of the estimated error: - * * \code - * x = VectorXd::Random(n); - * mr.setMaxIterations(1); - * int i = 0; - * do { - * x = mr.solveWithGuess(b,x); - * std::cout << i << " : " << mr.error() << std::endl; - * ++i; - * } while (mr.info()!=Success && i<100); - * \endcode - * Note that such a step by step excution is slightly slower. + * One can control the start using the solveWithGuess() method. * * \sa class ConjugateGradient, BiCGSTAB, SimplicialCholesky, DiagonalPreconditioner, IdentityPreconditioner */ @@ -225,7 +228,8 @@ namespace Eigen { * this class becomes invalid. Call compute() to update it with the new * matrix A, or modify a copy of A. */ - MINRES(const MatrixType& A) : Base(A) {} + template + explicit MINRES(const EigenBase& A) : Base(A.derived()) {} /** Destructor. */ ~MINRES(){} @@ -250,6 +254,11 @@ namespace Eigen { template void _solveWithGuess(const Rhs& b, Dest& x) const { + typedef typename internal::conditional + >::type MatrixWrapperType; + m_iterations = Base::maxIterations(); m_error = Base::m_tolerance; @@ -259,7 +268,7 @@ namespace Eigen { m_error = Base::m_tolerance; typename Dest::ColXpr xj(x,j); - internal::minres(mp_matrix->template selfadjointView(), b.col(j), xj, + internal::minres(MatrixWrapperType(*mp_matrix), b.col(j), xj, Base::m_preconditioner, m_iterations, m_error); } diff --git a/gtsam/3rdparty/Eigen/unsupported/Eigen/src/LevenbergMarquardt/CMakeLists.txt b/gtsam/3rdparty/Eigen/unsupported/Eigen/src/LevenbergMarquardt/CMakeLists.txt index 8513803ce..d9690854d 100644 --- a/gtsam/3rdparty/Eigen/unsupported/Eigen/src/LevenbergMarquardt/CMakeLists.txt +++ b/gtsam/3rdparty/Eigen/unsupported/Eigen/src/LevenbergMarquardt/CMakeLists.txt @@ -2,5 +2,5 @@ FILE(GLOB Eigen_LevenbergMarquardt_SRCS "*.h") INSTALL(FILES ${Eigen_LevenbergMarquardt_SRCS} - DESTINATION ${INCLUDE_INSTALL_DIR}/Eigen/src/LevenbergMarquardt COMPONENT Devel + DESTINATION ${INCLUDE_INSTALL_DIR}/unsupported/Eigen/src/LevenbergMarquardt COMPONENT Devel ) diff --git a/gtsam/3rdparty/Eigen/unsupported/test/minres.cpp b/gtsam/3rdparty/Eigen/unsupported/test/minres.cpp index fd12da548..509ebe09a 100644 --- a/gtsam/3rdparty/Eigen/unsupported/test/minres.cpp +++ b/gtsam/3rdparty/Eigen/unsupported/test/minres.cpp @@ -14,15 +14,32 @@ template void test_minres_T() { - MINRES, Lower, DiagonalPreconditioner > minres_colmajor_diag; - MINRES, Lower, IdentityPreconditioner > minres_colmajor_I; + MINRES, Lower|Upper, DiagonalPreconditioner > minres_colmajor_diag; + MINRES, Lower, IdentityPreconditioner > minres_colmajor_lower_I; + MINRES, Upper, IdentityPreconditioner > minres_colmajor_upper_I; // MINRES, Lower, IncompleteLUT > minres_colmajor_ilut; //minres, SSORPreconditioner > minres_colmajor_ssor; - CALL_SUBTEST( check_sparse_square_solving(minres_colmajor_diag) ); - CALL_SUBTEST( check_sparse_spd_solving(minres_colmajor_I) ); + +// CALL_SUBTEST( check_sparse_square_solving(minres_colmajor_diag) ); // CALL_SUBTEST( check_sparse_square_solving(minres_colmajor_ilut) ); //CALL_SUBTEST( check_sparse_square_solving(minres_colmajor_ssor) ); + + // Diagonal preconditioner + MINRES, Lower, DiagonalPreconditioner > minres_colmajor_lower_diag; + MINRES, Upper, DiagonalPreconditioner > minres_colmajor_upper_diag; + MINRES, Upper|Lower, DiagonalPreconditioner > minres_colmajor_uplo_diag; + + // call tests for SPD matrix + CALL_SUBTEST( check_sparse_spd_solving(minres_colmajor_lower_I) ); + CALL_SUBTEST( check_sparse_spd_solving(minres_colmajor_upper_I) ); + + CALL_SUBTEST( check_sparse_spd_solving(minres_colmajor_lower_diag) ); + CALL_SUBTEST( check_sparse_spd_solving(minres_colmajor_upper_diag) ); +// CALL_SUBTEST( check_sparse_spd_solving(minres_colmajor_uplo_diag) ); + + // TO DO: symmetric semi-definite matrix + // TO DO: symmetric indefinite matrix } void test_minres() diff --git a/gtsam/3rdparty/Eigen/unsupported/test/mpreal/mpreal.h b/gtsam/3rdparty/Eigen/unsupported/test/mpreal/mpreal.h index dddda7dd9..7d6f4e79f 100644 --- a/gtsam/3rdparty/Eigen/unsupported/test/mpreal/mpreal.h +++ b/gtsam/3rdparty/Eigen/unsupported/test/mpreal/mpreal.h @@ -57,7 +57,8 @@ #include // Options -#define MPREAL_HAVE_INT64_SUPPORT // Enable int64_t support if possible. Available only for MSVC 2010 & GCC. +// FIXME HAVE_INT64_SUPPORT leads to clashes with long int and int64_t on some systems. +//#define MPREAL_HAVE_INT64_SUPPORT // Enable int64_t support if possible. Available only for MSVC 2010 & GCC. #define MPREAL_HAVE_MSVC_DEBUGVIEW // Enable Debugger Visualizer for "Debug" builds in MSVC. #define MPREAL_HAVE_DYNAMIC_STD_NUMERIC_LIMITS // Enable extended std::numeric_limits specialization. // Meaning that "digits", "round_style" and similar members are defined as functions, not constants. diff --git a/gtsam/CMakeLists.txt b/gtsam/CMakeLists.txt index e26d85ff8..cab5e8639 100644 --- a/gtsam/CMakeLists.txt +++ b/gtsam/CMakeLists.txt @@ -9,7 +9,10 @@ set (gtsam_subdirs discrete linear nonlinear + sam + sfm slam + smart navigation ) diff --git a/gtsam/base/CMakeLists.txt b/gtsam/base/CMakeLists.txt index 66d3ec721..99984e7b3 100644 --- a/gtsam/base/CMakeLists.txt +++ b/gtsam/base/CMakeLists.txt @@ -5,5 +5,8 @@ install(FILES ${base_headers} DESTINATION include/gtsam/base) file(GLOB base_headers_tree "treeTraversal/*.h") install(FILES ${base_headers_tree} DESTINATION include/gtsam/base/treeTraversal) +file(GLOB deprecated_headers "deprecated/*.h") +install(FILES ${deprecated_headers} DESTINATION include/gtsam/base/deprecated) + # Build tests add_subdirectory(tests) diff --git a/gtsam/base/FastDefaultAllocator.h b/gtsam/base/FastDefaultAllocator.h index 156a87f55..bf5cfc498 100644 --- a/gtsam/base/FastDefaultAllocator.h +++ b/gtsam/base/FastDefaultAllocator.h @@ -17,8 +17,7 @@ */ #pragma once - -#include +#include // Configuration from CMake #if !defined GTSAM_ALLOCATOR_BOOSTPOOL && !defined GTSAM_ALLOCATOR_TBB && !defined GTSAM_ALLOCATOR_STL # ifdef GTSAM_USE_TBB @@ -85,4 +84,4 @@ namespace gtsam }; } -} \ No newline at end of file +} diff --git a/gtsam/base/FastMap.h b/gtsam/base/FastMap.h index 7cd6e28b8..65d532191 100644 --- a/gtsam/base/FastMap.h +++ b/gtsam/base/FastMap.h @@ -19,9 +19,9 @@ #pragma once #include -#include #include #include +#include namespace gtsam { diff --git a/gtsam/base/FastSet.h b/gtsam/base/FastSet.h index 73df17b0d..8c23ae9e5 100644 --- a/gtsam/base/FastSet.h +++ b/gtsam/base/FastSet.h @@ -18,26 +18,22 @@ #pragma once -#include -#include -#include -#include #include #include -#include -#include -#include -#include +#include +#include -BOOST_MPL_HAS_XXX_TRAIT_DEF(print) +#include +#include + +namespace boost { +namespace serialization { +class access; +} /* namespace serialization */ +} /* namespace boost */ namespace gtsam { -// This is used internally to allow this container to be Testable even when it -// contains non-testable elements. -template -struct FastSetTestableHelper; - /** * FastSet is a thin wrapper around std::set that uses the boost * fast_pool_allocator instead of the default STL allocator. This is just a @@ -45,12 +41,16 @@ struct FastSetTestableHelper; * we've seen that the fast_pool_allocator can lead to speedups of several %. * @addtogroup base */ -template -class FastSet: public std::set, typename internal::FastDefaultAllocator::type> { +template +class FastSet: public std::set, + typename internal::FastDefaultAllocator::type> { + + BOOST_CONCEPT_ASSERT ((IsTestable )); public: - typedef std::set, typename internal::FastDefaultAllocator::type> Base; + typedef std::set, + typename internal::FastDefaultAllocator::type> Base; /** Default constructor */ FastSet() { @@ -59,23 +59,23 @@ public: /** Constructor from a range, passes through to base class */ template explicit FastSet(INPUTITERATOR first, INPUTITERATOR last) : - Base(first, last) { + Base(first, last) { } /** Constructor from a iterable container, passes through to base class */ template explicit FastSet(const INPUTCONTAINER& container) : - Base(container.begin(), container.end()) { + Base(container.begin(), container.end()) { } /** Copy constructor from another FastSet */ FastSet(const FastSet& x) : - Base(x) { + Base(x) { } /** Copy constructor from the base set class */ FastSet(const Base& x) : - Base(x) { + Base(x) { } #ifdef GTSAM_ALLOCATOR_BOOSTPOOL @@ -85,7 +85,7 @@ public: // STL vector where if the size is zero, the pool allocator will allocate // huge amounts of memory. if(x.size() > 0) - Base::insert(x.begin(), x.end()); + Base::insert(x.begin(), x.end()); } #endif @@ -95,17 +95,31 @@ public: } /** Handy 'exists' function */ - bool exists(const VALUE& e) const { return this->find(e) != this->end(); } + bool exists(const VALUE& e) const { + return this->find(e) != this->end(); + } - /** Print to implement Testable */ - void print(const std::string& str = "") const { FastSetTestableHelper::print(*this, str); } + /** Print to implement Testable: pretty basic */ + void print(const std::string& str = "") const { + for (typename Base::const_iterator it = this->begin(); it != this->end(); ++it) + traits::Print(*it, str); + } /** Check for equality within tolerance to implement Testable */ - bool equals(const FastSet& other, double tol = 1e-9) const { return FastSetTestableHelper::equals(*this, other, tol); } + bool equals(const FastSet& other, double tol = 1e-9) const { + typename Base::const_iterator it1 = this->begin(), it2 = other.begin(); + while (it1 != this->end()) { + if (it2 == other.end() || !traits::Equals(*it2, *it2, tol)) + return false; + ++it1; + ++it2; + } + return true; + } /** insert another set: handy for MATLAB access */ void merge(const FastSet& other) { - Base::insert(other.begin(),other.end()); + Base::insert(other.begin(), other.end()); } private: @@ -117,59 +131,4 @@ private: } }; -// This is the default Testable interface for *non*Testable elements, which -// uses stream operators. -template -struct FastSetTestableHelper { - - typedef FastSet Set; - - static void print(const Set& set, const std::string& str) { - std::cout << str << "\n"; - for (typename Set::const_iterator it = set.begin(); it != set.end(); ++it) - std::cout << " " << *it << "\n"; - std::cout.flush(); - } - - static bool equals(const Set& set1, const Set& set2, double tol) { - typename Set::const_iterator it1 = set1.begin(); - typename Set::const_iterator it2 = set2.begin(); - while (it1 != set1.end()) { - if (it2 == set2.end() || - fabs((double)(*it1) - (double)(*it2)) > tol) - return false; - ++it1; - ++it2; - } - return true; - } -}; - -// This is the Testable interface for Testable elements -template -struct FastSetTestableHelper >::type> { - - typedef FastSet Set; - - static void print(const Set& set, const std::string& str) { - std::cout << str << "\n"; - for (typename Set::const_iterator it = set.begin(); it != set.end(); ++it) - it->print(" "); - std::cout.flush(); - } - - static bool equals(const Set& set1, const Set& set2, double tol) { - typename Set::const_iterator it1 = set1.begin(); - typename Set::const_iterator it2 = set2.begin(); - while (it1 != set1.end()) { - if (it2 == set2.end() || - !it1->equals(*it2, tol)) - return false; - ++it1; - ++it2; - } - return true; - } -}; - } diff --git a/gtsam/base/FastVector.h b/gtsam/base/FastVector.h index d154ea52a..7d1cb970c 100644 --- a/gtsam/base/FastVector.h +++ b/gtsam/base/FastVector.h @@ -18,12 +18,10 @@ #pragma once -#include +#include #include #include - -#include -#include +#include namespace gtsam { @@ -35,20 +33,27 @@ namespace gtsam { * @addtogroup base */ template -class FastVector: public std::vector::type> { +class FastVector: public std::vector::type> { public: - typedef std::vector::type> Base; + typedef std::vector::type> Base; /** Default constructor */ - FastVector() {} + FastVector() { + } /** Constructor from size */ - explicit FastVector(size_t size) : Base(size) {} + explicit FastVector(size_t size) : + Base(size) { + } /** Constructor from size and initial values */ - explicit FastVector(size_t size, const VALUE& initial) : Base(size, initial) {} + explicit FastVector(size_t size, const VALUE& initial) : + Base(size, initial) { + } /** Constructor from a range, passes through to base class */ template @@ -56,33 +61,22 @@ public: // This if statement works around a bug in boost pool allocator and/or // STL vector where if the size is zero, the pool allocator will allocate // huge amounts of memory. - if(first != last) + if (first != last) Base::assign(first, last); } - /** Copy constructor from a FastList */ - FastVector(const FastList& x) { - if(x.size() > 0) - Base::assign(x.begin(), x.end()); - } - - /** Copy constructor from a FastSet */ - FastVector(const FastSet& x) { - if(x.size() > 0) - Base::assign(x.begin(), x.end()); - } - /** Copy constructor from the base class */ - FastVector(const Base& x) : Base(x) {} + FastVector(const Base& x) : + Base(x) { + } /** Copy constructor from a standard STL container */ template - FastVector(const std::vector& x) - { + FastVector(const std::vector& x) { // This if statement works around a bug in boost pool allocator and/or // STL vector where if the size is zero, the pool allocator will allocate // huge amounts of memory. - if(x.size() > 0) + if (x.size() > 0) Base::assign(x.begin(), x.end()); } diff --git a/gtsam/base/GenericValue.h b/gtsam/base/GenericValue.h index e83a64ba9..17783c5b9 100644 --- a/gtsam/base/GenericValue.h +++ b/gtsam/base/GenericValue.h @@ -194,6 +194,11 @@ public: }; +// traits +template +struct traits > + : public Testable > {}; + // define Value::cast here since now GenericValue has been declared template const ValueType& Value::cast() const { diff --git a/gtsam/base/Lie.h b/gtsam/base/Lie.h index 05c7bc20f..1576aca1d 100644 --- a/gtsam/base/Lie.h +++ b/gtsam/base/Lie.h @@ -75,54 +75,89 @@ struct LieGroup { return derived().inverse(); } + /// expmap as required by manifold concept + /// Applies exponential map to v and composes with *this Class expmap(const TangentVector& v) const { return compose(Class::Expmap(v)); } + /// logmap as required by manifold concept + /// Applies logarithmic map to group element that takes *this to g TangentVector logmap(const Class& g) const { return Class::Logmap(between(g)); } + /// expmap with optional derivatives + Class expmap(const TangentVector& v, // + ChartJacobian H1, ChartJacobian H2 = boost::none) const { + Jacobian D_g_v; + Class g = Class::Expmap(v,H2 ? &D_g_v : 0); + Class h = compose(g); // derivatives inlined below + if (H1) *H1 = g.inverse().AdjointMap(); + if (H2) *H2 = D_g_v; + return h; + } + + /// logmap with optional derivatives + TangentVector logmap(const Class& g, // + ChartJacobian H1, ChartJacobian H2 = boost::none) const { + Class h = between(g); // derivatives inlined below + Jacobian D_v_h; + TangentVector v = Class::Logmap(h, (H1 || H2) ? &D_v_h : 0); + if (H1) *H1 = - D_v_h * h.inverse().AdjointMap(); + if (H2) *H2 = D_v_h; + return v; + } + + /// Retract at origin: possible in Lie group because it has an identity static Class Retract(const TangentVector& v) { return Class::ChartAtOrigin::Retract(v); } + /// LocalCoordinates at origin: possible in Lie group because it has an identity static TangentVector LocalCoordinates(const Class& g) { return Class::ChartAtOrigin::Local(g); } + /// Retract at origin with optional derivative static Class Retract(const TangentVector& v, ChartJacobian H) { return Class::ChartAtOrigin::Retract(v,H); } + /// LocalCoordinates at origin with optional derivative static TangentVector LocalCoordinates(const Class& g, ChartJacobian H) { return Class::ChartAtOrigin::Local(g,H); } + /// retract as required by manifold concept: applies v at *this Class retract(const TangentVector& v) const { return compose(Class::ChartAtOrigin::Retract(v)); } + /// localCoordinates as required by manifold concept: finds tangent vector between *this and g TangentVector localCoordinates(const Class& g) const { return Class::ChartAtOrigin::Local(between(g)); } + /// retract with optional derivatives Class retract(const TangentVector& v, // ChartJacobian H1, ChartJacobian H2 = boost::none) const { Jacobian D_g_v; - Class g = Class::ChartAtOrigin::Retract(v,H2 ? &D_g_v : 0); - Class h = compose(g,H1,H2); - if (H2) *H2 = (*H2) * D_g_v; + Class g = Class::ChartAtOrigin::Retract(v, H2 ? &D_g_v : 0); + Class h = compose(g); // derivatives inlined below + if (H1) *H1 = g.inverse().AdjointMap(); + if (H2) *H2 = D_g_v; return h; } + /// localCoordinates with optional derivatives TangentVector localCoordinates(const Class& g, // ChartJacobian H1, ChartJacobian H2 = boost::none) const { - Class h = between(g,H1,H2); + Class h = between(g); // derivatives inlined below Jacobian D_v_h; TangentVector v = Class::ChartAtOrigin::Local(h, (H1 || H2) ? &D_v_h : 0); - if (H1) *H1 = D_v_h * (*H1); - if (H2) *H2 = D_v_h * (*H2); + if (H1) *H1 = - D_v_h * h.inverse().AdjointMap(); + if (H2) *H2 = D_v_h; return v; } diff --git a/gtsam/base/LieMatrix.cpp b/gtsam/base/LieMatrix.cpp deleted file mode 100644 index cf5b57536..000000000 --- a/gtsam/base/LieMatrix.cpp +++ /dev/null @@ -1,27 +0,0 @@ -/* ---------------------------------------------------------------------------- - - * 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 LieMatrix.cpp - * @brief A wrapper around Matrix providing Lie compatibility - * @author Richard Roberts and Alex Cunningham - */ - -#include - -namespace gtsam { - -/* ************************************************************************* */ -void LieMatrix::print(const std::string& name) const { - gtsam::print(matrix(), name); -} - -} diff --git a/gtsam/base/LieMatrix.h b/gtsam/base/LieMatrix.h index e24f339e4..77edd5fd5 100644 --- a/gtsam/base/LieMatrix.h +++ b/gtsam/base/LieMatrix.h @@ -11,7 +11,7 @@ /** * @file LieMatrix.h - * @brief External deprecation warning, see LieMatrix_Deprecated.h for details + * @brief External deprecation warning, see deprecated/LieMatrix.h for details * @author Paul Drews */ @@ -23,4 +23,4 @@ #warning "LieMatrix.h is deprecated. Please use Eigen::Matrix instead." #endif -#include "gtsam/base/LieMatrix_Deprecated.h" +#include "gtsam/base/deprecated/LieMatrix.h" diff --git a/gtsam/base/LieScalar.cpp b/gtsam/base/LieScalar.cpp deleted file mode 100644 index 4c5a6a257..000000000 --- a/gtsam/base/LieScalar.cpp +++ /dev/null @@ -1,17 +0,0 @@ -/* - * LieScalar.cpp - * - * Created on: Apr 12, 2013 - * Author: thduynguyen - */ - - - - -#include - -namespace gtsam { - void LieScalar::print(const std::string& name) const { - std::cout << name << ": " << d_ << std::endl; - } -} diff --git a/gtsam/base/LieScalar.h b/gtsam/base/LieScalar.h index 650e2bb21..417570604 100644 --- a/gtsam/base/LieScalar.h +++ b/gtsam/base/LieScalar.h @@ -11,7 +11,7 @@ /** * @file LieScalar.h - * @brief External deprecation warning, see LieScalar_Deprecated.h for details + * @brief External deprecation warning, see deprecated/LieScalar.h for details * @author Kai Ni */ @@ -23,4 +23,4 @@ #warning "LieScalar.h is deprecated. Please use double/float instead." #endif -#include +#include diff --git a/gtsam/base/LieVector.cpp b/gtsam/base/LieVector.cpp deleted file mode 100644 index 3e4eeecf2..000000000 --- a/gtsam/base/LieVector.cpp +++ /dev/null @@ -1,40 +0,0 @@ -/* ---------------------------------------------------------------------------- - - * 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 LieVector.cpp - * @brief Implementations for LieVector functions - * @author Alex Cunningham - */ - -#include -#include - -using namespace std; - -namespace gtsam { - -/* ************************************************************************* */ -LieVector::LieVector(size_t m, const double* const data) -: Vector(m) -{ - for(size_t i = 0; i < m; i++) - (*this)(i) = data[i]; -} - -/* ************************************************************************* */ -void LieVector::print(const std::string& name) const { - gtsam::print(vector(), name); -} - -// Does not compile because LieVector is not fixed size. -// GTSAM_CONCEPT_LIE_INST(LieVector) -} // \namespace gtsam diff --git a/gtsam/base/LieVector.h b/gtsam/base/LieVector.h index 813431775..310abcf02 100644 --- a/gtsam/base/LieVector.h +++ b/gtsam/base/LieVector.h @@ -11,7 +11,7 @@ /** * @file LieVector.h - * @brief Deprecation warning for LieVector_Deprecated.h, see LieVector_Deprecated.h for details. + * @brief Deprecation warning for LieVector, see deprecated/LieVector.h for details. * @author Paul Drews */ @@ -23,4 +23,4 @@ #warning "LieVector.h is deprecated. Please use Eigen::Vector instead." #endif -#include +#include diff --git a/gtsam/base/Manifold.h b/gtsam/base/Manifold.h index d7ea9ea4c..b30edb3df 100644 --- a/gtsam/base/Manifold.h +++ b/gtsam/base/Manifold.h @@ -169,7 +169,8 @@ struct FixedDimension { }; /// Helper class to construct the product manifold of two other manifolds, M1 and M2 -/// Assumes nothing except manifold structure from M1 and M2 +/// Assumes nothing except manifold structure for M1 and M2, and the existence +/// of default constructor for those types template class ProductManifold: public std::pair { BOOST_CONCEPT_ASSERT((IsManifold)); @@ -187,8 +188,8 @@ public: typedef Eigen::Matrix TangentVector; typedef OptionalJacobian ChartJacobian; - /// Default constructor yields identity - ProductManifold():std::pair(traits::Identity(),traits::Identity()) {} + /// Default constructor needs default constructors to be defined + ProductManifold():std::pair(M1(),M2()) {} // Construct from two original manifold values ProductManifold(const M1& m1, const M2& m2):std::pair(m1,m2) {} diff --git a/gtsam/base/Matrix.cpp b/gtsam/base/Matrix.cpp index 9e56dfb6c..c6af89486 100644 --- a/gtsam/base/Matrix.cpp +++ b/gtsam/base/Matrix.cpp @@ -184,21 +184,17 @@ void transposeMultiplyAdd(double alpha, const Matrix& A, const Vector& e, SubVec /* ************************************************************************* */ //3 argument call void print(const Matrix& A, const string &s, ostream& stream) { - size_t m = A.rows(), n = A.cols(); - - // print out all elements - stream << s << "[\n"; - for( size_t i = 0 ; i < m ; i++) { - for( size_t j = 0 ; j < n ; j++) { - double aij = A(i,j); - if(aij != 0.0) - stream << setw(12) << setprecision(9) << aij << ",\t"; - else - stream << " 0.0,\t"; - } - stream << endl; - } - stream << "];" << endl; + static const Eigen::IOFormat matlab( + Eigen::StreamPrecision, // precision + 0, // flags + " ", // coeffSeparator + ";\n", // rowSeparator + " \t", // rowPrefix + "", // rowSuffix + "[\n", // matPrefix + "\n ]" // matSuffix + ); + cout << s << A.format(matlab) << endl; } /* ************************************************************************* */ @@ -584,15 +580,6 @@ Matrix vector_scale(const Matrix& A, const Vector& v, bool inf_mask) { return M; } -/* ************************************************************************* */ -Matrix3 skewSymmetric(double wx, double wy, double wz) -{ - return (Matrix3() << - 0.0, -wz, +wy, - +wz, 0.0, -wx, - -wy, +wx, 0.0).finished(); -} - /* ************************************************************************* */ Matrix LLt(const Matrix& A) { diff --git a/gtsam/base/Matrix.h b/gtsam/base/Matrix.h index caee2071c..37a0d28b8 100644 --- a/gtsam/base/Matrix.h +++ b/gtsam/base/Matrix.h @@ -21,13 +21,17 @@ // \callgraph #pragma once +#include #include -#include +#include // Configuration from CMake + #include #include #include #include +#include #include +#include /** @@ -475,9 +479,15 @@ GTSAM_EXPORT Matrix vector_scale(const Matrix& A, const Vector& v, bool inf_mask * @param wz * @return a 3*3 skew symmetric matrix */ -GTSAM_EXPORT Matrix3 skewSymmetric(double wx, double wy, double wz); -template -inline Matrix3 skewSymmetric(const Eigen::MatrixBase& w) { return skewSymmetric(w(0),w(1),w(2));} + +inline Matrix3 skewSymmetric(double wx, double wy, double wz) { + return (Matrix3() << 0.0, -wz, +wy, +wz, 0.0, -wx, -wy, +wx, 0.0).finished(); +} + +template +inline Matrix3 skewSymmetric(const Eigen::MatrixBase& w) { + return skewSymmetric(w(0), w(1), w(2)); +} /** Use Cholesky to calculate inverse square root of a matrix */ GTSAM_EXPORT Matrix inverse_square_root(const Matrix& A); @@ -524,6 +534,75 @@ GTSAM_EXPORT Matrix expm(const Matrix& A, size_t K=7); std::string formatMatrixIndented(const std::string& label, const Matrix& matrix, bool makeVectorHorizontal = false); +/** + * Functor that implements multiplication of a vector b with the inverse of a + * matrix A. The derivatives are inspired by Mike Giles' "An extended collection + * of matrix derivative results for forward and reverse mode algorithmic + * differentiation", at https://people.maths.ox.ac.uk/gilesm/files/NA-08-01.pdf + */ +template +struct MultiplyWithInverse { + typedef Eigen::Matrix VectorN; + typedef Eigen::Matrix MatrixN; + + /// A.inverse() * b, with optional derivatives + VectorN operator()(const MatrixN& A, const VectorN& b, + OptionalJacobian H1 = boost::none, + OptionalJacobian H2 = boost::none) const { + const MatrixN invA = A.inverse(); + const VectorN c = invA * b; + // The derivative in A is just -[c[0]*invA c[1]*invA ... c[N-1]*invA] + if (H1) + for (size_t j = 0; j < N; j++) + H1->template middleCols(N * j) = -c[j] * invA; + // The derivative in b is easy, as invA*b is just a linear map: + if (H2) *H2 = invA; + return c; + } +}; + +/** + * Functor that implements multiplication with the inverse of a matrix, itself + * the result of a function f. It turn out we only need the derivatives of the + * operator phi(a): b -> f(a) * b + */ +template +struct MultiplyWithInverseFunction { + enum { M = traits::dimension }; + typedef Eigen::Matrix VectorN; + typedef Eigen::Matrix MatrixN; + + // The function phi should calculate f(a)*b, with derivatives in a and b. + // Naturally, the derivative in b is f(a). + typedef boost::function, OptionalJacobian)> + Operator; + + /// Construct with function as explained above + MultiplyWithInverseFunction(const Operator& phi) : phi_(phi) {} + + /// f(a).inverse() * b, with optional derivatives + VectorN operator()(const T& a, const VectorN& b, + OptionalJacobian H1 = boost::none, + OptionalJacobian H2 = boost::none) const { + MatrixN A; + phi_(a, b, boost::none, A); // get A = f(a) by calling f once + const MatrixN invA = A.inverse(); + const VectorN c = invA * b; + + if (H1) { + Eigen::Matrix H; + phi_(a, c, H, boost::none); // get derivative H of forward mapping + *H1 = -invA* H; + } + if (H2) *H2 = invA; + return c; + } + + private: + const Operator phi_; +}; + } // namespace gtsam #include diff --git a/gtsam/base/OptionalJacobian.h b/gtsam/base/OptionalJacobian.h index 7055a287a..eb1c1bbcc 100644 --- a/gtsam/base/OptionalJacobian.h +++ b/gtsam/base/OptionalJacobian.h @@ -18,7 +18,7 @@ */ #pragma once - +#include // Configuration from CMake #include #ifndef OPTIONALJACOBIAN_NOBOOST @@ -40,7 +40,8 @@ class OptionalJacobian { public: - /// ::Jacobian size type + /// Jacobian size type + /// TODO(frank): how to enforce RowMajor? Or better, make it work with any storage order? typedef Eigen::Matrix Jacobian; private: @@ -53,6 +54,14 @@ private: new (&map_) Eigen::Map(data); } + // Private and very dangerous constructor straight from memory + OptionalJacobian(double* data) : map_(NULL) { + if (data) usurp(data); + } + + template + friend class OptionalJacobian; + public: /// Default constructor acts like boost::none @@ -98,6 +107,11 @@ public: #endif + /// Constructor that will usurp data of a block expression + /// TODO(frank): unfortunately using a Map makes usurping non-contiguous memory impossible + // template + // OptionalJacobian(Eigen::Block block) : map_(NULL) { ?? } + /// Return true is allocated, false if default constructor was used operator bool() const { return map_.data() != NULL; @@ -108,8 +122,36 @@ public: return map_; } - /// TODO: operator->() - Eigen::Map* operator->(){ return &map_; } + /// operator->() + Eigen::Map* operator->() { + return &map_; + } + + /// Access M*N sub-block if we are allocated, otherwise none + /// TODO(frank): this could work as is below if only constructor above worked + // template + // OptionalJacobian block(int startRow, int startCol) { + // if (*this) + // OptionalJacobian(map_.block(startRow, startCol)); + // else + // return OptionalJacobian(); + // } + + /// Access Rows*N sub-block if we are allocated, otherwise return an empty OptionalJacobian + /// The use case is functions with arguments that are dissected, e.g. Pose3 into Rot3, Point3 + /// TODO(frank): ideally, we'd like full block functionality, but see note above. + template + OptionalJacobian cols(int startCol) { + if (*this) + return OptionalJacobian(&map_(0,startCol)); + else + return OptionalJacobian(); + } + + /// Access M*Cols sub-block if we are allocated, otherwise return empty OptionalJacobian + /// The use case is functions that create their return value piecemeal by calling other functions + /// TODO(frank): Unfortunately we assume column-major storage order and hence this can't work + /// template OptionalJacobian rows(int startRow) { ?? } }; // The pure dynamic specialization of this is needed to support @@ -171,6 +213,16 @@ public: // forward declare template struct traits; +/** + * @brief: meta-function to generate Jacobian + * @param T return type + * @param A argument type + */ +template +struct MakeJacobian { + typedef Eigen::Matrix::dimension, traits::dimension> type; +}; + /** * @brief: meta-function to generate JacobianTA optional reference * Used mainly by Expressions diff --git a/gtsam/base/ProductLieGroup.h b/gtsam/base/ProductLieGroup.h index 90aeb54d1..463b5f5d9 100644 --- a/gtsam/base/ProductLieGroup.h +++ b/gtsam/base/ProductLieGroup.h @@ -55,7 +55,7 @@ public: traits::Compose(this->second,other.second)); } ProductLieGroup inverse() const { - return ProductLieGroup(this->first.inverse(), this->second.inverse()); + return ProductLieGroup(traits::Inverse(this->first), traits::Inverse(this->second)); } ProductLieGroup compose(const ProductLieGroup& g) const { return (*this) * g; @@ -74,17 +74,21 @@ public: typedef Eigen::Matrix TangentVector; typedef OptionalJacobian ChartJacobian; - static ProductLieGroup Retract(const TangentVector& v) { - return ProductLieGroup::ChartAtOrigin::Retract(v); + ProductLieGroup retract(const TangentVector& v, // + ChartJacobian H1 = boost::none, ChartJacobian H2 = boost::none) const { + if (H1||H2) throw std::runtime_error("ProductLieGroup::retract derivatives not implemented yet"); + G g = traits::Retract(this->first, v.template head()); + H h = traits::Retract(this->second, v.template tail()); + return ProductLieGroup(g,h); } - static TangentVector LocalCoordinates(const ProductLieGroup& g) { - return ProductLieGroup::ChartAtOrigin::Local(g); - } - ProductLieGroup retract(const TangentVector& v) const { - return compose(ProductLieGroup::ChartAtOrigin::Retract(v)); - } - TangentVector localCoordinates(const ProductLieGroup& g) const { - return ProductLieGroup::ChartAtOrigin::Local(between(g)); + TangentVector localCoordinates(const ProductLieGroup& g, // + ChartJacobian H1 = boost::none, ChartJacobian H2 = boost::none) const { + if (H1||H2) throw std::runtime_error("ProductLieGroup::localCoordinates derivatives not implemented yet"); + typename traits::TangentVector v1 = traits::Local(this->first, g.first); + typename traits::TangentVector v2 = traits::Local(this->second, g.second); + TangentVector v; + v << v1, v2; + return v; } /// @} @@ -147,51 +151,19 @@ public: v << v1, v2; return v; } - struct ChartAtOrigin { - static TangentVector Local(const ProductLieGroup& m, ChartJacobian Hm = boost::none) { - return Logmap(m, Hm); - } - static ProductLieGroup Retract(const TangentVector& v, ChartJacobian Hv = boost::none) { - return Expmap(v, Hv); - } - }; ProductLieGroup expmap(const TangentVector& v) const { return compose(ProductLieGroup::Expmap(v)); } TangentVector logmap(const ProductLieGroup& g) const { return ProductLieGroup::Logmap(between(g)); } - static ProductLieGroup Retract(const TangentVector& v, ChartJacobian H1) { - return ProductLieGroup::ChartAtOrigin::Retract(v,H1); - } - static TangentVector LocalCoordinates(const ProductLieGroup& g, ChartJacobian H1) { - return ProductLieGroup::ChartAtOrigin::Local(g,H1); - } - ProductLieGroup retract(const TangentVector& v, // - ChartJacobian H1, ChartJacobian H2 = boost::none) const { - Jacobian D_g_v; - ProductLieGroup g = ProductLieGroup::ChartAtOrigin::Retract(v,H2 ? &D_g_v : 0); - ProductLieGroup h = compose(g,H1,H2); - if (H2) *H2 = (*H2) * D_g_v; - return h; - } - TangentVector localCoordinates(const ProductLieGroup& g, // - ChartJacobian H1, ChartJacobian H2 = boost::none) const { - ProductLieGroup h = between(g,H1,H2); - Jacobian D_v_h; - TangentVector v = ProductLieGroup::ChartAtOrigin::Local(h, (H1 || H2) ? &D_v_h : 0); - if (H1) *H1 = D_v_h * (*H1); - if (H2) *H2 = D_v_h * (*H2); - return v; - } /// @} }; // Define any direct product group to be a model of the multiplicative Group concept template -struct traits > : internal::LieGroupTraits< - ProductLieGroup > { -}; +struct traits > : internal::LieGroupTraits > {}; + } // namespace gtsam diff --git a/gtsam/base/SymmetricBlockMatrix.cpp b/gtsam/base/SymmetricBlockMatrix.cpp index 546b6a7f1..7cca63092 100644 --- a/gtsam/base/SymmetricBlockMatrix.cpp +++ b/gtsam/base/SymmetricBlockMatrix.cpp @@ -20,6 +20,7 @@ #include #include #include +#include namespace gtsam { @@ -61,13 +62,13 @@ VerticalBlockMatrix SymmetricBlockMatrix::choleskyPartial( // Split conditional - // Create one big conditionals with many frontal variables. - gttic(Construct_conditional); - const size_t varDim = offset(nFrontals); - VerticalBlockMatrix Ab = VerticalBlockMatrix::LikeActiveViewOf(*this, varDim); - Ab.full() = matrix_.topRows(varDim); - Ab.full().triangularView().setZero(); - gttoc(Construct_conditional); + // Create one big conditionals with many frontal variables. + gttic(Construct_conditional); + const size_t varDim = offset(nFrontals); + VerticalBlockMatrix Ab = VerticalBlockMatrix::LikeActiveViewOf(*this, varDim); + Ab.full() = matrix_.topRows(varDim); + Ab.full().triangularView().setZero(); + gttoc(Construct_conditional); gttic(Remaining_factor); // Take lower-right block of Ab_ to get the remaining factor diff --git a/gtsam/base/SymmetricBlockMatrix.h b/gtsam/base/SymmetricBlockMatrix.h index 41584c7f9..1f81ca1f9 100644 --- a/gtsam/base/SymmetricBlockMatrix.h +++ b/gtsam/base/SymmetricBlockMatrix.h @@ -17,9 +17,21 @@ */ #pragma once -#include #include +#include #include +#include +#include +#include +#include +#include +#include + +namespace boost { +namespace serialization { +class access; +} /* namespace serialization */ +} /* namespace boost */ namespace gtsam { @@ -247,13 +259,8 @@ namespace gtsam { } }; - /* ************************************************************************* */ - class CholeskyFailed : public gtsam::ThreadsafeException - { - public: - CholeskyFailed() throw() {} - virtual ~CholeskyFailed() throw() {} - }; + /// Foward declare exception class + class CholeskyFailed; } diff --git a/gtsam/base/Testable.h b/gtsam/base/Testable.h index 4790530ab..92ccb9156 100644 --- a/gtsam/base/Testable.h +++ b/gtsam/base/Testable.h @@ -123,8 +123,8 @@ namespace gtsam { double tol_; equals_star(double tol = 1e-9) : tol_(tol) {} bool operator()(const boost::shared_ptr& expected, const boost::shared_ptr& actual) { - if (!actual || !expected) return false; - return (traits::Equals(*actual,*expected, tol_)); + if (!actual || !expected) return true; + return actual && expected && traits::Equals(*actual,*expected, tol_); } }; diff --git a/gtsam/base/TestableAssertions.h b/gtsam/base/TestableAssertions.h index 04d3fc676..f976be0e7 100644 --- a/gtsam/base/TestableAssertions.h +++ b/gtsam/base/TestableAssertions.h @@ -17,13 +17,14 @@ #pragma once -#include -#include -#include +#include +#include + #include #include -#include -#include +#include +#include +#include namespace gtsam { diff --git a/gtsam/base/ThreadsafeException.h b/gtsam/base/ThreadsafeException.h new file mode 100644 index 000000000..ca13047a8 --- /dev/null +++ b/gtsam/base/ThreadsafeException.h @@ -0,0 +1,155 @@ +/* ---------------------------------------------------------------------------- + + * 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 ThreadSafeException.h + * @brief Base exception type that uses tbb_exception if GTSAM is compiled with TBB + * @author Richard Roberts + * @date Aug 21, 2010 + * @addtogroup base + */ + +#pragma once + +#include // for GTSAM_USE_TBB + +#include +#include +#include + +#ifdef GTSAM_USE_TBB +#include +#include +#include +#include +#endif + +namespace gtsam { + +/// Base exception type that uses tbb_exception if GTSAM is compiled with TBB. +template +class ThreadsafeException: +#ifdef GTSAM_USE_TBB + public tbb::tbb_exception +#else +public std::exception +#endif +{ +#ifdef GTSAM_USE_TBB +private: + typedef tbb::tbb_exception Base; +protected: + typedef std::basic_string, + tbb::tbb_allocator > String; +#else +private: + typedef std::exception Base; +protected: + typedef std::string String; +#endif + +protected: + bool dynamic_; ///< Whether this object was moved + mutable boost::optional description_; ///< Optional description + + /// Default constructor is protected - may only be created from derived classes + ThreadsafeException() : + dynamic_(false) { + } + + /// Copy constructor is protected - may only be created from derived classes + ThreadsafeException(const ThreadsafeException& other) : + Base(other), dynamic_(false) { + } + + /// Construct with description string + ThreadsafeException(const std::string& description) : + dynamic_(false), description_( + String(description.begin(), description.end())) { + } + + /// Default destructor doesn't have the throw() + virtual ~ThreadsafeException() throw () { + } + +public: + // Implement functions for tbb_exception +#ifdef GTSAM_USE_TBB + virtual tbb::tbb_exception* move() throw () { + void* cloneMemory = scalable_malloc(sizeof(DERIVED)); + if (!cloneMemory) { + std::cerr << "Failed allocating memory to copy thrown exception, exiting now." << std::endl; + exit(-1); + } + DERIVED* clone = ::new(cloneMemory) DERIVED(static_cast(*this)); + clone->dynamic_ = true; + return clone; + } + + virtual void destroy() throw () { + if (dynamic_) { + DERIVED* derivedPtr = static_cast(this); + derivedPtr->~DERIVED(); + scalable_free(derivedPtr); + } + } + + virtual void throw_self() { + throw *static_cast(this); + } + + virtual const char* name() const throw () { + return typeid(DERIVED).name(); + } +#endif + + virtual const char* what() const throw () { + return description_ ? description_->c_str() : ""; + } +}; + +/// Thread-safe runtime error exception +class RuntimeErrorThreadsafe: public ThreadsafeException { +public: + /// Construct with a string describing the exception + RuntimeErrorThreadsafe(const std::string& description) : + ThreadsafeException(description) { + } +}; + +/// Thread-safe out of range exception +class OutOfRangeThreadsafe: public ThreadsafeException { +public: + /// Construct with a string describing the exception + OutOfRangeThreadsafe(const std::string& description) : + ThreadsafeException(description) { + } +}; + +/// Thread-safe invalid argument exception +class InvalidArgumentThreadsafe: public ThreadsafeException< + InvalidArgumentThreadsafe> { +public: + /// Construct with a string describing the exception + InvalidArgumentThreadsafe(const std::string& description) : + ThreadsafeException(description) { + } +}; + +/// Indicate Cholesky factorization failure +class CholeskyFailed : public gtsam::ThreadsafeException +{ +public: + CholeskyFailed() throw() {} + virtual ~CholeskyFailed() throw() {} +}; + +} // namespace gtsam diff --git a/gtsam/base/debug.cpp b/gtsam/base/debug.cpp index 6abc98642..1c4d08dcd 100644 --- a/gtsam/base/debug.cpp +++ b/gtsam/base/debug.cpp @@ -17,6 +17,8 @@ */ #include +#include // for GTSAM_USE_TBB + #ifdef GTSAM_USE_TBB #include #endif diff --git a/gtsam/base/LieMatrix_Deprecated.h b/gtsam/base/deprecated/LieMatrix.h similarity index 97% rename from gtsam/base/LieMatrix_Deprecated.h rename to gtsam/base/deprecated/LieMatrix.h index 15b4401f2..e26f45511 100644 --- a/gtsam/base/LieMatrix_Deprecated.h +++ b/gtsam/base/deprecated/LieMatrix.h @@ -60,8 +60,9 @@ struct LieMatrix : public Matrix { /// @{ /** print @param s optional string naming the object */ - GTSAM_EXPORT void print(const std::string& name="") const; - + GTSAM_EXPORT void print(const std::string& name = "") const { + gtsam::print(matrix(), name); + } /** equality up to tolerance */ inline bool equals(const LieMatrix& expected, double tol=1e-5) const { return gtsam::equal_with_abs_tol(matrix(), expected.matrix(), tol); diff --git a/gtsam/base/LieScalar_Deprecated.h b/gtsam/base/deprecated/LieScalar.h similarity index 92% rename from gtsam/base/LieScalar_Deprecated.h rename to gtsam/base/deprecated/LieScalar.h index 6ffc76d37..f9c424e95 100644 --- a/gtsam/base/LieScalar_Deprecated.h +++ b/gtsam/base/deprecated/LieScalar.h @@ -48,8 +48,10 @@ namespace gtsam { /// @name Testable /// @{ - void print(const std::string& name="") const; - bool equals(const LieScalar& expected, double tol=1e-5) const { + void print(const std::string& name = "") const { + std::cout << name << ": " << d_ << std::endl; + } + bool equals(const LieScalar& expected, double tol = 1e-5) const { return fabs(expected.d_ - d_) <= tol; } /// @} diff --git a/gtsam/base/LieVector_Deprecated.h b/gtsam/base/deprecated/LieVector.h similarity index 92% rename from gtsam/base/LieVector_Deprecated.h rename to gtsam/base/deprecated/LieVector.h index 67c42c748..4a85036e0 100644 --- a/gtsam/base/LieVector_Deprecated.h +++ b/gtsam/base/deprecated/LieVector.h @@ -18,6 +18,7 @@ #pragma once #include +#include namespace gtsam { @@ -50,11 +51,15 @@ struct LieVector : public Vector { LieVector(double d) : Vector((Vector(1) << d).finished()) {} /** constructor with size and initial data, row order ! */ - GTSAM_EXPORT LieVector(size_t m, const double* const data); + GTSAM_EXPORT LieVector(size_t m, const double* const data) : Vector(m) { + for (size_t i = 0; i < m; i++) (*this)(i) = data[i]; + } /// @name Testable /// @{ - GTSAM_EXPORT void print(const std::string& name="") const; + GTSAM_EXPORT void print(const std::string& name="") const { + gtsam::print(vector(), name); + } bool equals(const LieVector& expected, double tol=1e-5) const { return gtsam::equal(vector(), expected.vector(), tol); } diff --git a/gtsam/base/serializationTestHelpers.h b/gtsam/base/serializationTestHelpers.h index b6593bd9f..f408427d8 100644 --- a/gtsam/base/serializationTestHelpers.h +++ b/gtsam/base/serializationTestHelpers.h @@ -49,15 +49,15 @@ bool equality(const T& input = T()) { return input==output; } -// This version requires equals +// This version requires Testable template bool equalsObj(const T& input = T()) { T output; roundtrip(input,output); - return input.equals(output); + return assert_equal(input, output); } -// De-referenced version for pointers +// De-referenced version for pointers, requires equals method template bool equalsDereferenced(const T& input) { T output; @@ -84,15 +84,15 @@ bool equalityXML(const T& input = T()) { return input==output; } -// This version requires equals +// This version requires Testable template bool equalsXML(const T& input = T()) { T output; roundtripXML(input,output); - return input.equals(output); + return assert_equal(input, output); } -// This version is for pointers +// This version is for pointers, requires equals method template bool equalsDereferencedXML(const T& input = T()) { T output; @@ -119,15 +119,15 @@ bool equalityBinary(const T& input = T()) { return input==output; } -// This version requires equals +// This version requires Testable template bool equalsBinary(const T& input = T()) { T output; roundtripBinary(input,output); - return input.equals(output); + return assert_equal(input, output); } -// This version is for pointers +// This version is for pointers, requires equals method template bool equalsDereferencedBinary(const T& input = T()) { T output; diff --git a/gtsam/base/tests/testFastContainers.cpp b/gtsam/base/tests/testFastContainers.cpp index 464624bd4..19870fdeb 100644 --- a/gtsam/base/tests/testFastContainers.cpp +++ b/gtsam/base/tests/testFastContainers.cpp @@ -7,13 +7,14 @@ * @author Alex Cunningham */ -#include +#include +#include +#include #include #include -#include -#include +#include using namespace boost::assign; using namespace gtsam; @@ -21,7 +22,7 @@ using namespace gtsam; /* ************************************************************************* */ TEST( testFastContainers, KeySet ) { - FastVector init_vector; + FastVector init_vector; init_vector += 2, 3, 4, 5; FastSet actSet(init_vector); diff --git a/gtsam/base/tests/testLieMatrix.cpp b/gtsam/base/tests/testLieMatrix.cpp index 09caadabd..5e18e1495 100644 --- a/gtsam/base/tests/testLieMatrix.cpp +++ b/gtsam/base/tests/testLieMatrix.cpp @@ -15,8 +15,7 @@ */ #include -#include - +#include #include #include diff --git a/gtsam/base/tests/testLieScalar.cpp b/gtsam/base/tests/testLieScalar.cpp index 07e666fbe..bacb9dd1e 100644 --- a/gtsam/base/tests/testLieScalar.cpp +++ b/gtsam/base/tests/testLieScalar.cpp @@ -15,8 +15,7 @@ */ #include -#include - +#include #include #include diff --git a/gtsam/base/tests/testLieVector.cpp b/gtsam/base/tests/testLieVector.cpp index ed3afac8c..3c2885c18 100644 --- a/gtsam/base/tests/testLieVector.cpp +++ b/gtsam/base/tests/testLieVector.cpp @@ -15,8 +15,7 @@ */ #include -#include - +#include #include #include diff --git a/gtsam/base/tests/testOptionalJacobian.cpp b/gtsam/base/tests/testOptionalJacobian.cpp index 331fb49eb..de1c07dcf 100644 --- a/gtsam/base/tests/testOptionalJacobian.cpp +++ b/gtsam/base/tests/testOptionalJacobian.cpp @@ -61,20 +61,15 @@ TEST( OptionalJacobian, Constructors ) { } //****************************************************************************** +Matrix kTestMatrix = (Matrix23() << 11,12,13,21,22,23).finished(); + void test(OptionalJacobian<2, 3> H = boost::none) { if (H) - *H = Matrix23::Zero(); -} - -void testPtr(Matrix23* H = NULL) { - if (H) - *H = Matrix23::Zero(); + *H = kTestMatrix; } TEST( OptionalJacobian, Fixed) { - Matrix expected = Matrix23::Zero(); - // Default argument does nothing test(); @@ -82,61 +77,83 @@ TEST( OptionalJacobian, Fixed) { Matrix23 fixed1; fixed1.setOnes(); test(fixed1); - EXPECT(assert_equal(expected,fixed1)); + EXPECT(assert_equal(kTestMatrix,fixed1)); // Fixed size, no copy, pointer style Matrix23 fixed2; fixed2.setOnes(); test(&fixed2); - EXPECT(assert_equal(expected,fixed2)); + EXPECT(assert_equal(kTestMatrix,fixed2)); - // Empty is no longer a sign we don't want a matrix, we want it resized + // Passing in an empty matrix means we want it resized Matrix dynamic0; test(dynamic0); - EXPECT(assert_equal(expected,dynamic0)); + EXPECT(assert_equal(kTestMatrix,dynamic0)); // Dynamic wrong size Matrix dynamic1(3, 5); dynamic1.setOnes(); test(dynamic1); - EXPECT(assert_equal(expected,dynamic1)); + EXPECT(assert_equal(kTestMatrix,dynamic1)); // Dynamic right size Matrix dynamic2(2, 5); dynamic2.setOnes(); test(dynamic2); - EXPECT(assert_equal(expected, dynamic2)); + EXPECT(assert_equal(kTestMatrix, dynamic2)); } //****************************************************************************** void test2(OptionalJacobian<-1,-1> H = boost::none) { if (H) - *H = Matrix23::Zero(); // resizes + *H = kTestMatrix; // resizes } TEST( OptionalJacobian, Dynamic) { - Matrix expected = Matrix23::Zero(); - // Default argument does nothing test2(); - // Empty is no longer a sign we don't want a matrix, we want it resized + // Passing in an empty matrix means we want it resized Matrix dynamic0; test2(dynamic0); - EXPECT(assert_equal(expected,dynamic0)); + EXPECT(assert_equal(kTestMatrix,dynamic0)); // Dynamic wrong size Matrix dynamic1(3, 5); dynamic1.setOnes(); test2(dynamic1); - EXPECT(assert_equal(expected,dynamic1)); + EXPECT(assert_equal(kTestMatrix,dynamic1)); // Dynamic right size Matrix dynamic2(2, 5); dynamic2.setOnes(); test2(dynamic2); - EXPECT(assert_equal(expected, dynamic2)); + EXPECT(assert_equal(kTestMatrix, dynamic2)); +} + +//****************************************************************************** +void test3(double add, OptionalJacobian<2,1> H = boost::none) { + if (H) *H << add + 10, add + 20; +} + +// This function calls the above function three times, one for each column +void test4(OptionalJacobian<2, 3> H = boost::none) { + if (H) { + test3(1, H.cols<1>(0)); + test3(2, H.cols<1>(1)); + test3(3, H.cols<1>(2)); + } +} + +TEST(OptionalJacobian, Block) { + // Default argument does nothing + test4(); + + Matrix23 fixed; + fixed.setOnes(); + test4(fixed); + EXPECT(assert_equal(kTestMatrix, fixed)); } //****************************************************************************** diff --git a/gtsam/base/tests/testSerializationBase.cpp b/gtsam/base/tests/testSerializationBase.cpp index fceb2f4b4..1db28bcc8 100644 --- a/gtsam/base/tests/testSerializationBase.cpp +++ b/gtsam/base/tests/testSerializationBase.cpp @@ -16,6 +16,8 @@ * @date Feb 7, 2012 */ +#include + #include #include #include @@ -60,10 +62,10 @@ TEST (Serialization, FastMap) { /* ************************************************************************* */ TEST (Serialization, FastSet) { - FastSet set; - set.insert(1.0); - set.insert(2.0); - set.insert(3.0); + KeySet set; + set.insert(1); + set.insert(2); + set.insert(3); EXPECT(equality(set)); EXPECT(equalityXML(set)); diff --git a/gtsam/base/tests/testTestableAssertions.cpp b/gtsam/base/tests/testTestableAssertions.cpp index 364834e2a..305aa7ca9 100644 --- a/gtsam/base/tests/testTestableAssertions.cpp +++ b/gtsam/base/tests/testTestableAssertions.cpp @@ -15,8 +15,7 @@ */ #include -#include - +#include #include using namespace gtsam; diff --git a/gtsam/base/timing.cpp b/gtsam/base/timing.cpp index 36f1c2f5f..b76746ba0 100644 --- a/gtsam/base/timing.cpp +++ b/gtsam/base/timing.cpp @@ -16,24 +16,28 @@ * @date Oct 5, 2010 */ -#include -#include -#include -#include -#include -#include -#include -#include - #include #include +#include +#include +#include + +#include +#include +#include +#include +#include +#include +#include +#include + namespace gtsam { namespace internal { -GTSAM_EXPORT boost::shared_ptr timingRoot( +GTSAM_EXPORT boost::shared_ptr gTimingRoot( new TimingOutline("Total", getTicTocID("Total"))); -GTSAM_EXPORT boost::weak_ptr timingCurrent(timingRoot); +GTSAM_EXPORT boost::weak_ptr gCurrentTimer(gTimingRoot); /* ************************************************************************* */ // Implementation of TimingOutline @@ -50,8 +54,8 @@ void TimingOutline::add(size_t usecs, size_t usecsWall) { } /* ************************************************************************* */ -TimingOutline::TimingOutline(const std::string& label, size_t myId) : - myId_(myId), t_(0), tWall_(0), t2_(0.0), tIt_(0), tMax_(0), tMin_(0), n_(0), myOrder_( +TimingOutline::TimingOutline(const std::string& label, size_t id) : + id_(id), t_(0), tWall_(0), t2_(0.0), tIt_(0), tMax_(0), tMin_(0), n_(0), myOrder_( 0), lastChildOrder_(0), label_(label) { #ifdef GTSAM_USING_NEW_BOOST_TIMERS timer_.stop(); @@ -153,7 +157,7 @@ const boost::shared_ptr& TimingOutline::child(size_t child, } /* ************************************************************************* */ -void TimingOutline::ticInternal() { +void TimingOutline::tic() { #ifdef GTSAM_USING_NEW_BOOST_TIMERS assert(timer_.is_stopped()); timer_.start(); @@ -169,7 +173,7 @@ void TimingOutline::ticInternal() { } /* ************************************************************************* */ -void TimingOutline::tocInternal() { +void TimingOutline::toc() { #ifdef GTSAM_USING_NEW_BOOST_TIMERS assert(!timer_.is_stopped()); @@ -212,7 +216,6 @@ void TimingOutline::finishedIteration() { } /* ************************************************************************* */ -// Generate or retrieve a unique global ID number that will be used to look up tic_/toc statements size_t getTicTocID(const char *descriptionC) { const std::string description(descriptionC); // Global (static) map from strings to ID numbers and current next ID number @@ -232,37 +235,33 @@ size_t getTicTocID(const char *descriptionC) { } /* ************************************************************************* */ -void ticInternal(size_t id, const char *labelC) { +void tic(size_t id, const char *labelC) { const std::string label(labelC); - if (ISDEBUG("timing-verbose")) - std::cout << "gttic_(" << id << ", " << label << ")" << std::endl; boost::shared_ptr node = // - timingCurrent.lock()->child(id, label, timingCurrent); - timingCurrent = node; - node->ticInternal(); + gCurrentTimer.lock()->child(id, label, gCurrentTimer); + gCurrentTimer = node; + node->tic(); } /* ************************************************************************* */ -void tocInternal(size_t id, const char *label) { - if (ISDEBUG("timing-verbose")) - std::cout << "gttoc(" << id << ", " << label << ")" << std::endl; - boost::shared_ptr current(timingCurrent.lock()); - if (id != current->myId_) { - timingRoot->print(); +void toc(size_t id, const char *label) { + boost::shared_ptr current(gCurrentTimer.lock()); + if (id != current->id_) { + gTimingRoot->print(); throw std::invalid_argument( (boost::format( "gtsam timing: Mismatched tic/toc: gttoc(\"%s\") called when last tic was \"%s\".") % label % current->label_).str()); } if (!current->parent_.lock()) { - timingRoot->print(); + gTimingRoot->print(); throw std::invalid_argument( (boost::format( "gtsam timing: Mismatched tic/toc: extra gttoc(\"%s\"), already at the root") % label).str()); } - current->tocInternal(); - timingCurrent = current->parent_; + current->toc(); + gCurrentTimer = current->parent_; } } // namespace internal diff --git a/gtsam/base/timing.h b/gtsam/base/timing.h index 7a43ef884..b89e15637 100644 --- a/gtsam/base/timing.h +++ b/gtsam/base/timing.h @@ -17,12 +17,16 @@ */ #pragma once -#include -#include -#include -#include -#include #include +#include +#include // for GTSAM_USE_TBB + +#include +#include +#include + +#include +#include // This file contains the GTSAM timing instrumentation library, a low-overhead method for // learning at a medium-fine level how much time various components of an algorithm take @@ -113,6 +117,7 @@ # include #else # include +# include #endif #ifdef GTSAM_USE_TBB @@ -125,16 +130,21 @@ namespace gtsam { namespace internal { + // Generate/retrieve a unique global ID number that will be used to look up tic/toc statements GTSAM_EXPORT size_t getTicTocID(const char *description); - GTSAM_EXPORT void ticInternal(size_t id, const char *label); - GTSAM_EXPORT void tocInternal(size_t id, const char *label); + + // Create new TimingOutline child for gCurrentTimer, make it gCurrentTimer, and call tic method + GTSAM_EXPORT void tic(size_t id, const char *label); + + // Call toc on gCurrentTimer and then set gCurrentTimer to the parent of gCurrentTimer + GTSAM_EXPORT void toc(size_t id, const char *label); /** * Timing Entry, arranged in a tree */ class GTSAM_EXPORT TimingOutline { protected: - size_t myId_; + size_t id_; size_t t_; size_t tWall_; double t2_ ; ///< cache the \sum t_i^2 @@ -176,29 +186,38 @@ namespace gtsam { void print2(const std::string& outline = "", const double parentTotal = -1.0) const; const boost::shared_ptr& child(size_t child, const std::string& label, const boost::weak_ptr& thisPtr); - void ticInternal(); - void tocInternal(); + void tic(); + void toc(); void finishedIteration(); - GTSAM_EXPORT friend void tocInternal(size_t id, const char *label); + GTSAM_EXPORT friend void toc(size_t id, const char *label); }; // \TimingOutline /** - * No documentation + * Small class that calls internal::tic at construction, and internol::toc when destroyed */ class AutoTicToc { - private: + private: size_t id_; - const char *label_; + const char* label_; bool isSet_; - public: - AutoTicToc(size_t id, const char* label) : id_(id), label_(label), isSet_(true) { ticInternal(id_, label_); } - void stop() { tocInternal(id_, label_); isSet_ = false; } - ~AutoTicToc() { if(isSet_) stop(); } + + public: + AutoTicToc(size_t id, const char* label) + : id_(id), label_(label), isSet_(true) { + tic(id_, label_); + } + void stop() { + toc(id_, label_); + isSet_ = false; + } + ~AutoTicToc() { + if (isSet_) stop(); + } }; - GTSAM_EXTERN_EXPORT boost::shared_ptr timingRoot; - GTSAM_EXTERN_EXPORT boost::weak_ptr timingCurrent; + GTSAM_EXTERN_EXPORT boost::shared_ptr gTimingRoot; + GTSAM_EXTERN_EXPORT boost::weak_ptr gCurrentTimer; } // Tic and toc functions that are always active (whether or not ENABLE_TIMING is defined) @@ -210,7 +229,7 @@ namespace gtsam { // tic #define gttic_(label) \ static const size_t label##_id_tic = ::gtsam::internal::getTicTocID(#label); \ - ::gtsam::internal::AutoTicToc label##_obj = ::gtsam::internal::AutoTicToc(label##_id_tic, #label) + ::gtsam::internal::AutoTicToc label##_obj(label##_id_tic, #label) // toc #define gttoc_(label) \ @@ -228,26 +247,26 @@ namespace gtsam { // indicate iteration is finished inline void tictoc_finishedIteration_() { - ::gtsam::internal::timingRoot->finishedIteration(); } + ::gtsam::internal::gTimingRoot->finishedIteration(); } // print inline void tictoc_print_() { - ::gtsam::internal::timingRoot->print(); } + ::gtsam::internal::gTimingRoot->print(); } // print mean and standard deviation inline void tictoc_print2_() { - ::gtsam::internal::timingRoot->print2(); } + ::gtsam::internal::gTimingRoot->print2(); } // get a node by label and assign it to variable #define tictoc_getNode(variable, label) \ static const size_t label##_id_getnode = ::gtsam::internal::getTicTocID(#label); \ const boost::shared_ptr variable = \ - ::gtsam::internal::timingCurrent.lock()->child(label##_id_getnode, #label, ::gtsam::internal::timingCurrent); + ::gtsam::internal::gCurrentTimer.lock()->child(label##_id_getnode, #label, ::gtsam::internal::gCurrentTimer); // reset inline void tictoc_reset_() { - ::gtsam::internal::timingRoot.reset(new ::gtsam::internal::TimingOutline("Total", ::gtsam::internal::getTicTocID("Total"))); - ::gtsam::internal::timingCurrent = ::gtsam::internal::timingRoot; } + ::gtsam::internal::gTimingRoot.reset(new ::gtsam::internal::TimingOutline("Total", ::gtsam::internal::getTicTocID("Total"))); + ::gtsam::internal::gCurrentTimer = ::gtsam::internal::gTimingRoot; } #ifdef ENABLE_TIMING #define gttic(label) gttic_(label) diff --git a/gtsam/base/treeTraversal-inst.h b/gtsam/base/treeTraversal-inst.h index 3edd7d076..12a29e45b 100644 --- a/gtsam/base/treeTraversal-inst.h +++ b/gtsam/base/treeTraversal-inst.h @@ -1,19 +1,19 @@ /* ---------------------------------------------------------------------------- -* 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) + * 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 + * See LICENSE for the license information -* -------------------------------------------------------------------------- */ + * -------------------------------------------------------------------------- */ /** -* @file treeTraversal-inst.h -* @author Richard Roberts -* @date April 9, 2013 -*/ + * @file treeTraversal-inst.h + * @author Richard Roberts + * @date April 9, 2013 + */ #pragma once #include @@ -22,6 +22,7 @@ #include #include #include +#include // for GTSAM_USE_TBB #include #include @@ -33,192 +34,197 @@ namespace gtsam { - /** Internal functions used for traversing trees */ - namespace treeTraversal { +/** Internal functions used for traversing trees */ +namespace treeTraversal { - /* ************************************************************************* */ - namespace { - // Internal node used in DFS preorder stack - template - struct TraversalNode { - bool expanded; - const boost::shared_ptr& treeNode; - DATA& parentData; - typename FastList::iterator dataPointer; - TraversalNode(const boost::shared_ptr& _treeNode, DATA& _parentData) : - expanded(false), treeNode(_treeNode), parentData(_parentData) {} - }; - - // Do nothing - default argument for post-visitor for tree traversal - struct no_op { - template - void operator()(const boost::shared_ptr& node, const DATA& data) {} - }; - - } - - /** Traverse a forest depth-first with pre-order and post-order visits. - * @param forest The forest of trees to traverse. The method \c forest.roots() should exist - * and return a collection of (shared) pointers to \c FOREST::Node. - * @param visitorPre \c visitorPre(node, parentData) will be called at every node, before - * visiting its children, and will be passed, by reference, the \c DATA object returned - * by the visit to its parent. Likewise, \c visitorPre should return the \c DATA object - * to pass to the children. The returned \c DATA object will be copy-constructed only - * upon returning to store internally, thus may be modified by visiting the children. - * Regarding efficiency, this copy-on-return is usually optimized out by the compiler. - * @param visitorPost \c visitorPost(node, data) will be called at every node, after visiting - * its children, and will be passed, by reference, the \c DATA object returned by the - * call to \c visitorPre (the \c DATA object may be modified by visiting the children). - * @param rootData The data to pass by reference to \c visitorPre when it is called on each - * root node. */ - template - void DepthFirstForest(FOREST& forest, DATA& rootData, VISITOR_PRE& visitorPre, VISITOR_POST& visitorPost) - { - // Typedefs - typedef typename FOREST::Node Node; - typedef boost::shared_ptr sharedNode; - - // Depth first traversal stack - typedef TraversalNode TraversalNode; - typedef FastList Stack; - Stack stack; - FastList dataList; // List to store node data as it is returned from the pre-order visitor - - // Add roots to stack (insert such that they are visited and processed in order - { - typename Stack::iterator insertLocation = stack.begin(); - BOOST_FOREACH(const sharedNode& root, forest.roots()) - stack.insert(insertLocation, TraversalNode(root, rootData)); - } - - // Traverse - while(!stack.empty()) - { - // Get next node - TraversalNode& node = stack.front(); - - if(node.expanded) { - // If already expanded, then the data stored in the node is no longer needed, so visit - // then delete it. - (void) visitorPost(node.treeNode, *node.dataPointer); - dataList.erase(node.dataPointer); - stack.pop_front(); - } else { - // If not already visited, visit the node and add its children (use reverse iterators so - // children are processed in the order they appear) - node.dataPointer = dataList.insert(dataList.end(), visitorPre(node.treeNode, node.parentData)); - typename Stack::iterator insertLocation = stack.begin(); - BOOST_FOREACH(const sharedNode& child, node.treeNode->children) - stack.insert(insertLocation, TraversalNode(child, *node.dataPointer)); - node.expanded = true; - } - } - assert(dataList.empty()); - } - - /** Traverse a forest depth-first, with a pre-order visit but no post-order visit. - * @param forest The forest of trees to traverse. The method \c forest.roots() should exist - * and return a collection of (shared) pointers to \c FOREST::Node. - * @param visitorPre \c visitorPre(node, parentData) will be called at every node, before - * visiting its children, and will be passed, by reference, the \c DATA object returned - * by the visit to its parent. Likewise, \c visitorPre should return the \c DATA object - * to pass to the children. The returned \c DATA object will be copy-constructed only - * upon returning to store internally, thus may be modified by visiting the children. - * Regarding efficiency, this copy-on-return is usually optimized out by the compiler. - * @param rootData The data to pass by reference to \c visitorPre when it is called on each - * root node. */ - template - void DepthFirstForest(FOREST& forest, DATA& rootData, VISITOR_PRE& visitorPre) - { - no_op visitorPost; - DepthFirstForest(forest, rootData, visitorPre, visitorPost); - } - - /** Traverse a forest depth-first with pre-order and post-order visits. - * @param forest The forest of trees to traverse. The method \c forest.roots() should exist - * and return a collection of (shared) pointers to \c FOREST::Node. - * @param visitorPre \c visitorPre(node, parentData) will be called at every node, before - * visiting its children, and will be passed, by reference, the \c DATA object returned - * by the visit to its parent. Likewise, \c visitorPre should return the \c DATA object - * to pass to the children. The returned \c DATA object will be copy-constructed only - * upon returning to store internally, thus may be modified by visiting the children. - * Regarding efficiency, this copy-on-return is usually optimized out by the compiler. - * @param visitorPost \c visitorPost(node, data) will be called at every node, after visiting - * its children, and will be passed, by reference, the \c DATA object returned by the - * call to \c visitorPre (the \c DATA object may be modified by visiting the children). - * @param rootData The data to pass by reference to \c visitorPre when it is called on each - * root node. */ - template - void DepthFirstForestParallel(FOREST& forest, DATA& rootData, VISITOR_PRE& visitorPre, VISITOR_POST& visitorPost, - int problemSizeThreshold = 10) - { -#ifdef GTSAM_USE_TBB - // Typedefs - typedef typename FOREST::Node Node; - typedef boost::shared_ptr sharedNode; - - tbb::task::spawn_root_and_wait(internal::CreateRootTask( - forest.roots(), rootData, visitorPre, visitorPost, problemSizeThreshold)); -#else - DepthFirstForest(forest, rootData, visitorPre, visitorPost); -#endif - } - - - /* ************************************************************************* */ - /** Traversal function for CloneForest */ - namespace { - template - boost::shared_ptr - CloneForestVisitorPre(const boost::shared_ptr& node, const boost::shared_ptr& parentPointer) - { - // Clone the current node and add it to its cloned parent - boost::shared_ptr clone = boost::make_shared(*node); - clone->children.clear(); - parentPointer->children.push_back(clone); - return clone; - } - } - - /** Clone a tree, copy-constructing new nodes (calling boost::make_shared) and setting up child - * pointers for a clone of the original tree. - * @param forest The forest of trees to clone. The method \c forest.roots() should exist and - * return a collection of shared pointers to \c FOREST::Node. - * @return The new collection of roots. */ - template - FastVector > CloneForest(const FOREST& forest) - { - typedef typename FOREST::Node Node; - boost::shared_ptr rootContainer = boost::make_shared(); - DepthFirstForest(forest, rootContainer, CloneForestVisitorPre); - return FastVector >(rootContainer->children.begin(), rootContainer->children.end()); - } - - - /* ************************************************************************* */ - /** Traversal function for PrintForest */ - namespace { - struct PrintForestVisitorPre - { - const KeyFormatter& formatter; - PrintForestVisitorPre(const KeyFormatter& formatter) : formatter(formatter) {} - template std::string operator()(const boost::shared_ptr& node, const std::string& parentString) - { - // Print the current node - node->print(parentString + "-", formatter); - // Increment the indentation - return parentString + "| "; - } - }; - } - - /** Print a tree, prefixing each line with \c str, and formatting keys using \c keyFormatter. - * To print each node, this function calls the \c print function of the tree nodes. */ - template - void PrintForest(const FOREST& forest, std::string str, const KeyFormatter& keyFormatter) { - PrintForestVisitorPre visitor(keyFormatter); - DepthFirstForest(forest, str, visitor); - } +/* ************************************************************************* */ +namespace { +// Internal node used in DFS preorder stack +template +struct TraversalNode { + bool expanded; + const boost::shared_ptr& treeNode; + DATA& parentData; + typename FastList::iterator dataPointer; + TraversalNode(const boost::shared_ptr& _treeNode, DATA& _parentData) : + expanded(false), treeNode(_treeNode), parentData(_parentData) { } +}; + +// Do nothing - default argument for post-visitor for tree traversal +struct no_op { + template + void operator()(const boost::shared_ptr& node, const DATA& data) { + } +}; + +} + +/** Traverse a forest depth-first with pre-order and post-order visits. + * @param forest The forest of trees to traverse. The method \c forest.roots() should exist + * and return a collection of (shared) pointers to \c FOREST::Node. + * @param visitorPre \c visitorPre(node, parentData) will be called at every node, before + * visiting its children, and will be passed, by reference, the \c DATA object returned + * by the visit to its parent. Likewise, \c visitorPre should return the \c DATA object + * to pass to the children. The returned \c DATA object will be copy-constructed only + * upon returning to store internally, thus may be modified by visiting the children. + * Regarding efficiency, this copy-on-return is usually optimized out by the compiler. + * @param visitorPost \c visitorPost(node, data) will be called at every node, after visiting + * its children, and will be passed, by reference, the \c DATA object returned by the + * call to \c visitorPre (the \c DATA object may be modified by visiting the children). + * @param rootData The data to pass by reference to \c visitorPre when it is called on each + * root node. */ +template +void DepthFirstForest(FOREST& forest, DATA& rootData, VISITOR_PRE& visitorPre, + VISITOR_POST& visitorPost) { + // Typedefs + typedef typename FOREST::Node Node; + typedef boost::shared_ptr sharedNode; + + // Depth first traversal stack + typedef TraversalNode TraversalNode; + typedef FastList Stack; + Stack stack; + FastList dataList; // List to store node data as it is returned from the pre-order visitor + + // Add roots to stack (insert such that they are visited and processed in order + { + typename Stack::iterator insertLocation = stack.begin(); + BOOST_FOREACH(const sharedNode& root, forest.roots()) + stack.insert(insertLocation, TraversalNode(root, rootData)); + } + + // Traverse + while (!stack.empty()) { + // Get next node + TraversalNode& node = stack.front(); + + if (node.expanded) { + // If already expanded, then the data stored in the node is no longer needed, so visit + // then delete it. + (void) visitorPost(node.treeNode, *node.dataPointer); + dataList.erase(node.dataPointer); + stack.pop_front(); + } else { + // If not already visited, visit the node and add its children (use reverse iterators so + // children are processed in the order they appear) + node.dataPointer = dataList.insert(dataList.end(), + visitorPre(node.treeNode, node.parentData)); + typename Stack::iterator insertLocation = stack.begin(); + BOOST_FOREACH(const sharedNode& child, node.treeNode->children) + stack.insert(insertLocation, TraversalNode(child, *node.dataPointer)); + node.expanded = true; + } + } + assert(dataList.empty()); +} + +/** Traverse a forest depth-first, with a pre-order visit but no post-order visit. + * @param forest The forest of trees to traverse. The method \c forest.roots() should exist + * and return a collection of (shared) pointers to \c FOREST::Node. + * @param visitorPre \c visitorPre(node, parentData) will be called at every node, before + * visiting its children, and will be passed, by reference, the \c DATA object returned + * by the visit to its parent. Likewise, \c visitorPre should return the \c DATA object + * to pass to the children. The returned \c DATA object will be copy-constructed only + * upon returning to store internally, thus may be modified by visiting the children. + * Regarding efficiency, this copy-on-return is usually optimized out by the compiler. + * @param rootData The data to pass by reference to \c visitorPre when it is called on each + * root node. */ +template +void DepthFirstForest(FOREST& forest, DATA& rootData, VISITOR_PRE& visitorPre) { + no_op visitorPost; + DepthFirstForest(forest, rootData, visitorPre, visitorPost); +} + +/** Traverse a forest depth-first with pre-order and post-order visits. + * @param forest The forest of trees to traverse. The method \c forest.roots() should exist + * and return a collection of (shared) pointers to \c FOREST::Node. + * @param visitorPre \c visitorPre(node, parentData) will be called at every node, before + * visiting its children, and will be passed, by reference, the \c DATA object returned + * by the visit to its parent. Likewise, \c visitorPre should return the \c DATA object + * to pass to the children. The returned \c DATA object will be copy-constructed only + * upon returning to store internally, thus may be modified by visiting the children. + * Regarding efficiency, this copy-on-return is usually optimized out by the compiler. + * @param visitorPost \c visitorPost(node, data) will be called at every node, after visiting + * its children, and will be passed, by reference, the \c DATA object returned by the + * call to \c visitorPre (the \c DATA object may be modified by visiting the children). + * @param rootData The data to pass by reference to \c visitorPre when it is called on each + * root node. */ +template +void DepthFirstForestParallel(FOREST& forest, DATA& rootData, + VISITOR_PRE& visitorPre, VISITOR_POST& visitorPost, + int problemSizeThreshold = 10) { +#ifdef GTSAM_USE_TBB + // Typedefs + typedef typename FOREST::Node Node; + typedef boost::shared_ptr sharedNode; + + tbb::task::spawn_root_and_wait( + internal::CreateRootTask(forest.roots(), rootData, visitorPre, + visitorPost, problemSizeThreshold)); +#else + DepthFirstForest(forest, rootData, visitorPre, visitorPost); +#endif +} + +/* ************************************************************************* */ +/** Traversal function for CloneForest */ +namespace { +template +boost::shared_ptr CloneForestVisitorPre( + const boost::shared_ptr& node, + const boost::shared_ptr& parentPointer) { + // Clone the current node and add it to its cloned parent + boost::shared_ptr clone = boost::make_shared(*node); + clone->children.clear(); + parentPointer->children.push_back(clone); + return clone; +} +} + +/** Clone a tree, copy-constructing new nodes (calling boost::make_shared) and setting up child + * pointers for a clone of the original tree. + * @param forest The forest of trees to clone. The method \c forest.roots() should exist and + * return a collection of shared pointers to \c FOREST::Node. + * @return The new collection of roots. */ +template +FastVector > CloneForest( + const FOREST& forest) { + typedef typename FOREST::Node Node; + boost::shared_ptr rootContainer = boost::make_shared(); + DepthFirstForest(forest, rootContainer, CloneForestVisitorPre); + return FastVector >(rootContainer->children.begin(), + rootContainer->children.end()); +} + +/* ************************************************************************* */ +/** Traversal function for PrintForest */ +namespace { +struct PrintForestVisitorPre { + const KeyFormatter& formatter; + PrintForestVisitorPre(const KeyFormatter& formatter) : + formatter(formatter) { + } + template std::string operator()( + const boost::shared_ptr& node, const std::string& parentString) { + // Print the current node + node->print(parentString + "-", formatter); + // Increment the indentation + return parentString + "| "; + } +}; +} + +/** Print a tree, prefixing each line with \c str, and formatting keys using \c keyFormatter. + * To print each node, this function calls the \c print function of the tree nodes. */ +template +void PrintForest(const FOREST& forest, std::string str, + const KeyFormatter& keyFormatter) { + PrintForestVisitorPre visitor(keyFormatter); + DepthFirstForest(forest, str, visitor); +} +} } diff --git a/gtsam/base/treeTraversal/parallelTraversalTasks.h b/gtsam/base/treeTraversal/parallelTraversalTasks.h index 7986f9534..c1df47a01 100644 --- a/gtsam/base/treeTraversal/parallelTraversalTasks.h +++ b/gtsam/base/treeTraversal/parallelTraversalTasks.h @@ -24,6 +24,7 @@ #ifdef GTSAM_USE_TBB # include +# include # undef max // TBB seems to include windows.h and we don't want these macros # undef min # undef ERROR diff --git a/gtsam/base/types.cpp b/gtsam/base/types.cpp deleted file mode 100644 index 03e7fd120..000000000 --- a/gtsam/base/types.cpp +++ /dev/null @@ -1,35 +0,0 @@ -/* ---------------------------------------------------------------------------- - - * 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 types.h - * @brief Typedefs for easier changing of types - * @author Richard Roberts - * @date Aug 21, 2010 - * @addtogroup base - */ - -#include -#include -#include - -namespace gtsam { - - /* ************************************************************************* */ - std::string _defaultKeyFormatter(Key key) { - const Symbol asSymbol(key); - if(asSymbol.chr() > 0) - return (std::string)asSymbol; - else - return boost::lexical_cast(key); - } - -} \ No newline at end of file diff --git a/gtsam/base/types.h b/gtsam/base/types.h index a66db13c8..84c94e73d 100644 --- a/gtsam/base/types.h +++ b/gtsam/base/types.h @@ -20,19 +20,16 @@ #pragma once #include -#include -#include +#include #include -#include +#include // for GTSAM_USE_TBB + #include -#include -#include #ifdef GTSAM_USE_TBB #include #include #include -#include #endif #ifdef GTSAM_USE_EIGEN_MKL_OPENMP @@ -58,22 +55,9 @@ namespace gtsam { /// Integer nonlinear key type typedef size_t Key; - /// Typedef for a function to format a key, i.e. to convert it to a string - typedef boost::function KeyFormatter; - - // Helper function for DefaultKeyFormatter - GTSAM_EXPORT std::string _defaultKeyFormatter(Key key); - - /// The default KeyFormatter, which is used if no KeyFormatter is passed to - /// a nonlinear 'print' function. Automatically detects plain integer keys - /// and Symbol keys. - static const KeyFormatter DefaultKeyFormatter = &_defaultKeyFormatter; - - /// The index type for Eigen objects typedef ptrdiff_t DenseIndex; - /* ************************************************************************* */ /** * Helper class that uses templates to select between two types based on @@ -148,104 +132,6 @@ namespace gtsam { return ListOfOneContainer(element); } - /* ************************************************************************* */ - /// Base exception type that uses tbb_exception if GTSAM is compiled with TBB. - template - class ThreadsafeException : -#ifdef GTSAM_USE_TBB - public tbb::tbb_exception -#else - public std::exception -#endif - { -#ifdef GTSAM_USE_TBB - private: - typedef tbb::tbb_exception Base; - protected: - typedef std::basic_string, tbb::tbb_allocator > String; -#else - private: - typedef std::exception Base; - protected: - typedef std::string String; -#endif - - protected: - bool dynamic_; ///< Whether this object was moved - mutable boost::optional description_; ///< Optional description - - /// Default constructor is protected - may only be created from derived classes - ThreadsafeException() : dynamic_(false) {} - - /// Copy constructor is protected - may only be created from derived classes - ThreadsafeException(const ThreadsafeException& other) : Base(other), dynamic_(false) {} - - /// Construct with description string - ThreadsafeException(const std::string& description) : dynamic_(false), description_(String(description.begin(), description.end())) {} - - /// Default destructor doesn't have the throw() - virtual ~ThreadsafeException() throw () {} - - public: - // Implement functions for tbb_exception -#ifdef GTSAM_USE_TBB - virtual tbb::tbb_exception* move() throw () { - void* cloneMemory = scalable_malloc(sizeof(DERIVED)); - if (!cloneMemory) { - std::cerr << "Failed allocating memory to copy thrown exception, exiting now." << std::endl; - exit(-1); - } - DERIVED* clone = ::new(cloneMemory) DERIVED(static_cast(*this)); - clone->dynamic_ = true; - return clone; - } - - virtual void destroy() throw() { - if (dynamic_) { - DERIVED* derivedPtr = static_cast(this); - derivedPtr->~DERIVED(); - scalable_free(derivedPtr); - } - } - - virtual void throw_self() { - throw *static_cast(this); } - - virtual const char* name() const throw() { - return typeid(DERIVED).name(); } -#endif - - virtual const char* what() const throw() { - return description_ ? description_->c_str() : ""; } - }; - - /* ************************************************************************* */ - /// Threadsafe runtime error exception - class RuntimeErrorThreadsafe : public ThreadsafeException - { - public: - /// Construct with a string describing the exception - RuntimeErrorThreadsafe(const std::string& description) : ThreadsafeException(description) {} - }; - - /* ************************************************************************* */ - /// Threadsafe runtime error exception - class OutOfRangeThreadsafe : public ThreadsafeException - { - public: - /// Construct with a string describing the exception - OutOfRangeThreadsafe(const std::string& description) : ThreadsafeException(description) {} - }; - - /* ************************************************************************* */ - /// Threadsafe invalid argument exception - class InvalidArgumentThreadsafe : public ThreadsafeException - { - public: - /// Construct with a string describing the exception - InvalidArgumentThreadsafe(const std::string& description) : ThreadsafeException(description) {} - }; - /* ************************************************************************* */ #ifdef __clang__ # pragma clang diagnostic push diff --git a/gtsam/discrete/DiscreteFactorGraph.cpp b/gtsam/discrete/DiscreteFactorGraph.cpp index 77be1d277..c2128c776 100644 --- a/gtsam/discrete/DiscreteFactorGraph.cpp +++ b/gtsam/discrete/DiscreteFactorGraph.cpp @@ -39,8 +39,8 @@ namespace gtsam { } /* ************************************************************************* */ - FastSet DiscreteFactorGraph::keys() const { - FastSet keys; + KeySet DiscreteFactorGraph::keys() const { + KeySet keys; BOOST_FOREACH(const sharedFactor& factor, *this) if (factor) keys.insert(factor->begin(), factor->end()); return keys; diff --git a/gtsam/discrete/DiscreteFactorGraph.h b/gtsam/discrete/DiscreteFactorGraph.h index c5b11adf1..cdfd7d522 100644 --- a/gtsam/discrete/DiscreteFactorGraph.h +++ b/gtsam/discrete/DiscreteFactorGraph.h @@ -120,7 +120,7 @@ public: } /** Return the set of variables involved in the factors (set union) */ - FastSet keys() const; + KeySet keys() const; /** return product of all factors as a single factor */ DecisionTreeFactor product() const; diff --git a/gtsam/discrete/Potentials.h b/gtsam/discrete/Potentials.h index 978781d63..1078b4c61 100644 --- a/gtsam/discrete/Potentials.h +++ b/gtsam/discrete/Potentials.h @@ -19,6 +19,7 @@ #include #include +#include #include #include diff --git a/gtsam/geometry/BearingRange.h b/gtsam/geometry/BearingRange.h new file mode 100644 index 000000000..27fe2f197 --- /dev/null +++ b/gtsam/geometry/BearingRange.h @@ -0,0 +1,133 @@ +/* ---------------------------------------------------------------------------- + + * 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 BearingRange.h + * @date July, 2015 + * @author Frank Dellaert + * @brief Bearing-Range product + */ + +#pragma once + +#include +#include +#include +#include + +namespace gtsam { + +// Forward declaration of Bearing functor which should be of A1*A2 -> return_type +// For example Bearing(pose,point), defined in Pose3.h will return Unit3 +// At time of writing only Pose2 and Pose3 specialize this functor. +template +struct Bearing; + +// Forward declaration of Range functor which should be of A1*A2 -> return_type +// For example Range(T1,T2), defined in Pose2.h will return double +// At time of writing Pose2, Pose3, and several Camera variants specialize this for several types +template +struct Range; + +/** + * Bearing-Range product for a particular A1,A2 combination will use the functors above to create + * a similar functor of type A1*A2 -> pair + * For example BearingRange(pose,point) will return pair + * and BearingRange(pose,point) will return pair + */ +template +struct BearingRange + : public ProductManifold::result_type, + typename Range::result_type> { + typedef typename Bearing::result_type B; + typedef typename Range::result_type R; + typedef ProductManifold Base; + + BearingRange() {} + BearingRange(const ProductManifold& br) : Base(br) {} + BearingRange(const B& b, const R& r) : Base(b, r) {} + + /// Prediction function that stacks measurements + static BearingRange Measure( + const A1& a1, const A2& a2, + OptionalJacobian::dimension> H1 = boost::none, + OptionalJacobian::dimension> H2 = + boost::none) { + typename MakeJacobian::type HB1; + typename MakeJacobian::type HB2; + typename MakeJacobian::type HR1; + typename MakeJacobian::type HR2; + + B b = Bearing()(a1, a2, H1 ? &HB1 : 0, H2 ? &HB2 : 0); + R r = Range()(a1, a2, H1 ? &HR1 : 0, H2 ? &HR2 : 0); + + if (H1) *H1 << HB1, HR1; + if (H2) *H2 << HB2, HR2; + return BearingRange(b, r); + } + + void print(const std::string& str = "") const { + std::cout << str; + traits::Print(this->first, "bearing "); + traits::Print(this->second, "range "); + } + bool equals(const BearingRange& m2, double tol = 1e-8) const { + return traits::Equals(this->first, m2.first, tol) && + traits::Equals(this->second, m2.second, tol); + } + + private: + /// Serialization function + template + void serialize(ARCHIVE& ar, const unsigned int /*version*/) { + ar& boost::serialization::make_nvp("bearing", this->first); + ar& boost::serialization::make_nvp("range", this->second); + } + + friend class boost::serialization::access; +}; + +// Declare this to be both Testable and a Manifold +template +struct traits > + : Testable >, + internal::ManifoldTraits > {}; + +// Helper class for to implement Range traits for classes with a bearing method +// For example, to specialize Bearing to Pose3 and Point3, using Pose3::bearing, it suffices to say +// template <> struct Bearing : HasBearing {}; +// where the third argument is used to indicate the return type +template +struct HasBearing { + typedef RT result_type; + RT operator()( + const A1& a1, const A2& a2, + OptionalJacobian::dimension, traits::dimension> H1, + OptionalJacobian::dimension, traits::dimension> H2) { + return a1.bearing(a2, H1, H2); + } +}; + +// Similar helper class for to implement Range traits for classes with a range method +// For classes with overloaded range methods, such as SimpleCamera, this can even be templated: +// template struct Range : HasRange {}; +template +struct HasRange { + typedef RT result_type; + RT operator()( + const A1& a1, const A2& a2, + OptionalJacobian::dimension, traits::dimension> H1, + OptionalJacobian::dimension, traits::dimension> H2) { + return a1.range(a2, H1, H2); + } +}; + +} // namespace gtsam diff --git a/gtsam/geometry/Cal3Bundler.h b/gtsam/geometry/Cal3Bundler.h index 234ee261a..d95c47f7b 100644 --- a/gtsam/geometry/Cal3Bundler.h +++ b/gtsam/geometry/Cal3Bundler.h @@ -18,7 +18,6 @@ #pragma once -#include #include namespace gtsam { diff --git a/gtsam/geometry/Cal3DS2.h b/gtsam/geometry/Cal3DS2.h index 9f4641f71..81463ac06 100644 --- a/gtsam/geometry/Cal3DS2.h +++ b/gtsam/geometry/Cal3DS2.h @@ -18,7 +18,6 @@ #pragma once -#include #include namespace gtsam { diff --git a/gtsam/geometry/Cal3Unified.h b/gtsam/geometry/Cal3Unified.h index 99bd04fb1..9982cec47 100644 --- a/gtsam/geometry/Cal3Unified.h +++ b/gtsam/geometry/Cal3Unified.h @@ -23,7 +23,6 @@ #pragma once #include -#include namespace gtsam { diff --git a/gtsam/geometry/Cal3_S2.cpp b/gtsam/geometry/Cal3_S2.cpp index 3ec29bbd2..c131d46f7 100644 --- a/gtsam/geometry/Cal3_S2.cpp +++ b/gtsam/geometry/Cal3_S2.cpp @@ -83,10 +83,21 @@ Point2 Cal3_S2::uncalibrate(const Point2& p, OptionalJacobian<2, 5> Dcal, } /* ************************************************************************* */ -Point2 Cal3_S2::calibrate(const Point2& p) const { - const double u = p.x(), v = p.y(); - return Point2((1 / fx_) * (u - u0_ - (s_ / fy_) * (v - v0_)), - (1 / fy_) * (v - v0_)); +Point2 Cal3_S2::calibrate(const Point2& p, OptionalJacobian<2,5> Dcal, + OptionalJacobian<2,2> Dp) const { + const double u = p.x(), v = p.y(); + double delta_u = u - u0_, delta_v = v - v0_; + double inv_fx = 1/ fx_, inv_fy = 1/fy_; + double inv_fy_delta_v = inv_fy * delta_v, inv_fx_s_inv_fy = inv_fx * s_ * inv_fy; + Point2 point(inv_fx * (delta_u - s_ * inv_fy_delta_v), + inv_fy_delta_v); + if(Dcal) + *Dcal << - inv_fx * point.x(), inv_fx * s_ * inv_fy * inv_fy_delta_v, -inv_fx * point.y(), + -inv_fx, inv_fx_s_inv_fy, + 0, -inv_fy * point.y(), 0, 0, -inv_fy; + if(Dp) + *Dp << inv_fx, -inv_fx_s_inv_fy, 0, inv_fy; + return point; } /* ************************************************************************* */ diff --git a/gtsam/geometry/Cal3_S2.h b/gtsam/geometry/Cal3_S2.h index 3d5342c92..4e62ca7e9 100644 --- a/gtsam/geometry/Cal3_S2.h +++ b/gtsam/geometry/Cal3_S2.h @@ -156,9 +156,12 @@ public: /** * convert image coordinates uv to intrinsic coordinates xy * @param p point in image coordinates + * @param Dcal optional 2*5 Jacobian wrpt Cal3_S2 parameters + * @param Dp optional 2*2 Jacobian wrpt intrinsic coordinates * @return point in intrinsic coordinates */ - Point2 calibrate(const Point2& p) const; + Point2 calibrate(const Point2& p, OptionalJacobian<2,5> Dcal = boost::none, + OptionalJacobian<2,2> Dp = boost::none) const; /** * convert homogeneous image coordinates to intrinsic coordinates diff --git a/gtsam/geometry/CalibratedCamera.cpp b/gtsam/geometry/CalibratedCamera.cpp index 33f2c84eb..2d27b4dc7 100644 --- a/gtsam/geometry/CalibratedCamera.cpp +++ b/gtsam/geometry/CalibratedCamera.cpp @@ -85,8 +85,7 @@ const Pose3& PinholeBase::getPose(OptionalJacobian<6, 6> H) const { } /* ************************************************************************* */ -Point2 PinholeBase::project_to_camera(const Point3& pc, - OptionalJacobian<2, 3> Dpoint) { +Point2 PinholeBase::Project(const Point3& pc, OptionalJacobian<2, 3> Dpoint) { double d = 1.0 / pc.z(); const double u = pc.x() * d, v = pc.y() * d; if (Dpoint) @@ -94,10 +93,22 @@ Point2 PinholeBase::project_to_camera(const Point3& pc, return Point2(u, v); } +/* ************************************************************************* */ +Point2 PinholeBase::Project(const Unit3& pc, OptionalJacobian<2, 2> Dpoint) { + if (Dpoint) { + Matrix32 Dpoint3_pc; + Matrix23 Duv_point3; + Point2 uv = Project(pc.point3(Dpoint3_pc), Duv_point3); + *Dpoint = Duv_point3 * Dpoint3_pc; + return uv; + } else + return Project(pc.point3()); +} + /* ************************************************************************* */ pair PinholeBase::projectSafe(const Point3& pw) const { const Point3 pc = pose().transform_to(pw); - const Point2 pn = project_to_camera(pc); + const Point2 pn = Project(pc); return make_pair(pn, pc.z() > 0); } @@ -109,9 +120,9 @@ Point2 PinholeBase::project2(const Point3& point, OptionalJacobian<2, 6> Dpose, const Point3 q = pose().transform_to(point, boost::none, Dpoint ? &Rt : 0); #ifdef GTSAM_THROW_CHEIRALITY_EXCEPTION if (q.z() <= 0) - throw CheiralityException(); + throw CheiralityException(); #endif - const Point2 pn = project_to_camera(q); + const Point2 pn = Project(q); if (Dpose || Dpoint) { const double d = 1.0 / q.z(); @@ -123,6 +134,32 @@ Point2 PinholeBase::project2(const Point3& point, OptionalJacobian<2, 6> Dpose, return pn; } +/* ************************************************************************* */ +Point2 PinholeBase::project2(const Unit3& pw, OptionalJacobian<2, 6> Dpose, + OptionalJacobian<2, 2> Dpoint) const { + + // world to camera coordinate + Matrix23 Dpc_rot; + Matrix2 Dpc_point; + const Unit3 pc = pose().rotation().unrotate(pw, Dpose ? &Dpc_rot : 0, + Dpose ? &Dpc_point : 0); + + // camera to normalized image coordinate + Matrix2 Dpn_pc; + const Point2 pn = Project(pc, Dpose || Dpoint ? &Dpn_pc : 0); + + // chain the Jacobian matrices + if (Dpose) { + // only rotation is important + Matrix26 Dpc_pose; + Dpc_pose.setZero(); + Dpc_pose.leftCols<3>() = Dpc_rot; + *Dpose = Dpn_pc * Dpc_pose; // 2x2 * 2x6 + } + if (Dpoint) + *Dpoint = Dpn_pc * Dpc_point; // 2x2 * 2*2 + return pn; +} /* ************************************************************************* */ Point3 PinholeBase::backproject_from_camera(const Point2& p, const double depth) { diff --git a/gtsam/geometry/CalibratedCamera.h b/gtsam/geometry/CalibratedCamera.h index f17cc6441..b1e5917b2 100644 --- a/gtsam/geometry/CalibratedCamera.h +++ b/gtsam/geometry/CalibratedCamera.h @@ -18,7 +18,13 @@ #pragma once +#include #include +#include +#include +#include +#include +#include namespace gtsam { @@ -39,6 +45,18 @@ public: */ class GTSAM_EXPORT PinholeBase { +public: + + /** Pose Concept requirements */ + typedef Rot3 Rotation; + typedef Point3 Translation; + + /** + * Some classes template on either PinholeCamera or StereoCamera, + * and this typedef informs those classes what "project" returns. + */ + typedef Point2 Measurement; + private: Pose3 pose_; ///< 3D pose of camera @@ -130,6 +148,16 @@ public: return pose_; } + /// get rotation + const Rot3& rotation() const { + return pose_.rotation(); + } + + /// get translation + const Point3& translation() const { + return pose_.translation(); + } + /// return pose, with derivative const Pose3& getPose(OptionalJacobian<6, 6> H) const; @@ -142,14 +170,21 @@ public: * Does *not* throw a CheiralityException, even if pc behind image plane * @param pc point in camera coordinates */ - static Point2 project_to_camera(const Point3& pc, // + static Point2 Project(const Point3& pc, // OptionalJacobian<2, 3> Dpoint = boost::none); + /** + * Project from 3D point at infinity in camera coordinates into image + * Does *not* throw a CheiralityException, even if pc behind image plane + * @param pc point in camera coordinates + */ + static Point2 Project(const Unit3& pc, // + OptionalJacobian<2, 2> Dpoint = boost::none); + /// Project a point into the image and check depth std::pair projectSafe(const Point3& pw) const; - /** - * Project point into the image + /** Project point into the image * Throws a CheiralityException if point behind image plane iff GTSAM_THROW_CHEIRALITY_EXCEPTION * @param point 3D point in world coordinates * @return the intrinsic coordinates of the projected point @@ -157,9 +192,33 @@ public: Point2 project2(const Point3& point, OptionalJacobian<2, 6> Dpose = boost::none, OptionalJacobian<2, 3> Dpoint = boost::none) const; + /** Project point at infinity into the image + * Throws a CheiralityException if point behind image plane iff GTSAM_THROW_CHEIRALITY_EXCEPTION + * @param point 3D point in world coordinates + * @return the intrinsic coordinates of the projected point + */ + Point2 project2(const Unit3& point, + OptionalJacobian<2, 6> Dpose = boost::none, + OptionalJacobian<2, 2> Dpoint = boost::none) const; + /// backproject a 2-dimensional point to a 3-dimensional point at given depth static Point3 backproject_from_camera(const Point2& p, const double depth); + /// @} + /// @name Advanced interface + /// @{ + + /** + * Return the start and end indices (inclusive) of the translation component of the + * exponential map parameterization + * @return a pair of [start, end] indices into the tangent space vector + */ + inline static std::pair translationInterval() { + return std::make_pair(3, 5); + } + + /// @} + private: /** Serialization function */ @@ -260,7 +319,7 @@ public: } /// @} - /// @name Transformations and mesaurement functions + /// @name Transformations and measurement functions /// @{ /** @@ -326,14 +385,16 @@ private: /// @} }; -template<> -struct traits : public internal::Manifold { -}; +// manifold traits +template <> +struct traits : public internal::Manifold {}; -template<> -struct traits : public internal::Manifold< - CalibratedCamera> { -}; +template <> +struct traits : public internal::Manifold {}; -} +// range traits, used in RangeFactor +template +struct Range : HasRange {}; + +} // namespace gtsam diff --git a/gtsam/geometry/CameraSet.h b/gtsam/geometry/CameraSet.h index 3e40d11a0..3208c6555 100644 --- a/gtsam/geometry/CameraSet.h +++ b/gtsam/geometry/CameraSet.h @@ -21,13 +21,14 @@ #include #include // for Cheirality exception #include +#include +#include #include namespace gtsam { /** * @brief A set of cameras, all with their own calibration - * Assumes that a camera is laid out as 6 Pose3 parameters then calibration */ template class CameraSet: public std::vector { @@ -40,28 +41,46 @@ protected: */ typedef typename CAMERA::Measurement Z; + static const int D = traits::dimension; ///< Camera dimension static const int ZDim = traits::dimension; ///< Measurement dimension - static const int Dim = traits::dimension; ///< Camera dimension + + /// Make a vector of re-projection errors + static Vector ErrorVector(const std::vector& predicted, + const std::vector& measured) { + + // Check size + size_t m = predicted.size(); + if (measured.size() != m) + throw std::runtime_error("CameraSet::errors: size mismatch"); + + // Project and fill error vector + Vector b(ZDim * m); + for (size_t i = 0, row = 0; i < m; i++, row += ZDim) { + Z e = predicted[i] - measured[i]; + b.segment(row) = e.vector(); + } + return b; + } public: /// Definitions for blocks of F - typedef Eigen::Matrix MatrixZD; // F - typedef std::pair FBlock; // Fblocks + typedef Eigen::Matrix MatrixZD; + typedef std::vector FBlocks; /** * print * @param s optional string naming the factor * @param keyFormatter optional formatter useful for printing Symbols */ - void print(const std::string& s = "") const { + virtual void print(const std::string& s = "") const { std::cout << s << "CameraSet, cameras = \n"; for (size_t k = 0; k < this->size(); ++k) - this->at(k).print(); + this->at(k).print(s); } /// equals - virtual bool equals(const CameraSet& p, double tol = 1e-9) const { + bool equals(const CameraSet& p, double tol = 1e-9) const { if (this->size() != p.size()) return false; bool camerasAreEqual = true; @@ -74,31 +93,226 @@ public: } /** - * Project a point, with derivatives in this, point, and calibration + * Project a point (possibly Unit3 at infinity), with derivatives + * Note that F is a sparse block-diagonal matrix, so instead of a large dense + * matrix this function returns the diagonal blocks. * throws CheiralityException */ - std::vector project(const Point3& point, boost::optional F = - boost::none, boost::optional E = boost::none, - boost::optional H = boost::none) const { + template + std::vector project2(const POINT& point, // + boost::optional Fs = boost::none, // + boost::optional E = boost::none) const { - size_t nrCameras = this->size(); - if (F) F->resize(ZDim * nrCameras, 6); - if (E) E->resize(ZDim * nrCameras, 3); - if (H && Dim > 6) H->resize(ZDim * nrCameras, Dim - 6); - std::vector z(nrCameras); + static const int N = FixedDimension::value; - for (size_t i = 0; i < nrCameras; i++) { - Eigen::Matrix Fi; - Eigen::Matrix Ei; - Eigen::Matrix Hi; - z[i] = this->at(i).project(point, F ? &Fi : 0, E ? &Ei : 0, H ? &Hi : 0); - if (F) F->block(ZDim * i, 0) = Fi; - if (E) E->block(ZDim * i, 0) = Ei; - if (H) H->block(ZDim * i, 0) = Hi; + // Allocate result + size_t m = this->size(); + std::vector z(m); + + // Allocate derivatives + if (E) + E->resize(ZDim * m, N); + if (Fs) + Fs->resize(m); + + // Project and fill derivatives + for (size_t i = 0; i < m; i++) { + MatrixZD Fi; + Eigen::Matrix Ei; + z[i] = this->at(i).project2(point, Fs ? &Fi : 0, E ? &Ei : 0); + if (Fs) + (*Fs)[i] = Fi; + if (E) + E->block(ZDim * i, 0) = Ei; } + return z; } + /// Calculate vector [project2(point)-z] of re-projection errors + template + Vector reprojectionError(const POINT& point, const std::vector& measured, + boost::optional Fs = boost::none, // + boost::optional E = boost::none) const { + return ErrorVector(project2(point, Fs, E), measured); + } + + /** + * Do Schur complement, given Jacobian as Fs,E,P, return SymmetricBlockMatrix + * G = F' * F - F' * E * P * E' * F + * g = F' * (b - E * P * E' * b) + * Fixed size version + */ + template // N = 2 or 3 + static SymmetricBlockMatrix SchurComplement(const FBlocks& Fs, + const Matrix& E, const Eigen::Matrix& P, const Vector& b) { + + // a single point is observed in m cameras + size_t m = Fs.size(); + + // Create a SymmetricBlockMatrix + size_t M1 = D * m + 1; + std::vector dims(m + 1); // this also includes the b term + std::fill(dims.begin(), dims.end() - 1, D); + dims.back() = 1; + SymmetricBlockMatrix augmentedHessian(dims, Matrix::Zero(M1, M1)); + + // Blockwise Schur complement + for (size_t i = 0; i < m; i++) { // for each camera + + const MatrixZD& Fi = Fs[i]; + const Eigen::Matrix Ei_P = // + E.block(ZDim * i, 0, ZDim, N) * P; + + // D = (Dx2) * ZDim + augmentedHessian(i, m) = Fi.transpose() * b.segment(ZDim * i) // F' * b + - Fi.transpose() * (Ei_P * (E.transpose() * b)); // D = (DxZDim) * (ZDimx3) * (N*ZDimm) * (ZDimm x 1) + + // (DxD) = (DxZDim) * ( (ZDimxD) - (ZDimx3) * (3xZDim) * (ZDimxD) ) + augmentedHessian(i, i) = Fi.transpose() + * (Fi - Ei_P * E.block(ZDim * i, 0, ZDim, N).transpose() * Fi); + + // upper triangular part of the hessian + for (size_t j = i + 1; j < m; j++) { // for each camera + const MatrixZD& Fj = Fs[j]; + + // (DxD) = (Dx2) * ( (2x2) * (2xD) ) + augmentedHessian(i, j) = -Fi.transpose() + * (Ei_P * E.block(ZDim * j, 0, ZDim, N).transpose() * Fj); + } + } // end of for over cameras + + augmentedHessian(m, m)(0, 0) += b.squaredNorm(); + return augmentedHessian; + } + + /// Computes Point Covariance P, with lambda parameter + template // N = 2 or 3 + static void ComputePointCovariance(Eigen::Matrix& P, + const Matrix& E, double lambda, bool diagonalDamping = false) { + + Matrix EtE = E.transpose() * E; + + if (diagonalDamping) { // diagonal of the hessian + EtE.diagonal() += lambda * EtE.diagonal(); + } else { + DenseIndex n = E.cols(); + EtE += lambda * Eigen::MatrixXd::Identity(n, n); + } + + P = (EtE).inverse(); + } + + /// Computes Point Covariance P, with lambda parameter, dynamic version + static Matrix PointCov(const Matrix& E, const double lambda = 0.0, + bool diagonalDamping = false) { + if (E.cols() == 2) { + Matrix2 P2; + ComputePointCovariance(P2, E, lambda, diagonalDamping); + return P2; + } else { + Matrix3 P3; + ComputePointCovariance(P3, E, lambda, diagonalDamping); + return P3; + } + } + + /** + * Do Schur complement, given Jacobian as Fs,E,P, return SymmetricBlockMatrix + * Dynamic version + */ + static SymmetricBlockMatrix SchurComplement(const FBlocks& Fblocks, + const Matrix& E, const Vector& b, const double lambda = 0.0, + bool diagonalDamping = false) { + SymmetricBlockMatrix augmentedHessian; + if (E.cols() == 2) { + Matrix2 P; + ComputePointCovariance(P, E, lambda, diagonalDamping); + augmentedHessian = SchurComplement(Fblocks, E, P, b); + } else { + Matrix3 P; + ComputePointCovariance(P, E, lambda, diagonalDamping); + augmentedHessian = SchurComplement(Fblocks, E, P, b); + } + return augmentedHessian; + } + + /** + * Applies Schur complement (exploiting block structure) to get a smart factor on cameras, + * and adds the contribution of the smart factor to a pre-allocated augmented Hessian. + */ + template // N = 2 or 3 + static void UpdateSchurComplement(const FBlocks& Fs, const Matrix& E, + const Eigen::Matrix& P, const Vector& b, + const FastVector& allKeys, const FastVector& keys, + /*output ->*/SymmetricBlockMatrix& augmentedHessian) { + + assert(keys.size()==Fs.size()); + assert(keys.size()<=allKeys.size()); + + FastMap KeySlotMap; + for (size_t slot = 0; slot < allKeys.size(); slot++) + KeySlotMap.insert(std::make_pair(allKeys[slot], slot)); + + // Schur complement trick + // G = F' * F - F' * E * P * E' * F + // g = F' * (b - E * P * E' * b) + + Eigen::Matrix matrixBlock; + + // a single point is observed in m cameras + size_t m = Fs.size(); // cameras observing current point + size_t M = (augmentedHessian.rows() - 1) / D; // all cameras in the group + assert(allKeys.size()==M); + + // Blockwise Schur complement + for (size_t i = 0; i < m; i++) { // for each camera in the current factor + + const MatrixZD& Fi = Fs[i]; + const Eigen::Matrix Ei_P = E.template block( + ZDim * i, 0) * P; + + // D = (DxZDim) * (ZDim) + // allKeys are the list of all camera keys in the group, e.g, (1,3,4,5,7) + // we should map those to a slot in the local (grouped) hessian (0,1,2,3,4) + // Key cameraKey_i = this->keys_[i]; + DenseIndex aug_i = KeySlotMap.at(keys[i]); + + // information vector - store previous vector + // vectorBlock = augmentedHessian(aug_i, aug_m).knownOffDiagonal(); + // add contribution of current factor + augmentedHessian(aug_i, M) = augmentedHessian(aug_i, M).knownOffDiagonal() + + Fi.transpose() * b.segment(ZDim * i) // F' * b + - Fi.transpose() * (Ei_P * (E.transpose() * b)); // D = (DxZDim) * (ZDimx3) * (N*ZDimm) * (ZDimm x 1) + + // (DxD) = (DxZDim) * ( (ZDimxD) - (ZDimx3) * (3xZDim) * (ZDimxD) ) + // main block diagonal - store previous block + matrixBlock = augmentedHessian(aug_i, aug_i); + // add contribution of current factor + augmentedHessian(aug_i, aug_i) = matrixBlock + + (Fi.transpose() + * (Fi - Ei_P * E.template block(ZDim * i, 0).transpose() * Fi)); + + // upper triangular part of the hessian + for (size_t j = i + 1; j < m; j++) { // for each camera + const MatrixZD& Fj = Fs[j]; + + DenseIndex aug_j = KeySlotMap.at(keys[j]); + + // (DxD) = (DxZDim) * ( (ZDimxZDim) * (ZDimxD) ) + // off diagonal block - store previous block + // matrixBlock = augmentedHessian(aug_i, aug_j).knownOffDiagonal(); + // add contribution of current factor + augmentedHessian(aug_i, aug_j) = + augmentedHessian(aug_i, aug_j).knownOffDiagonal() + - Fi.transpose() + * (Ei_P * E.template block(ZDim * j, 0).transpose() * Fj); + } + } // end of for over cameras + + augmentedHessian(M, M)(0, 0) += b.squaredNorm(); + } + private: /// Serialization function @@ -109,6 +323,9 @@ private: } }; +template +const int CameraSet::D; + template const int CameraSet::ZDim; diff --git a/gtsam/geometry/OrientedPlane3.cpp b/gtsam/geometry/OrientedPlane3.cpp index e96708942..95290497d 100644 --- a/gtsam/geometry/OrientedPlane3.cpp +++ b/gtsam/geometry/OrientedPlane3.cpp @@ -13,6 +13,7 @@ * @file OrientedPlane3.cpp * @date Dec 19, 2013 * @author Alex Trevor + * @author Zhaoyang Lv * @brief A plane, represented by a normal direction and perpendicular distance */ @@ -25,79 +26,54 @@ using namespace std; namespace gtsam { /* ************************************************************************* */ -/// The print fuction -void OrientedPlane3::print(const std::string& s) const { - Vector coeffs = planeCoefficients(); +void OrientedPlane3::print(const string& s) const { + Vector4 coeffs = planeCoefficients(); cout << s << " : " << coeffs << endl; } /* ************************************************************************* */ -OrientedPlane3 OrientedPlane3::Transform(const gtsam::OrientedPlane3& plane, - const gtsam::Pose3& xr, OptionalJacobian<3, 6> Hr, - OptionalJacobian<3, 3> Hp) { - Matrix n_hr; - Matrix n_hp; - Unit3 n_rotated = xr.rotation().unrotate(plane.n_, n_hr, n_hp); +OrientedPlane3 OrientedPlane3::transform(const Pose3& xr, OptionalJacobian<3, 3> Hp, + OptionalJacobian<3, 6> Hr) const { + Matrix23 D_rotated_plane; + Matrix22 D_rotated_pose; + Unit3 n_rotated = xr.rotation().unrotate(n_, D_rotated_plane, D_rotated_pose); - Vector n_unit = plane.n_.unitVector(); - Vector unit_vec = n_rotated.unitVector(); - double pred_d = n_unit.dot(xr.translation().vector()) + plane.d_; - OrientedPlane3 transformed_plane(unit_vec(0), unit_vec(1), unit_vec(2), - pred_d); + Vector3 unit_vec = n_rotated.unitVector(); + double pred_d = n_.unitVector().dot(xr.translation().vector()) + d_; if (Hr) { - *Hr = gtsam::zeros(3, 6); - (*Hr).block<2, 3>(0, 0) = n_hr; - (*Hr).block<1, 3>(2, 3) = unit_vec; + *Hr = zeros(3, 6); + Hr->block<2, 3>(0, 0) = D_rotated_plane; + Hr->block<1, 3>(2, 3) = unit_vec; } if (Hp) { - Vector xrp = xr.translation().vector(); - Matrix n_basis = plane.n_.basis(); - Vector hpp = n_basis.transpose() * xrp; - *Hp = gtsam::zeros(3, 3); - (*Hp).block<2, 2>(0, 0) = n_hp; - (*Hp).block<1, 2>(2, 0) = hpp; + Vector2 hpp = n_.basis().transpose() * xr.translation().vector(); + *Hp = Z_3x3; + Hp->block<2, 2>(0, 0) = D_rotated_pose; + Hp->block<1, 2>(2, 0) = hpp; (*Hp)(2, 2) = 1; } - return (transformed_plane); + return OrientedPlane3(unit_vec(0), unit_vec(1), unit_vec(2), pred_d); } + /* ************************************************************************* */ -Vector3 OrientedPlane3::error(const gtsam::OrientedPlane3& plane) const { +Vector3 OrientedPlane3::error(const OrientedPlane3& plane) const { Vector2 n_error = -n_.localCoordinates(plane.n_); - double d_error = d_ - plane.d_; - Vector3 e; - e << n_error(0), n_error(1), d_error; - return (e); + return Vector3(n_error(0), n_error(1), d_ - plane.d_); } /* ************************************************************************* */ OrientedPlane3 OrientedPlane3::retract(const Vector3& v) const { - // Retract the Unit3 - Vector2 n_v(v(0), v(1)); - Unit3 n_retracted = n_.retract(n_v); - double d_retracted = d_ + v(2); - return OrientedPlane3(n_retracted, d_retracted); + return OrientedPlane3(n_.retract(Vector2(v(0), v(1))), d_ + v(2)); } /* ************************************************************************* */ Vector3 OrientedPlane3::localCoordinates(const OrientedPlane3& y) const { Vector2 n_local = n_.localCoordinates(y.n_); double d_local = d_ - y.d_; - Vector3 e; - e << n_local(0), n_local(1), -d_local; - return e; + return Vector3(n_local(0), n_local(1), -d_local); } -/* ************************************************************************* */ -Vector3 OrientedPlane3::planeCoefficients() const { - Vector unit_vec = n_.unitVector(); - Vector3 a; - a << unit_vec[0], unit_vec[1], unit_vec[2], d_; - return a; -} - -/* ************************************************************************* */ - } diff --git a/gtsam/geometry/OrientedPlane3.h b/gtsam/geometry/OrientedPlane3.h index d987ad7b3..5c9a5cdef 100644 --- a/gtsam/geometry/OrientedPlane3.h +++ b/gtsam/geometry/OrientedPlane3.h @@ -14,6 +14,7 @@ * @date Dec 19, 2013 * @author Alex Trevor * @author Frank Dellaert + * @author Zhaoyang Lv * @brief An infinite plane, represented by a normal direction and perpendicular distance */ @@ -22,46 +23,56 @@ #include #include #include -#include namespace gtsam { -/// Represents an infinite plane in 3D. -class OrientedPlane3: public DerivedValue { +/** + * @brief Represents an infinite plane in 3D, which is composed of a planar normal and its + * perpendicular distance to the origin. + * Currently it provides a transform of the plane, and a norm 1 differencing of two planes. + * Refer to Trevor12iros for more math details. + */ +class GTSAM_EXPORT OrientedPlane3 { private: - Unit3 n_; /// The direction of the planar normal - double d_; /// The perpendicular distance to this plane + Unit3 n_; ///< The direction of the planar normal + double d_; ///< The perpendicular distance to this plane public: enum { dimension = 3 }; + /// @name Constructors /// @{ /// Default constructor OrientedPlane3() : - n_(), d_(0.0) { + n_(), d_(0.0) { } /// Construct from a Unit3 and a distance OrientedPlane3(const Unit3& s, double d) : - n_(s), d_(d) { + n_(s), d_(d) { } + /// Construct from a vector of plane coefficients OrientedPlane3(const Vector4& vec) : - n_(vec(0), vec(1), vec(2)), d_(vec(3)) { + n_(vec(0), vec(1), vec(2)), d_(vec(3)) { } - /// Construct from a, b, c, d + /// Construct from four numbers of plane coeffcients (a, b, c, d) OrientedPlane3(double a, double b, double c, double d) { Point3 p(a, b, c); n_ = Unit3(p); d_ = d; } + /// @} + /// @name Testable + /// @{ + /// The print function void print(const std::string& s = std::string()) const; @@ -70,13 +81,38 @@ public: return (n_.equals(s.n_, tol) && (fabs(d_ - s.d_) < tol)); } - /// Transforms a plane to the specified pose - static OrientedPlane3 Transform(const gtsam::OrientedPlane3& plane, - const gtsam::Pose3& xr, OptionalJacobian<3, 6> Hr = boost::none, - OptionalJacobian<3, 3> Hp = boost::none); + /// @} - /// Computes the error between two poses - Vector3 error(const gtsam::OrientedPlane3& plane) const; + /** Transforms a plane to the specified pose + * @param xr a transformation in current coordiante + * @param Hp optional Jacobian wrpt the destination plane + * @param Hr optional jacobian wrpt the pose transformation + * @return the transformed plane + */ + OrientedPlane3 transform(const Pose3& xr, + OptionalJacobian<3, 3> Hp = boost::none, + OptionalJacobian<3, 6> Hr = boost::none) const; + + /** + * @deprecated the static method has wrong Jacobian order, + * please use the member method transform() + * @param The raw plane + * @param xr a transformation in current coordiante + * @param Hr optional jacobian wrpt the pose transformation + * @param Hp optional Jacobian wrpt the destination plane + * @return the transformed plane + */ + static OrientedPlane3 Transform(const OrientedPlane3& plane, + const Pose3& xr, OptionalJacobian<3, 6> Hr = boost::none, + OptionalJacobian<3, 3> Hp = boost::none) { + return plane.transform(xr, Hp, Hr); + } + + /** Computes the error between two planes. + * The error is a norm 1 difference in tangent space. + * @param the other plane + */ + Vector3 error(const OrientedPlane3& plane) const; /// Dimensionality of tangent space = 3 DOF inline static size_t Dim() { @@ -94,22 +130,31 @@ public: /// The local coordinates function Vector3 localCoordinates(const OrientedPlane3& s) const; - /// Returns the plane coefficients (a, b, c, d) - Vector3 planeCoefficients() const; + /// Returns the plane coefficients + inline Vector4 planeCoefficients() const { + Vector3 unit_vec = n_.unitVector(); + return Vector4(unit_vec[0], unit_vec[1], unit_vec[2], d_); + } + /// Return the normal inline Unit3 normal() const { return n_; } + /// Return the perpendicular distance to the origin + inline double distance() const { + return d_; + } + /// @} }; template<> struct traits : public internal::Manifold< - OrientedPlane3> { +OrientedPlane3> { }; template<> struct traits : public internal::Manifold< - OrientedPlane3> { +OrientedPlane3> { }; } // namespace gtsam diff --git a/gtsam/geometry/PinholeCamera.h b/gtsam/geometry/PinholeCamera.h index fb57b0a69..6177dec95 100644 --- a/gtsam/geometry/PinholeCamera.h +++ b/gtsam/geometry/PinholeCamera.h @@ -19,6 +19,7 @@ #pragma once #include +#include namespace gtsam { @@ -31,14 +32,6 @@ namespace gtsam { template class GTSAM_EXPORT PinholeCamera: public PinholeBaseK { -public: - - /** - * Some classes template on either PinholeCamera or StereoCamera, - * and this typedef informs those classes what "project" returns. - */ - typedef Point2 Measurement; - private: typedef PinholeBaseK Base; ///< base class has 3D pose as private member @@ -153,7 +146,7 @@ public: const Pose3& getPose(OptionalJacobian<6, dimension> H) const { if (H) { H->setZero(); - H->block(0, 0, 6, 6) = I_6x6; + H->template block<6, 6>(0, 0) = I_6x6; } return Base::pose(); } @@ -184,16 +177,15 @@ public: if ((size_t) d.size() == 6) return PinholeCamera(this->pose().retract(d), calibration()); else - return PinholeCamera(this->pose().retract(d.head(6)), + return PinholeCamera(this->pose().retract(d.head<6>()), calibration().retract(d.tail(calibration().dim()))); } /// return canonical coordinate VectorK6 localCoordinates(const PinholeCamera& T2) const { VectorK6 d; - // TODO: why does d.head<6>() not compile?? - d.head(6) = this->pose().localCoordinates(T2.pose()); - d.tail(DimK) = calibration().localCoordinates(T2.calibration()); + d.template head<6>() = this->pose().localCoordinates(T2.pose()); + d.template tail() = calibration().localCoordinates(T2.calibration()); return d; } @@ -208,101 +200,34 @@ public: typedef Eigen::Matrix Matrix2K; - /** project a point from world coordinate to the image - * @param pw is a point in world coordinates - * @param Dpose is the Jacobian w.r.t. pose3 - * @param Dpoint is the Jacobian w.r.t. point3 - * @param Dcal is the Jacobian w.r.t. calibration + /** Templated projection of a 3D point or a point at infinity into the image + * @param pw either a Point3 or a Unit3, in world coordinates */ - Point2 project(const Point3& pw, OptionalJacobian<2, 6> Dpose = boost::none, - OptionalJacobian<2, 3> Dpoint = boost::none, - OptionalJacobian<2, DimK> Dcal = boost::none) const { - - // project to normalized coordinates - const Point2 pn = PinholeBase::project2(pw, Dpose, Dpoint); - - // uncalibrate to pixel coordinates - Matrix2 Dpi_pn; - const Point2 pi = calibration().uncalibrate(pn, Dcal, - Dpose || Dpoint ? &Dpi_pn : 0); - - // If needed, apply chain rule - if (Dpose) - *Dpose = Dpi_pn * *Dpose; - if (Dpoint) - *Dpoint = Dpi_pn * *Dpoint; - - return pi; - } - - /** project a point at infinity from world coordinate to the image - * @param pw is a point in the world coordinate (it is pw = lambda*[pw_x pw_y pw_z] with lambda->inf) - * @param Dpose is the Jacobian w.r.t. pose3 - * @param Dpoint is the Jacobian w.r.t. point3 - * @param Dcal is the Jacobian w.r.t. calibration - */ - Point2 projectPointAtInfinity(const Point3& pw, OptionalJacobian<2, 6> Dpose = - boost::none, OptionalJacobian<2, 2> Dpoint = boost::none, - OptionalJacobian<2, DimK> Dcal = boost::none) const { - - if (!Dpose && !Dpoint && !Dcal) { - const Point3 pc = this->pose().rotation().unrotate(pw); // get direction in camera frame (translation does not matter) - const Point2 pn = Base::project_to_camera(pc); // project the point to the camera - return K_.uncalibrate(pn); - } - - // world to camera coordinate - Matrix3 Dpc_rot, Dpc_point; - const Point3 pc = this->pose().rotation().unrotate(pw, Dpc_rot, Dpc_point); - - Matrix36 Dpc_pose; - Dpc_pose.setZero(); - Dpc_pose.leftCols<3>() = Dpc_rot; - - // camera to normalized image coordinate - Matrix23 Dpn_pc; // 2*3 - const Point2 pn = Base::project_to_camera(pc, Dpn_pc); - - // uncalibration - Matrix2 Dpi_pn; // 2*2 - const Point2 pi = K_.uncalibrate(pn, Dcal, Dpi_pn); - - // chain the Jacobian matrices - const Matrix23 Dpi_pc = Dpi_pn * Dpn_pc; - if (Dpose) - *Dpose = Dpi_pc * Dpc_pose; - if (Dpoint) - *Dpoint = (Dpi_pc * Dpc_point).leftCols<2>(); // only 2dof are important for the point (direction-only) - return pi; - } - - /** project a point from world coordinate to the image, fixed Jacobians - * @param pw is a point in the world coordinate - */ - Point2 project2( - const Point3& pw, // - OptionalJacobian<2, dimension> Dcamera = boost::none, - OptionalJacobian<2, 3> Dpoint = boost::none) const { - - // project to normalized coordinates + template + Point2 _project2(const POINT& pw, OptionalJacobian<2, dimension> Dcamera, + OptionalJacobian<2, FixedDimension::value> Dpoint) const { + // We just call 3-derivative version in Base Matrix26 Dpose; - const Point2 pn = PinholeBase::project2(pw, Dpose, Dpoint); - - // uncalibrate to pixel coordinates - Matrix2K Dcal; - Matrix2 Dpi_pn; - const Point2 pi = calibration().uncalibrate(pn, Dcamera ? &Dcal : 0, - Dcamera || Dpoint ? &Dpi_pn : 0); - - // If needed, calculate derivatives + Eigen::Matrix Dcal; + Point2 pi = Base::project(pw, Dcamera ? &Dpose : 0, Dpoint, + Dcamera ? &Dcal : 0); if (Dcamera) - *Dcamera << Dpi_pn * Dpose, Dcal; - if (Dpoint) - *Dpoint = Dpi_pn * (*Dpoint); - + *Dcamera << Dpose, Dcal; return pi; } + /// project a 3D point from world coordinates into the image + Point2 project2(const Point3& pw, OptionalJacobian<2, dimension> Dcamera = + boost::none, OptionalJacobian<2, 3> Dpoint = boost::none) const { + return _project2(pw, Dcamera, Dpoint); + } + + /// project a point at infinity from world coordinates into the image + Point2 project2(const Unit3& pw, OptionalJacobian<2, dimension> Dcamera = + boost::none, OptionalJacobian<2, 2> Dpoint = boost::none) const { + return _project2(pw, Dcamera, Dpoint); + } + /** * Calculate range to a landmark * @param point 3D location of landmark @@ -339,24 +264,22 @@ public: template double range(const PinholeCamera& camera, OptionalJacobian<1, dimension> Dcamera = boost::none, - boost::optional Dother = boost::none) const { + OptionalJacobian<1, 6 + CalibrationB::dimension> Dother = boost::none) const { Matrix16 Dcamera_, Dother_; double result = this->pose().range(camera.pose(), Dcamera ? &Dcamera_ : 0, Dother ? &Dother_ : 0); if (Dcamera) { - Dcamera->resize(1, 6 + DimK); *Dcamera << Dcamera_, Eigen::Matrix::Zero(); } if (Dother) { - Dother->resize(1, 6 + CalibrationB::dimension); Dother->setZero(); - Dother->block(0, 0, 1, 6) = Dother_; + Dother->template block<1, 6>(0, 0) = Dother_; } return result; } /** - * Calculate range to another camera + * Calculate range to a calibrated camera * @param camera Other camera * @return range (double) */ @@ -380,14 +303,18 @@ private: }; -template -struct traits > : public internal::Manifold< - PinholeCamera > { -}; +// manifold traits -template -struct traits > : public internal::Manifold< - PinholeCamera > { -}; +template +struct traits > + : public internal::Manifold > {}; -} // \ gtsam +template +struct traits > + : public internal::Manifold > {}; + +// range traits, used in RangeFactor +template +struct Range, T> : HasRange, T, double> {}; + +} // \ gtsam diff --git a/gtsam/geometry/PinholePose.h b/gtsam/geometry/PinholePose.h index bfb336f9a..ac453e048 100644 --- a/gtsam/geometry/PinholePose.h +++ b/gtsam/geometry/PinholePose.h @@ -30,14 +30,19 @@ namespace gtsam { * @addtogroup geometry * \nosubgrouping */ -template +template class GTSAM_EXPORT PinholeBaseK: public PinholeBase { - GTSAM_CONCEPT_MANIFOLD_TYPE(Calibration) +private: -public : + GTSAM_CONCEPT_MANIFOLD_TYPE(CALIBRATION); - typedef Calibration CalibrationType; + // Get dimensions of calibration type at compile time + static const int DimK = FixedDimension::value; + +public: + + typedef CALIBRATION CalibrationType; /// @name Standard Constructors /// @{ @@ -67,7 +72,7 @@ public : } /// return calibration - virtual const Calibration& calibration() const = 0; + virtual const CALIBRATION& calibration() const = 0; /// @} /// @name Transformations and measurement functions @@ -80,27 +85,65 @@ public : return pn; } - /** project a point from world coordinate to the image, fixed Jacobians + /** project a point from world coordinate to the image * @param pw is a point in the world coordinates */ - Point2 project2(const Point3& pw, OptionalJacobian<2, 6> Dpose = boost::none, - OptionalJacobian<2, 3> Dpoint = boost::none) const { + Point2 project(const Point3& pw) const { + const Point2 pn = PinholeBase::project2(pw); // project to normalized coordinates + return calibration().uncalibrate(pn); // uncalibrate to pixel coordinates + } + + /** project a point from world coordinate to the image + * @param pw is a point at infinity in the world coordinates + */ + Point2 project(const Unit3& pw) const { + const Unit3 pc = pose().rotation().unrotate(pw); // convert to camera frame + const Point2 pn = PinholeBase::Project(pc); // project to normalized coordinates + return calibration().uncalibrate(pn); // uncalibrate to pixel coordinates + } + + /** Templated projection of a point (possibly at infinity) from world coordinate to the image + * @param pw is a 3D point or aUnit3 (point at infinity) in world coordinates + * @param Dpose is the Jacobian w.r.t. pose3 + * @param Dpoint is the Jacobian w.r.t. point3 + * @param Dcal is the Jacobian w.r.t. calibration + */ + template + Point2 _project(const POINT& pw, OptionalJacobian<2, 6> Dpose, + OptionalJacobian<2, FixedDimension::value> Dpoint, + OptionalJacobian<2, DimK> Dcal) const { // project to normalized coordinates const Point2 pn = PinholeBase::project2(pw, Dpose, Dpoint); // uncalibrate to pixel coordinates Matrix2 Dpi_pn; - const Point2 pi = calibration().uncalibrate(pn, boost::none, + const Point2 pi = calibration().uncalibrate(pn, Dcal, Dpose || Dpoint ? &Dpi_pn : 0); // If needed, apply chain rule - if (Dpose) *Dpose = Dpi_pn * (*Dpose); - if (Dpoint) *Dpoint = Dpi_pn * (*Dpoint); + if (Dpose) + *Dpose = Dpi_pn * *Dpose; + if (Dpoint) + *Dpoint = Dpi_pn * *Dpoint; return pi; } + /// project a 3D point from world coordinates into the image + Point2 project(const Point3& pw, OptionalJacobian<2, 6> Dpose, + OptionalJacobian<2, 3> Dpoint = boost::none, + OptionalJacobian<2, DimK> Dcal = boost::none) const { + return _project(pw, Dpose, Dpoint, Dcal); + } + + /// project a point at infinity from world coordinates into the image + Point2 project(const Unit3& pw, OptionalJacobian<2, 6> Dpose, + OptionalJacobian<2, 2> Dpoint = boost::none, + OptionalJacobian<2, DimK> Dcal = boost::none) const { + return _project(pw, Dpose, Dpoint, Dcal); + } + /// backproject a 2-dimensional point to a 3-dimensional point at given depth Point3 backproject(const Point2& p, double depth) const { const Point2 pn = calibration().calibrate(p); @@ -108,9 +151,9 @@ public : } /// backproject a 2-dimensional point to a 3-dimensional point at infinity - Point3 backprojectPointAtInfinity(const Point2& p) const { + Unit3 backprojectPointAtInfinity(const Point2& p) const { const Point2 pn = calibration().calibrate(p); - const Point3 pc(pn.x(), pn.y(), 1.0); //by convention the last element is 1 + const Unit3 pc(pn.x(), pn.y(), 1.0); //by convention the last element is 1 return pose().rotation().rotate(pc); } @@ -178,13 +221,13 @@ private: * @addtogroup geometry * \nosubgrouping */ -template -class GTSAM_EXPORT PinholePose: public PinholeBaseK { +template +class GTSAM_EXPORT PinholePose: public PinholeBaseK { private: - typedef PinholeBaseK Base; ///< base class has 3D pose as private member - boost::shared_ptr K_; ///< shared pointer to fixed calibration + typedef PinholeBaseK Base; ///< base class has 3D pose as private member + boost::shared_ptr K_; ///< shared pointer to fixed calibration public: @@ -201,11 +244,11 @@ public: /** constructor with pose, uses default calibration */ explicit PinholePose(const Pose3& pose) : - Base(pose), K_(new Calibration()) { + Base(pose), K_(new CALIBRATION()) { } /** constructor with pose and calibration */ - PinholePose(const Pose3& pose, const boost::shared_ptr& K) : + PinholePose(const Pose3& pose, const boost::shared_ptr& K) : Base(pose), K_(K) { } @@ -220,14 +263,14 @@ public: * (theta 0 = looking in direction of positive X axis) * @param height camera height */ - static PinholePose Level(const boost::shared_ptr& K, + static PinholePose Level(const boost::shared_ptr& K, const Pose2& pose2, double height) { return PinholePose(Base::LevelPose(pose2, height), K); } /// PinholePose::level with default calibration static PinholePose Level(const Pose2& pose2, double height) { - return PinholePose::Level(boost::make_shared(), pose2, height); + return PinholePose::Level(boost::make_shared(), pose2, height); } /** @@ -240,8 +283,8 @@ public: * @param K optional calibration parameter */ static PinholePose Lookat(const Point3& eye, const Point3& target, - const Point3& upVector, const boost::shared_ptr& K = - boost::make_shared()) { + const Point3& upVector, const boost::shared_ptr& K = + boost::make_shared()) { return PinholePose(Base::LookatPose(eye, target, upVector), K); } @@ -251,12 +294,12 @@ public: /// Init from 6D vector explicit PinholePose(const Vector &v) : - Base(v), K_(new Calibration()) { + Base(v), K_(new CALIBRATION()) { } /// Init from Vector and calibration PinholePose(const Vector &v, const Vector &K) : - Base(v), K_(new Calibration(K)) { + Base(v), K_(new CALIBRATION(K)) { } /// @} @@ -286,10 +329,26 @@ public: } /// return calibration - virtual const Calibration& calibration() const { + virtual const CALIBRATION& calibration() const { return *K_; } + /** project a point from world coordinate to the image, 2 derivatives only + * @param pw is a point in world coordinates + * @param Dpose is the Jacobian w.r.t. the whole camera (really only the pose) + * @param Dpoint is the Jacobian w.r.t. point3 + */ + Point2 project2(const Point3& pw, OptionalJacobian<2, 6> Dpose = boost::none, + OptionalJacobian<2, 3> Dpoint = boost::none) const { + return Base::project(pw, Dpose, Dpoint); + } + + /// project2 version for point at infinity + Point2 project2(const Unit3& pw, OptionalJacobian<2, 6> Dpose = boost::none, + OptionalJacobian<2, 2> Dpoint = boost::none) const { + return Base::project(pw, Dpose, Dpoint); + } + /// @} /// @name Manifold /// @{ @@ -336,14 +395,14 @@ private: }; // end of class PinholePose -template -struct traits > : public internal::Manifold< - PinholePose > { +template +struct traits > : public internal::Manifold< + PinholePose > { }; -template -struct traits > : public internal::Manifold< - PinholePose > { +template +struct traits > : public internal::Manifold< + PinholePose > { }; } // \ gtsam diff --git a/gtsam/geometry/PinholeSet.h b/gtsam/geometry/PinholeSet.h new file mode 100644 index 000000000..5101e9fc8 --- /dev/null +++ b/gtsam/geometry/PinholeSet.h @@ -0,0 +1,85 @@ +/* ---------------------------------------------------------------------------- + + * 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 PinholeSet.h + * @brief A CameraSet of either CalibratedCamera, PinholePose, or PinholeCamera + * @author Frank Dellaert + */ + +#pragma once + +#include +#include +#include +#include + +namespace gtsam { + +/** + * PinholeSet: triangulates point and keeps an estimate of it around. + */ +template +class PinholeSet: public CameraSet { + +private: + typedef CameraSet Base; + typedef PinholeSet This; + +protected: + +public: + + /** Virtual destructor */ + virtual ~PinholeSet() { + } + + /// @name Testable + /// @{ + + /// print + virtual void print(const std::string& s = "") const { + Base::print(s); + } + + /// equals + bool equals(const PinholeSet& p, double tol = 1e-9) const { + return Base::equals(p, tol); // TODO all flags + } + + /// @} + + /// triangulateSafe + TriangulationResult triangulateSafe( + const std::vector& measured, + const TriangulationParameters& params) const { + return gtsam::triangulateSafe(*this, measured, params); + } + +private: + + /// Serialization function + friend class boost::serialization::access; + template + void serialize(ARCHIVE & ar, const unsigned int version) { + ar & BOOST_SERIALIZATION_BASE_OBJECT_NVP(Base); + } +}; + +template +struct traits > : public Testable > { +}; + +template +struct traits > : public Testable > { +}; + +} // \ namespace gtsam diff --git a/gtsam/geometry/Point3.cpp b/gtsam/geometry/Point3.cpp index a87aeb650..bffda9fef 100644 --- a/gtsam/geometry/Point3.cpp +++ b/gtsam/geometry/Point3.cpp @@ -58,6 +58,22 @@ Point3 Point3::operator/(double s) const { return Point3(x_ / s, y_ / s, z_ / s); } +/* ************************************************************************* */ +double Point3::distance(const Point3 &p2, OptionalJacobian<1, 3> H1, + OptionalJacobian<1, 3> H2) const { + double d = (p2 - *this).norm(); + if (H1) { + *H1 << x_ - p2.x(), y_ - p2.y(), z_ - p2.z(); + *H1 = *H1 *(1. / d); + } + + if (H2) { + *H2 << -x_ + p2.x(), -y_ + p2.y(), -z_ + p2.z(); + *H2 = *H2 *(1. / d); + } + return d; +} + /* ************************************************************************* */ Point3 Point3::add(const Point3 &q, OptionalJacobian<3,3> H1, OptionalJacobian<3,3> H2) const { @@ -75,13 +91,27 @@ Point3 Point3::sub(const Point3 &q, OptionalJacobian<3,3> H1, } /* ************************************************************************* */ -Point3 Point3::cross(const Point3 &q) const { +Point3 Point3::cross(const Point3 &q, OptionalJacobian<3, 3> H_p, OptionalJacobian<3, 3> H_q) const { + if (H_p) { + *H_p << skewSymmetric(-q.vector()); + } + if (H_q) { + *H_q << skewSymmetric(vector()); + } + return Point3(y_ * q.z_ - z_ * q.y_, z_ * q.x_ - x_ * q.z_, x_ * q.y_ - y_ * q.x_); } /* ************************************************************************* */ -double Point3::dot(const Point3 &q) const { +double Point3::dot(const Point3 &q, OptionalJacobian<1, 3> H_p, OptionalJacobian<1, 3> H_q) const { + if (H_p) { + *H_p << q.vector().transpose(); + } + if (H_q) { + *H_q << vector().transpose(); + } + return (x_ * q.x_ + y_ * q.y_ + z_ * q.z_); } @@ -116,6 +146,12 @@ ostream &operator<<(ostream &os, const Point3& p) { return os; } +/* ************************************************************************* */ +ostream &operator<<(ostream &os, const gtsam::Point3Pair &p) { + os << p.first << " <-> " << p.second; + return os; +} + /* ************************************************************************* */ } // namespace gtsam diff --git a/gtsam/geometry/Point3.h b/gtsam/geometry/Point3.h index 883e5fb62..e19b74d1c 100644 --- a/gtsam/geometry/Point3.h +++ b/gtsam/geometry/Point3.h @@ -22,6 +22,7 @@ #pragma once #include +#include #include #include @@ -36,8 +37,8 @@ namespace gtsam { private: - double x_, y_, z_; - + double x_, y_, z_; + public: enum { dimension = 3 }; @@ -55,7 +56,7 @@ namespace gtsam { /// @{ /// Construct from 3-element vector - Point3(const Vector3& v) { + explicit Point3(const Vector3& v) { x_ = v(0); y_ = v(1); z_ = v(2); @@ -81,6 +82,11 @@ namespace gtsam { /// inverse Point3 operator - () const { return Point3(-x_,-y_,-z_);} + /// add vector on right + inline Point3 operator +(const Vector3& v) const { + return Point3(x_ + v[0], y_ + v[1], z_ + v[2]); + } + /// add Point3 operator + (const Point3& q) const; @@ -98,20 +104,8 @@ namespace gtsam { Point3 operator / (double s) const; /** distance between two points */ - inline double distance(const Point3& p2, - OptionalJacobian<1,3> H1 = boost::none, OptionalJacobian<1,3> H2 = boost::none) const { - double d = (p2 - *this).norm(); - if (H1) { - *H1 << x_-p2.x(), y_-p2.y(), z_-p2.z(); - *H1 = *H1 *(1./d); - } - - if (H2) { - *H2 << -x_+p2.x(), -y_+p2.y(), -z_+p2.z(); - *H2 << *H2 *(1./d); - } - return d; - } + double distance(const Point3& p2, OptionalJacobian<1, 3> H1 = boost::none, + OptionalJacobian<1, 3> H2 = boost::none) const; /** @deprecated The following function has been deprecated, use distance above */ inline double dist(const Point3& p2) const { @@ -125,17 +119,19 @@ namespace gtsam { Point3 normalize(OptionalJacobian<3, 3> H = boost::none) const; /** cross product @return this x q */ - Point3 cross(const Point3 &q) const; + Point3 cross(const Point3 &q, OptionalJacobian<3, 3> H_p = boost::none, // + OptionalJacobian<3, 3> H_q = boost::none) const; /** dot product @return this * q*/ - double dot(const Point3 &q) const; + double dot(const Point3 &q, OptionalJacobian<1, 3> H_p = boost::none, // + OptionalJacobian<1, 3> H_q = boost::none) const; /// @} /// @name Standard Interface /// @{ /// equality - bool operator ==(const Point3& q) const; + bool operator ==(const Point3& q) const; /** return vectorized form (column-wise)*/ Vector3 vector() const { return Vector3(x_,y_,z_); } @@ -191,6 +187,10 @@ namespace gtsam { /// @} }; +// Convenience typedef +typedef std::pair Point3Pair; +std::ostream &operator<<(std::ostream &os, const gtsam::Point3Pair &p); + /// Syntactic sugar for multiplying coordinates by a scalar s*p inline Point3 operator*(double s, const Point3& p) { return p*s;} @@ -199,4 +199,19 @@ struct traits : public internal::VectorSpace {}; template<> struct traits : public internal::VectorSpace {}; -} + +template +struct Range; + +template <> +struct Range { + typedef double result_type; + double operator()(const Point3& p, const Point3& q, + OptionalJacobian<1, 3> H1 = boost::none, + OptionalJacobian<1, 3> H2 = boost::none) { + return p.distance(q, H1, H2); + } +}; + +} // namespace gtsam + diff --git a/gtsam/geometry/Pose2.cpp b/gtsam/geometry/Pose2.cpp index 9e87407f4..89f6b3754 100644 --- a/gtsam/geometry/Pose2.cpp +++ b/gtsam/geometry/Pose2.cpp @@ -201,95 +201,88 @@ Pose2 Pose2::inverse() const { /* ************************************************************************* */ // see doc/math.lyx, SE(2) section Point2 Pose2::transform_to(const Point2& point, - OptionalJacobian<2, 3> H1, OptionalJacobian<2, 2> H2) const { - Point2 d = point - t_; - Point2 q = r_.unrotate(d); - if (!H1 && !H2) return q; - if (H1) *H1 << - -1.0, 0.0, q.y(), - 0.0, -1.0, -q.x(); - if (H2) *H2 << r_.transpose(); + OptionalJacobian<2, 3> Hpose, OptionalJacobian<2, 2> Hpoint) const { + OptionalJacobian<2, 2> Htranslation = Hpose.cols<2>(0); + OptionalJacobian<2, 1> Hrotation = Hpose.cols<1>(2); + const Point2 q = r_.unrotate(point - t_, Hrotation, Hpoint); + if (Htranslation) *Htranslation << -1.0, 0.0, 0.0, -1.0; return q; } /* ************************************************************************* */ // see doc/math.lyx, SE(2) section -Point2 Pose2::transform_from(const Point2& p, - OptionalJacobian<2, 3> H1, OptionalJacobian<2, 2> H2) const { - const Point2 q = r_ * p; - if (H1 || H2) { - const Matrix2 R = r_.matrix(); - Matrix21 Drotate1; - Drotate1 << -q.y(), q.x(); - if (H1) *H1 << R, Drotate1; - if (H2) *H2 = R; // R - } +Point2 Pose2::transform_from(const Point2& point, + OptionalJacobian<2, 3> Hpose, OptionalJacobian<2, 2> Hpoint) const { + OptionalJacobian<2, 2> Htranslation = Hpose.cols<2>(0); + OptionalJacobian<2, 1> Hrotation = Hpose.cols<1>(2); + const Point2 q = r_.rotate(point, Hrotation, Hpoint); + if (Htranslation) *Htranslation = Hpoint ? *Hpoint : r_.matrix(); return q + t_; } /* ************************************************************************* */ Rot2 Pose2::bearing(const Point2& point, - OptionalJacobian<1, 3> H1, OptionalJacobian<1, 2> H2) const { + OptionalJacobian<1, 3> Hpose, OptionalJacobian<1, 2> Hpoint) const { // make temporary matrices - Matrix23 D1; Matrix2 D2; - Point2 d = transform_to(point, H1 ? &D1 : 0, H2 ? &D2 : 0); // uses pointer version - if (!H1 && !H2) return Rot2::relativeBearing(d); + Matrix23 D_d_pose; Matrix2 D_d_point; + Point2 d = transform_to(point, Hpose ? &D_d_pose : 0, Hpoint ? &D_d_point : 0); + if (!Hpose && !Hpoint) return Rot2::relativeBearing(d); Matrix12 D_result_d; - Rot2 result = Rot2::relativeBearing(d, D_result_d); - if (H1) *H1 = D_result_d * (D1); - if (H2) *H2 = D_result_d * (D2); + Rot2 result = Rot2::relativeBearing(d, Hpose || Hpoint ? &D_result_d : 0); + if (Hpose) *Hpose = D_result_d * D_d_pose; + if (Hpoint) *Hpoint = D_result_d * D_d_point; return result; } /* ************************************************************************* */ Rot2 Pose2::bearing(const Pose2& pose, - OptionalJacobian<1, 3> H1, OptionalJacobian<1, 3> H2) const { + OptionalJacobian<1, 3> Hpose, OptionalJacobian<1, 3> Hother) const { Matrix12 D2; - Rot2 result = bearing(pose.t(), H1, H2 ? &D2 : 0); - if (H2) { + Rot2 result = bearing(pose.t(), Hpose, Hother ? &D2 : 0); + if (Hother) { Matrix12 H2_ = D2 * pose.r().matrix(); - *H2 << H2_, Z_1x1; + *Hother << H2_, Z_1x1; } return result; } /* ************************************************************************* */ double Pose2::range(const Point2& point, - OptionalJacobian<1,3> H1, OptionalJacobian<1,2> H2) const { + OptionalJacobian<1,3> Hpose, OptionalJacobian<1,2> Hpoint) const { Point2 d = point - t_; - if (!H1 && !H2) return d.norm(); - Matrix12 H; - double r = d.norm(H); - if (H1) { - Matrix23 H1_; - H1_ << -r_.c(), r_.s(), 0.0, - -r_.s(), -r_.c(), 0.0; - *H1 = H * H1_; + if (!Hpose && !Hpoint) return d.norm(); + Matrix12 D_r_d; + double r = d.norm(D_r_d); + if (Hpose) { + Matrix23 D_d_pose; + D_d_pose << -r_.c(), r_.s(), 0.0, + -r_.s(), -r_.c(), 0.0; + *Hpose = D_r_d * D_d_pose; } - if (H2) *H2 = H; + if (Hpoint) *Hpoint = D_r_d; return r; } /* ************************************************************************* */ double Pose2::range(const Pose2& pose, - OptionalJacobian<1,3> H1, - OptionalJacobian<1,3> H2) const { + OptionalJacobian<1,3> Hpose, + OptionalJacobian<1,3> Hother) const { Point2 d = pose.t() - t_; - if (!H1 && !H2) return d.norm(); - Matrix12 H; - double r = d.norm(H); - if (H1) { - Matrix23 H1_; - H1_ << + if (!Hpose && !Hother) return d.norm(); + Matrix12 D_r_d; + double r = d.norm(D_r_d); + if (Hpose) { + Matrix23 D_d_pose; + D_d_pose << -r_.c(), r_.s(), 0.0, -r_.s(), -r_.c(), 0.0; - *H1 = H * H1_; + *Hpose = D_r_d * D_d_pose; } - if (H2) { - Matrix23 H2_; - H2_ << + if (Hother) { + Matrix23 D_d_other; + D_d_other << pose.r_.c(), -pose.r_.s(), 0.0, pose.r_.s(), pose.r_.c(), 0.0; - *H2 = H * H2_; + *Hother = D_r_d * D_d_other; } return r; } diff --git a/gtsam/geometry/Pose2.h b/gtsam/geometry/Pose2.h index f3cb9e2a1..31dfb479f 100644 --- a/gtsam/geometry/Pose2.h +++ b/gtsam/geometry/Pose2.h @@ -20,9 +20,11 @@ #pragma once +#include #include #include #include +#include namespace gtsam { @@ -289,11 +291,18 @@ inline Matrix wedge(const Vector& xi) { typedef std::pair Point2Pair; GTSAM_EXPORT boost::optional align(const std::vector& pairs); -template<> +template <> struct traits : public internal::LieGroup {}; -template<> +template <> struct traits : public internal::LieGroup {}; +// bearing and range traits, used in RangeFactor +template +struct Bearing : HasBearing {}; + +template +struct Range : HasRange {}; + } // namespace gtsam diff --git a/gtsam/geometry/Pose3.cpp b/gtsam/geometry/Pose3.cpp index 32fd75eb8..9954240fd 100644 --- a/gtsam/geometry/Pose3.cpp +++ b/gtsam/geometry/Pose3.cpp @@ -32,7 +32,7 @@ GTSAM_CONCEPT_POSE_INST(Pose3); /* ************************************************************************* */ Pose3::Pose3(const Pose2& pose2) : - R_(Rot3::rodriguez(0, 0, pose2.theta())), t_( + R_(Rot3::Rodrigues(0, 0, pose2.theta())), t_( Point3(pose2.x(), pose2.y(), 0)) { } @@ -112,24 +112,20 @@ bool Pose3::equals(const Pose3& pose, double tol) const { /* ************************************************************************* */ /** Modified from Murray94book version (which assumes w and v normalized?) */ Pose3 Pose3::Expmap(const Vector6& xi, OptionalJacobian<6, 6> H) { - if (H) { - *H = ExpmapDerivative(xi); - } + if (H) *H = ExpmapDerivative(xi); // get angular velocity omega and translational velocity v from twist xi - Point3 w(xi(0), xi(1), xi(2)), v(xi(3), xi(4), xi(5)); + Point3 omega(xi(0), xi(1), xi(2)), v(xi(3), xi(4), xi(5)); - double theta = w.norm(); - if (theta < 1e-10) { - static const Rot3 I; - return Pose3(I, v); - } else { - Point3 n(w / theta); // axis unit vector - Rot3 R = Rot3::rodriguez(n.vector(), theta); - double vn = n.dot(v); // translation parallel to n - Point3 n_cross_v = n.cross(v); // points towards axis - Point3 t = (n_cross_v - R * n_cross_v) / theta + vn * n; + Rot3 R = Rot3::Expmap(omega.vector()); + double theta2 = omega.dot(omega); + if (theta2 > std::numeric_limits::epsilon()) { + Point3 t_parallel = omega * omega.dot(v); // translation parallel to axis + Point3 omega_cross_v = omega.cross(v); // points towards axis + Point3 t = (omega_cross_v - R * omega_cross_v + t_parallel) / theta2; return Pose3(R, t); + } else { + return Pose3(R, v); } } @@ -197,10 +193,10 @@ Vector6 Pose3::ChartAtOrigin::Local(const Pose3& T, ChartJacobian H) { * The closed-form formula is similar to formula 102 in Barfoot14tro) */ static Matrix3 computeQforExpmapDerivative(const Vector6& xi) { - Vector3 w(sub(xi, 0, 3)); - Vector3 v(sub(xi, 3, 6)); - Matrix3 V = skewSymmetric(v); - Matrix3 W = skewSymmetric(w); + const Vector3 w = xi.head<3>(); + const Vector3 v = xi.tail<3>(); + const Matrix3 V = skewSymmetric(v); + const Matrix3 W = skewSymmetric(w); Matrix3 Q; @@ -219,8 +215,8 @@ static Matrix3 computeQforExpmapDerivative(const Vector6& xi) { // The closed-form formula in Barfoot14tro eq. (102) double phi = w.norm(); if (fabs(phi)>1e-5) { - double sinPhi = sin(phi), cosPhi = cos(phi); - double phi2 = phi * phi, phi3 = phi2 * phi, phi4 = phi3 * phi, phi5 = phi4 * phi; + const double sinPhi = sin(phi), cosPhi = cos(phi); + const double phi2 = phi * phi, phi3 = phi2 * phi, phi4 = phi3 * phi, phi5 = phi4 * phi; // Invert the sign of odd-order terms to have the right Jacobian Q = -0.5*V + (phi-sinPhi)/phi3*(W*V + V*W - W*V*W) + (1-phi2/2-cosPhi)/phi4*(W*W*V + V*W*W - 3*W*V*W) @@ -238,40 +234,37 @@ static Matrix3 computeQforExpmapDerivative(const Vector6& xi) { /* ************************************************************************* */ Matrix6 Pose3::ExpmapDerivative(const Vector6& xi) { - Vector3 w(sub(xi, 0, 3)); - Matrix3 Jw = Rot3::ExpmapDerivative(w); - Matrix3 Q = computeQforExpmapDerivative(xi); - Matrix6 J = (Matrix(6,6) << Jw, Z_3x3, Q, Jw).finished(); + const Vector3 w = xi.head<3>(); + const Matrix3 Jw = Rot3::ExpmapDerivative(w); + const Matrix3 Q = computeQforExpmapDerivative(xi); + Matrix6 J; + J << Jw, Z_3x3, Q, Jw; return J; } /* ************************************************************************* */ Matrix6 Pose3::LogmapDerivative(const Pose3& pose) { - Vector6 xi = Logmap(pose); - Vector3 w(sub(xi, 0, 3)); - Matrix3 Jw = Rot3::LogmapDerivative(w); - Matrix3 Q = computeQforExpmapDerivative(xi); - Matrix3 Q2 = -Jw*Q*Jw; - Matrix6 J = (Matrix(6,6) << Jw, Z_3x3, Q2, Jw).finished(); + const Vector6 xi = Logmap(pose); + const Vector3 w = xi.head<3>(); + const Matrix3 Jw = Rot3::LogmapDerivative(w); + const Matrix3 Q = computeQforExpmapDerivative(xi); + const Matrix3 Q2 = -Jw*Q*Jw; + Matrix6 J; + J << Jw, Z_3x3, Q2, Jw; return J; } /* ************************************************************************* */ const Point3& Pose3::translation(OptionalJacobian<3, 6> H) const { - if (H) { - *H << Z_3x3, rotation().matrix(); - } + if (H) *H << Z_3x3, rotation().matrix(); return t_; } /* ************************************************************************* */ Matrix4 Pose3::matrix() const { - const Matrix3 R = R_.matrix(); - const Vector3 T = t_.vector(); - Matrix14 A14; - A14 << 0.0, 0.0, 0.0, 1.0; + static const Matrix14 A14 = (Matrix14() << 0.0, 0.0, 0.0, 1.0).finished(); Matrix4 mat; - mat << R, T, A14; + mat << R_.matrix(), t_.vector(), A14; return mat; } @@ -285,15 +278,17 @@ Pose3 Pose3::transform_to(const Pose3& pose) const { /* ************************************************************************* */ Point3 Pose3::transform_from(const Point3& p, OptionalJacobian<3,6> Dpose, OptionalJacobian<3,3> Dpoint) const { + // Only get matrix once, to avoid multiple allocations, + // as well as multiple conversions in the Quaternion case + const Matrix3 R = R_.matrix(); if (Dpose) { - const Matrix3 R = R_.matrix(); - Matrix3 DR = R * skewSymmetric(-p.x(), -p.y(), -p.z()); - (*Dpose) << DR, R; + Dpose->leftCols<3>() = R * skewSymmetric(-p.x(), -p.y(), -p.z()); + Dpose->rightCols<3>() = R; } if (Dpoint) { - *Dpoint = R_.matrix(); + *Dpoint = R; } - return R_ * p + t_; + return Point3(R * p.vector()) + t_; } /* ************************************************************************* */ @@ -318,35 +313,47 @@ Point3 Pose3::transform_to(const Point3& p, OptionalJacobian<3,6> Dpose, /* ************************************************************************* */ double Pose3::range(const Point3& point, OptionalJacobian<1, 6> H1, - OptionalJacobian<1, 3> H2) const { + OptionalJacobian<1, 3> H2) const { + Matrix36 D_local_pose; + Matrix3 D_local_point; + Point3 local = transform_to(point, H1 ? &D_local_pose : 0, H2 ? &D_local_point : 0); if (!H1 && !H2) { - return transform_to(point).norm(); + return local.norm(); } else { - Matrix36 D1; - Matrix3 D2; - Point3 d = transform_to(point, H1 ? &D1 : 0, H2 ? &D2 : 0); - const double x = d.x(), y = d.y(), z = d.z(), d2 = x * x + y * y + z * z, - n = sqrt(d2); - Matrix13 D_result_d; - D_result_d << x / n, y / n, z / n; - if (H1) *H1 = D_result_d * D1; - if (H2) *H2 = D_result_d * D2; - return n; + Matrix13 D_r_local; + const double r = local.norm(D_r_local); + if (H1) *H1 = D_r_local * D_local_pose; + if (H2) *H2 = D_r_local * D_local_point; + return r; } } /* ************************************************************************* */ -double Pose3::range(const Pose3& pose, OptionalJacobian<1,6> H1, - OptionalJacobian<1,6> H2) const { - Matrix13 D2; - double r = range(pose.translation(), H1, H2? &D2 : 0); - if (H2) { - Matrix13 H2_ = D2 * pose.rotation().matrix(); - *H2 << Matrix13::Zero(), H2_; - } +double Pose3::range(const Pose3& pose, OptionalJacobian<1, 6> H1, + OptionalJacobian<1, 6> H2) const { + Matrix13 D_local_point; + double r = range(pose.translation(), H1, H2 ? &D_local_point : 0); + if (H2) *H2 << Matrix13::Zero(), D_local_point * pose.rotation().matrix(); return r; } +/* ************************************************************************* */ +Unit3 Pose3::bearing(const Point3& point, OptionalJacobian<2, 6> H1, + OptionalJacobian<2, 3> H2) const { + Matrix36 D_local_pose; + Matrix3 D_local_point; + Point3 local = transform_to(point, H1 ? &D_local_pose : 0, H2 ? &D_local_point : 0); + if (!H1 && !H2) { + return Unit3(local); + } else { + Matrix23 D_b_local; + Unit3 b = Unit3::FromPoint3(local, D_b_local); + if (H1) *H1 = D_b_local * D_local_pose; + if (H2) *H2 = D_b_local * D_local_point; + return b; + } +} + /* ************************************************************************* */ boost::optional align(const vector& pairs) { const size_t n = pairs.size(); @@ -380,7 +387,7 @@ boost::optional align(const vector& pairs) { Matrix3 UVtranspose = U * V.transpose(); Matrix3 detWeighting = I_3x3; detWeighting(2, 2) = UVtranspose.determinant(); - Rot3 R(Matrix(V * detWeighting * U.transpose())); + Rot3 R(Matrix3(V * detWeighting * U.transpose())); Point3 t = Point3(cq) - R * Point3(cp); return Pose3(R, t); } diff --git a/gtsam/geometry/Pose3.h b/gtsam/geometry/Pose3.h index 8a0f23404..f82e25424 100644 --- a/gtsam/geometry/Pose3.h +++ b/gtsam/geometry/Pose3.h @@ -19,6 +19,7 @@ #include +#include #include #include #include @@ -262,6 +263,14 @@ public: double range(const Pose3& pose, OptionalJacobian<1, 6> H1 = boost::none, OptionalJacobian<1, 6> H2 = boost::none) const; + /** + * Calculate bearing to a landmark + * @param point 3D location of landmark + * @return bearing (Unit3) + */ + Unit3 bearing(const Point3& point, OptionalJacobian<2, 6> H1 = boost::none, + OptionalJacobian<2, 3> H2 = boost::none) const; + /// @} /// @name Advanced Interface /// @{ @@ -323,11 +332,17 @@ GTSAM_EXPORT boost::optional align(const std::vector& pairs); // For MATLAB wrapper typedef std::vector Pose3Vector; -template<> +template <> struct traits : public internal::LieGroup {}; -template<> +template <> struct traits : public internal::LieGroup {}; +// bearing and range traits, used in RangeFactor +template <> +struct Bearing : HasBearing {}; -} // namespace gtsam +template +struct Range : HasRange {}; + +} // namespace gtsam diff --git a/gtsam/geometry/Quaternion.h b/gtsam/geometry/Quaternion.h index cd093ca61..0ab4a5ee6 100644 --- a/gtsam/geometry/Quaternion.h +++ b/gtsam/geometry/Quaternion.h @@ -20,6 +20,7 @@ #include #include #include // Logmap/Expmap derivatives +#include #define QUATERNION_TYPE Eigen::Quaternion<_Scalar,_Options> @@ -73,14 +74,22 @@ struct traits { return g.inverse(); } - /// Exponential map, simply be converting omega to axis/angle representation + /// Exponential map, using the inlined code from Eigen's conversion from axis/angle static Q Expmap(const Eigen::Ref& omega, - ChartJacobian H = boost::none) { - if(H) *H = SO3::ExpmapDerivative(omega); - if (omega.isZero()) return Q::Identity(); - else { - _Scalar angle = omega.norm(); - return Q(Eigen::AngleAxis<_Scalar>(angle, omega / angle)); + ChartJacobian H = boost::none) { + using std::cos; + using std::sin; + if (H) *H = SO3::ExpmapDerivative(omega.template cast()); + _Scalar theta2 = omega.dot(omega); + if (theta2 > std::numeric_limits<_Scalar>::epsilon()) { + _Scalar theta = std::sqrt(theta2); + _Scalar ha = _Scalar(0.5) * theta; + Vector3 vec = (sin(ha) / theta) * omega; + return Q(cos(ha), vec.x(), vec.y(), vec.z()); + } else { + // first order approximation sin(theta/2)/theta = 0.5 + Vector3 vec = _Scalar(0.5) * omega; + return Q(1.0, vec.x(), vec.y(), vec.z()); } } @@ -93,9 +102,9 @@ struct traits { static const double twoPi = 2.0 * M_PI, NearlyOne = 1.0 - 1e-10, NearlyNegativeOne = -1.0 + 1e-10; - Vector3 omega; + TangentVector omega; - const double qw = q.w(); + const _Scalar qw = q.w(); // See Quaternion-Logmap.nb in doc for Taylor expansions if (qw > NearlyOne) { // Taylor expansion of (angle / s) at 1 @@ -107,7 +116,7 @@ struct traits { omega = (-8. / 3. - 2. / 3. * qw) * q.vec(); } else { // Normal, away from zero case - double angle = 2 * acos(qw), s = sqrt(1 - qw * qw); + _Scalar angle = 2 * acos(qw), s = sqrt(1 - qw * qw); // Important: convert to [-pi,pi] to keep error continuous if (angle > M_PI) angle -= twoPi; @@ -116,7 +125,7 @@ struct traits { omega = (angle / s) * q.vec(); } - if(H) *H = SO3::LogmapDerivative(omega); + if(H) *H = SO3::LogmapDerivative(omega.template cast()); return omega; } diff --git a/gtsam/geometry/Rot3.cpp b/gtsam/geometry/Rot3.cpp index fa09ddc21..ef384c3ef 100644 --- a/gtsam/geometry/Rot3.cpp +++ b/gtsam/geometry/Rot3.cpp @@ -34,29 +34,12 @@ void Rot3::print(const std::string& s) const { } /* ************************************************************************* */ -Rot3 Rot3::rodriguez(const Point3& w, double theta) { - return rodriguez((Vector)w.vector(),theta); -} - -/* ************************************************************************* */ -Rot3 Rot3::rodriguez(const Unit3& w, double theta) { - return rodriguez(w.point3(),theta); -} - -/* ************************************************************************* */ -Rot3 Rot3::Random(boost::mt19937 & rng) { +Rot3 Rot3::Random(boost::mt19937& rng) { // TODO allow any engine without including all of boost :-( - Unit3 w = Unit3::Random(rng); - boost::uniform_real randomAngle(-M_PI,M_PI); + Unit3 axis = Unit3::Random(rng); + boost::uniform_real randomAngle(-M_PI, M_PI); double angle = randomAngle(rng); - return rodriguez(w,angle); -} - -/* ************************************************************************* */ -Rot3 Rot3::rodriguez(const Vector3& w) { - double t = w.norm(); - if (t < 1e-10) return Rot3(); - return rodriguez(w/t, t); + return AxisAngle(axis, angle); } /* ************************************************************************* */ @@ -140,7 +123,7 @@ Vector3 Rot3::rpy() const { /* ************************************************************************* */ Vector Rot3::quaternion() const { - Quaternion q = toQuaternion(); + gtsam::Quaternion q = toQuaternion(); Vector v(4); v(0) = q.w(); v(1) = q.x(); diff --git a/gtsam/geometry/Rot3.h b/gtsam/geometry/Rot3.h index 881c58579..264be1537 100644 --- a/gtsam/geometry/Rot3.h +++ b/gtsam/geometry/Rot3.h @@ -22,8 +22,9 @@ #pragma once -#include #include +#include +#include #include #include // Get GTSAM_USE_QUATERNIONS macro @@ -58,7 +59,7 @@ namespace gtsam { #ifdef GTSAM_USE_QUATERNIONS /** Internal Eigen Quaternion */ - Quaternion quaternion_; + gtsam::Quaternion quaternion_; #else Matrix3 rot_; #endif @@ -84,11 +85,33 @@ namespace gtsam { double R21, double R22, double R23, double R31, double R32, double R33); - /** constructor from a rotation matrix */ - Rot3(const Matrix3& R); + /** + * Constructor from a rotation matrix + * Version for generic matrices. Need casting to Matrix3 + * in quaternion mode, since Eigen's quaternion doesn't + * allow assignment/construction from a generic matrix. + * See: http://stackoverflow.com/questions/27094132/cannot-understand-if-this-is-circular-dependency-or-clang#tab-top + */ + template + inline Rot3(const Eigen::MatrixBase& R) { + #ifdef GTSAM_USE_QUATERNIONS + quaternion_=Matrix3(R); + #else + rot_ = R; + #endif + } - /** constructor from a rotation matrix */ - Rot3(const Matrix& R); + /** + * Constructor from a rotation matrix + * Overload version for Matrix3 to avoid casting in quaternion mode. + */ + inline Rot3(const Matrix3& R) { + #ifdef GTSAM_USE_QUATERNIONS + quaternion_=R; + #else + rot_ = R; + #endif + } /** Constructor from a quaternion. This can also be called using a plain * Vector, due to implicit conversion from Vector to Quaternion @@ -123,13 +146,13 @@ namespace gtsam { } /// Positive yaw is to right (as in aircraft heading). See ypr - static Rot3 yaw (double t) { return Rz(t); } + static Rot3 Yaw (double t) { return Rz(t); } /// Positive pitch is up (increasing aircraft altitude).See ypr - static Rot3 pitch(double t) { return Ry(t); } + static Rot3 Pitch(double t) { return Ry(t); } //// Positive roll is to right (increasing yaw in aircraft). - static Rot3 roll (double t) { return Rx(t); } + static Rot3 Roll (double t) { return Rx(t); } /** * Returns rotation nRb from body to nav frame. @@ -140,54 +163,67 @@ namespace gtsam { * as described in http://www.sedris.org/wg8home/Documents/WG80462.pdf. * Assumes vehicle coordinate frame X forward, Y right, Z down. */ - static Rot3 ypr (double y, double p, double r) { return RzRyRx(r,p,y);} + static Rot3 Ypr(double y, double p, double r) { return RzRyRx(r,p,y);} /** Create from Quaternion coefficients */ - static Rot3 quaternion(double w, double x, double y, double z) { - Quaternion q(w, x, y, z); + static Rot3 Quaternion(double w, double x, double y, double z) { + gtsam::Quaternion q(w, x, y, z); return Rot3(q); } /** - * Rodriguez' formula to compute an incremental rotation matrix - * @param w is the rotation axis, unit length - * @param theta rotation angle - * @return incremental rotation matrix + * Convert from axis/angle representation + * @param axis is the rotation axis, unit length + * @param angle rotation angle + * @return incremental rotation */ - static Rot3 rodriguez(const Vector3& w, double theta); + static Rot3 AxisAngle(const Vector3& axis, double angle) { +#ifdef GTSAM_USE_QUATERNIONS + return gtsam::Quaternion(Eigen::AngleAxis(angle, axis)); +#else + return SO3::AxisAngle(axis,angle); +#endif + } /** - * Rodriguez' formula to compute an incremental rotation matrix - * @param w is the rotation axis, unit length - * @param theta rotation angle - * @return incremental rotation matrix + * Convert from axis/angle representation + * @param axisw is the rotation axis, unit length + * @param angle rotation angle + * @return incremental rotation */ - static Rot3 rodriguez(const Point3& w, double theta); + static Rot3 AxisAngle(const Point3& axis, double angle) { + return AxisAngle(axis.vector(),angle); + } /** - * Rodriguez' formula to compute an incremental rotation matrix - * @param w is the rotation axis - * @param theta rotation angle - * @return incremental rotation matrix + * Convert from axis/angle representation + * @param axis is the rotation axis + * @param angle rotation angle + * @return incremental rotation */ - static Rot3 rodriguez(const Unit3& w, double theta); + static Rot3 AxisAngle(const Unit3& axis, double angle) { + return AxisAngle(axis.unitVector(),angle); + } /** - * Rodriguez' formula to compute an incremental rotation matrix - * @param v a vector of incremental roll,pitch,yaw - * @return incremental rotation matrix + * Rodrigues' formula to compute an incremental rotation + * @param w a vector of incremental roll,pitch,yaw + * @return incremental rotation */ - static Rot3 rodriguez(const Vector3& v); + static Rot3 Rodrigues(const Vector3& w) { + return Rot3::Expmap(w); + } /** - * Rodriguez' formula to compute an incremental rotation matrix + * Rodrigues' formula to compute an incremental rotation * @param wx Incremental roll (about X) * @param wy Incremental pitch (about Y) * @param wz Incremental yaw (about Z) - * @return incremental rotation matrix + * @return incremental rotation */ - static Rot3 rodriguez(double wx, double wy, double wz) - { return rodriguez(Vector3(wx, wy, wz));} + static Rot3 Rodrigues(double wx, double wy, double wz) { + return Rodrigues(Vector3(wx, wy, wz)); + } /// @} /// @name Testable @@ -272,11 +308,15 @@ namespace gtsam { /** * Exponential map at identity - create a rotation from canonical coordinates - * \f$ [R_x,R_y,R_z] \f$ using Rodriguez' formula + * \f$ [R_x,R_y,R_z] \f$ using Rodrigues' formula */ - static Rot3 Expmap(const Vector& v, OptionalJacobian<3,3> H = boost::none) { + static Rot3 Expmap(const Vector3& v, OptionalJacobian<3,3> H = boost::none) { if(H) *H = Rot3::ExpmapDerivative(v); - if (zero(v)) return Rot3(); else return rodriguez(v); +#ifdef GTSAM_USE_QUATERNIONS + return traits::Expmap(v); +#else + return traits::Expmap(v); +#endif } /** @@ -312,6 +352,17 @@ namespace gtsam { Point3 rotate(const Point3& p, OptionalJacobian<3,3> H1 = boost::none, OptionalJacobian<3,3> H2 = boost::none) const; + /// operator* for Vector3 + inline Vector3 operator*(const Vector3& v) const { + return rotate(Point3(v)).vector(); + } + + /// rotate for Vector3 + Vector3 rotate(const Vector3& v, OptionalJacobian<3, 3> H1 = boost::none, + OptionalJacobian<3, 3> H2 = boost::none) const { + return rotate(Point3(v), H1, H2).vector(); + } + /// rotate point from rotated coordinate frame to world = R*p Point3 operator*(const Point3& p) const; @@ -319,6 +370,12 @@ namespace gtsam { Point3 unrotate(const Point3& p, OptionalJacobian<3,3> H1 = boost::none, OptionalJacobian<3,3> H2=boost::none) const; + /// unrotate for Vector3 + Vector3 unrotate(const Vector3& v, OptionalJacobian<3, 3> H1 = boost::none, + OptionalJacobian<3, 3> H2 = boost::none) const { + return unrotate(Point3(v), H1, H2).vector(); + } + /// @} /// @name Group Action on Unit3 /// @{ @@ -362,13 +419,13 @@ namespace gtsam { /** * Use RQ to calculate yaw-pitch-roll angle representation - * @return a vector containing ypr s.t. R = Rot3::ypr(y,p,r) + * @return a vector containing ypr s.t. R = Rot3::Ypr(y,p,r) */ Vector3 ypr() const; /** * Use RQ to calculate roll-pitch-yaw angle representation - * @return a vector containing ypr s.t. R = Rot3::ypr(y,p,r) + * @return a vector containing ypr s.t. R = Rot3::Ypr(y,p,r) */ Vector3 rpy() const; @@ -403,7 +460,7 @@ namespace gtsam { /** Compute the quaternion representation of this rotation. * @return The quaternion */ - Quaternion toQuaternion() const; + gtsam::Quaternion toQuaternion() const; /** * Converts to a generic matrix to allow for use with matlab @@ -423,6 +480,24 @@ namespace gtsam { /// @} +#ifdef GTSAM_ALLOW_DEPRECATED_SINCE_V4 + /// @name Deprecated + /// @{ + static Rot3 rodriguez(const Vector3& axis, double angle) { return AxisAngle(axis, angle); } + static Rot3 rodriguez(const Point3& axis, double angle) { return AxisAngle(axis, angle); } + static Rot3 rodriguez(const Unit3& axis, double angle) { return AxisAngle(axis, angle); } + static Rot3 rodriguez(const Vector3& w) { return Rodrigues(w); } + static Rot3 rodriguez(double wx, double wy, double wz) { return Rodrigues(wx, wy, wz); } + static Rot3 yaw (double t) { return Yaw(t); } + static Rot3 pitch(double t) { return Pitch(t); } + static Rot3 roll (double t) { return Roll(t); } + static Rot3 ypr(double y, double p, double r) { return Ypr(r,p,y);} + static Rot3 quaternion(double w, double x, double y, double z) { + return Rot3::Quaternion(w, x, y, z); + } + /// @} +#endif + private: /** Serialization function */ diff --git a/gtsam/geometry/Rot3M.cpp b/gtsam/geometry/Rot3M.cpp index b4c79de3b..c3636000b 100644 --- a/gtsam/geometry/Rot3M.cpp +++ b/gtsam/geometry/Rot3M.cpp @@ -51,19 +51,7 @@ Rot3::Rot3(double R11, double R12, double R13, } /* ************************************************************************* */ -Rot3::Rot3(const Matrix3& R) { - rot_ = R; -} - -/* ************************************************************************* */ -Rot3::Rot3(const Matrix& R) { - if (R.rows()!=3 || R.cols()!=3) - throw invalid_argument("Rot3 constructor expects 3*3 matrix"); - rot_ = R; -} - -/* ************************************************************************* */ -Rot3::Rot3(const Quaternion& q) : rot_(q.toRotationMatrix()) { +Rot3::Rot3(const gtsam::Quaternion& q) : rot_(q.toRotationMatrix()) { } /* ************************************************************************* */ @@ -117,11 +105,6 @@ Rot3 Rot3::RzRyRx(double x, double y, double z) { ); } -/* ************************************************************************* */ -Rot3 Rot3::rodriguez(const Vector3& w, double theta) { - return SO3::Rodrigues(w,theta); -} - /* ************************************************************************* */ Rot3 Rot3::operator*(const Rot3& R2) const { return Rot3(Matrix3(rot_*R2.rot_)); @@ -136,10 +119,8 @@ Matrix3 Rot3::transpose() const { /* ************************************************************************* */ Point3 Rot3::rotate(const Point3& p, OptionalJacobian<3,3> H1, OptionalJacobian<3,3> H2) const { - if (H1 || H2) { - if (H1) *H1 = rot_ * skewSymmetric(-p.x(), -p.y(), -p.z()); - if (H2) *H2 = rot_; - } + if (H1) *H1 = rot_ * skewSymmetric(-p.x(), -p.y(), -p.z()); + if (H2) *H2 = rot_; return Point3(rot_ * p.vector()); } @@ -210,8 +191,8 @@ Point3 Rot3::r2() const { return Point3(rot_.col(1)); } Point3 Rot3::r3() const { return Point3(rot_.col(2)); } /* ************************************************************************* */ -Quaternion Rot3::toQuaternion() const { - return Quaternion(rot_); +gtsam::Quaternion Rot3::toQuaternion() const { + return gtsam::Quaternion(rot_); } /* ************************************************************************* */ diff --git a/gtsam/geometry/Rot3Q.cpp b/gtsam/geometry/Rot3Q.cpp index 52fb4f262..f8a01141b 100644 --- a/gtsam/geometry/Rot3Q.cpp +++ b/gtsam/geometry/Rot3Q.cpp @@ -27,14 +27,12 @@ using namespace std; namespace gtsam { - static const Matrix I3 = eye(3); - /* ************************************************************************* */ Rot3::Rot3() : quaternion_(Quaternion::Identity()) {} /* ************************************************************************* */ Rot3::Rot3(const Point3& col1, const Point3& col2, const Point3& col3) : - quaternion_((Eigen::Matrix3d() << + quaternion_((Matrix3() << col1.x(), col2.x(), col3.x(), col1.y(), col2.y(), col3.y(), col1.z(), col2.z(), col3.z()).finished()) {} @@ -43,50 +41,38 @@ namespace gtsam { Rot3::Rot3(double R11, double R12, double R13, double R21, double R22, double R23, double R31, double R32, double R33) : - quaternion_((Eigen::Matrix3d() << + quaternion_((Matrix3() << R11, R12, R13, R21, R22, R23, R31, R32, R33).finished()) {} /* ************************************************************************* */ - Rot3::Rot3(const Matrix3& R) : - quaternion_(R) {} - - /* ************************************************************************* */ - Rot3::Rot3(const Matrix& R) : - quaternion_(Matrix3(R)) {} - - /* ************************************************************************* */ - Rot3::Rot3(const Quaternion& q) : + Rot3::Rot3(const gtsam::Quaternion& q) : quaternion_(q) { } /* ************************************************************************* */ Rot3 Rot3::Rx(double t) { - return Quaternion(Eigen::AngleAxisd(t, Eigen::Vector3d::UnitX())); + return gtsam::Quaternion(Eigen::AngleAxisd(t, Eigen::Vector3d::UnitX())); } /* ************************************************************************* */ Rot3 Rot3::Ry(double t) { - return Quaternion(Eigen::AngleAxisd(t, Eigen::Vector3d::UnitY())); + return gtsam::Quaternion(Eigen::AngleAxisd(t, Eigen::Vector3d::UnitY())); } /* ************************************************************************* */ Rot3 Rot3::Rz(double t) { - return Quaternion(Eigen::AngleAxisd(t, Eigen::Vector3d::UnitZ())); + return gtsam::Quaternion(Eigen::AngleAxisd(t, Eigen::Vector3d::UnitZ())); } /* ************************************************************************* */ Rot3 Rot3::RzRyRx(double x, double y, double z) { return Rot3( - Quaternion(Eigen::AngleAxisd(z, Eigen::Vector3d::UnitZ())) * - Quaternion(Eigen::AngleAxisd(y, Eigen::Vector3d::UnitY())) * - Quaternion(Eigen::AngleAxisd(x, Eigen::Vector3d::UnitX()))); + gtsam::Quaternion(Eigen::AngleAxisd(z, Eigen::Vector3d::UnitZ())) * + gtsam::Quaternion(Eigen::AngleAxisd(y, Eigen::Vector3d::UnitY())) * + gtsam::Quaternion(Eigen::AngleAxisd(x, Eigen::Vector3d::UnitX()))); } - /* ************************************************************************* */ - Rot3 Rot3::rodriguez(const Vector3& w, double theta) { - return Quaternion(Eigen::AngleAxis(theta, w)); - } /* ************************************************************************* */ Rot3 Rot3::operator*(const Rot3& R2) const { return Rot3(quaternion_ * R2.quaternion_); @@ -103,16 +89,16 @@ namespace gtsam { /* ************************************************************************* */ Point3 Rot3::rotate(const Point3& p, OptionalJacobian<3,3> H1, OptionalJacobian<3,3> H2) const { - Matrix R = matrix(); + const Matrix3 R = matrix(); if (H1) *H1 = R * skewSymmetric(-p.x(), -p.y(), -p.z()); if (H2) *H2 = R; - Eigen::Vector3d r = R * p.vector(); + const Vector3 r = R * p.vector(); return Point3(r.x(), r.y(), r.z()); } /* ************************************************************************* */ Vector3 Rot3::Logmap(const Rot3& R, OptionalJacobian<3, 3> H) { - return traits::Logmap(R.quaternion_, H); + return traits::Logmap(R.quaternion_, H); } /* ************************************************************************* */ @@ -142,7 +128,7 @@ namespace gtsam { Point3 Rot3::r3() const { return Point3(quaternion_.toRotationMatrix().col(2)); } /* ************************************************************************* */ - Quaternion Rot3::toQuaternion() const { return quaternion_; } + gtsam::Quaternion Rot3::toQuaternion() const { return quaternion_; } /* ************************************************************************* */ diff --git a/gtsam/geometry/SO3.cpp b/gtsam/geometry/SO3.cpp index 7e755d680..459f15561 100644 --- a/gtsam/geometry/SO3.cpp +++ b/gtsam/geometry/SO3.cpp @@ -11,58 +11,125 @@ /** * @file SO3.cpp - * @brief 3*3 matrix representation o SO(3) + * @brief 3*3 matrix representation of SO(3) * @author Frank Dellaert + * @author Luca Carlone + * @author Duy Nguyen Ta * @date December 2014 */ #include #include #include - -using namespace std; +#include namespace gtsam { -/* ************************************************************************* */ -SO3 SO3::Rodrigues(const Vector3& axis, double theta) { - using std::cos; - using std::sin; +namespace so3 { - // get components of axis \omega - double wx = axis(0), wy = axis(1), wz = axis(2); - - double c = cos(theta), s = sin(theta), c_1 = 1 - c; - double wwTxx = wx * wx, wwTyy = wy * wy, wwTzz = wz * wz; - double swx = wx * s, swy = wy * s, swz = wz * s; - - double C00 = c_1 * wwTxx, C01 = c_1 * wx * wy, C02 = c_1 * wx * wz; - double C11 = c_1 * wwTyy, C12 = c_1 * wy * wz; - double C22 = c_1 * wwTzz; - - Matrix3 R; - R << c + C00, -swz + C01, swy + C02, // - swz + C01, c + C11, -swx + C12, // - -swy + C02, swx + C12, c + C22; - - return R; +void ExpmapFunctor::init(bool nearZeroApprox) { + nearZero = nearZeroApprox || (theta2 <= std::numeric_limits::epsilon()); + if (nearZero) return; + theta = std::sqrt(theta2); // rotation angle + sin_theta = std::sin(theta); + const double s2 = std::sin(theta / 2.0); + one_minus_cos = 2.0 * s2 * s2; // numerically better than [1 - cos(theta)] } -/// simply convert omega to axis/angle representation -SO3 SO3::Expmap(const Vector3& omega, - ChartJacobian H) { - - if (H) - *H = ExpmapDerivative(omega); - - if (omega.isZero()) - return Identity(); - else { - double angle = omega.norm(); - return Rodrigues(omega / angle, angle); +ExpmapFunctor::ExpmapFunctor(const Vector3& omega, bool nearZeroApprox) + : theta2(omega.dot(omega)) { + const double wx = omega.x(), wy = omega.y(), wz = omega.z(); + W << 0.0, -wz, +wy, +wz, 0.0, -wx, -wy, +wx, 0.0; + init(nearZeroApprox); + if (!nearZero) { + theta = std::sqrt(theta2); + K = W / theta; + KK = K * K; } } +ExpmapFunctor::ExpmapFunctor(const Vector3& axis, double angle, bool nearZeroApprox) + : theta2(angle * angle) { + const double ax = axis.x(), ay = axis.y(), az = axis.z(); + K << 0.0, -az, +ay, +az, 0.0, -ax, -ay, +ax, 0.0; + W = K * angle; + init(nearZeroApprox); + if (!nearZero) { + theta = angle; + KK = K * K; + } +} + +SO3 ExpmapFunctor::expmap() const { + if (nearZero) + return I_3x3 + W; + else + return I_3x3 + sin_theta * K + one_minus_cos * KK; +} + +DexpFunctor::DexpFunctor(const Vector3& omega, bool nearZeroApprox) + : ExpmapFunctor(omega, nearZeroApprox), omega(omega) { + if (nearZero) + dexp_ = I_3x3 - 0.5 * W; + else { + a = one_minus_cos / theta; + b = 1.0 - sin_theta / theta; + dexp_ = I_3x3 - a * K + b * KK; + } +} + +Vector3 DexpFunctor::applyDexp(const Vector3& v, OptionalJacobian<3, 3> H1, + OptionalJacobian<3, 3> H2) const { + if (H1) { + if (nearZero) { + *H1 = 0.5 * skewSymmetric(v); + } else { + // TODO(frank): Iserles hints that there should be a form I + c*K + d*KK + const Vector3 Kv = K * v; + const double Da = (sin_theta - 2.0 * a) / theta2; + const double Db = (one_minus_cos - 3.0 * b) / theta2; + *H1 = (Db * K - Da * I_3x3) * Kv * omega.transpose() - + skewSymmetric(Kv * b / theta) + + (a * I_3x3 - b * K) * skewSymmetric(v / theta); + } + } + if (H2) *H2 = dexp_; + return dexp_ * v; +} + +Vector3 DexpFunctor::applyInvDexp(const Vector3& v, OptionalJacobian<3, 3> H1, + OptionalJacobian<3, 3> H2) const { + const Matrix3 invDexp = dexp_.inverse(); + const Vector3 c = invDexp * v; + if (H1) { + Matrix3 D_dexpv_omega; + applyDexp(c, D_dexpv_omega); // get derivative H of forward mapping + *H1 = -invDexp* D_dexpv_omega; + } + if (H2) *H2 = invDexp; + return c; +} + +} // namespace so3 + +/* ************************************************************************* */ +SO3 SO3::AxisAngle(const Vector3& axis, double theta) { + return so3::ExpmapFunctor(axis, theta).expmap(); +} + +SO3 SO3::Expmap(const Vector3& omega, ChartJacobian H) { + if (H) { + so3::DexpFunctor impl(omega); + *H = impl.dexp(); + return impl.expmap(); + } else + return so3::ExpmapFunctor(omega).expmap(); +} + +Matrix3 SO3::ExpmapDerivative(const Vector3& omega) { + return so3::DexpFunctor(omega).dexp(); +} + /* ************************************************************************* */ Vector3 SO3::Logmap(const SO3& R, ChartJacobian H) { using std::sqrt; @@ -74,7 +141,7 @@ Vector3 SO3::Logmap(const SO3& R, ChartJacobian H) { const double& R31 = R(2, 0), R32 = R(2, 1), R33 = R(2, 2); // Get trace(R) - double tr = R.trace(); + const double tr = R.trace(); Vector3 omega; @@ -90,7 +157,7 @@ Vector3 SO3::Logmap(const SO3& R, ChartJacobian H) { omega = (M_PI / sqrt(2.0 + 2.0 * R11)) * Vector3(1.0 + R11, R21, R31); } else { double magnitude; - double tr_3 = tr - 3.0; // always negative + const double tr_3 = tr - 3.0; // always negative if (tr_3 < -1e-7) { double theta = acos((tr - 1.0) / 2.0); magnitude = theta / (2.0 * sin(theta)); @@ -107,51 +174,13 @@ Vector3 SO3::Logmap(const SO3& R, ChartJacobian H) { } /* ************************************************************************* */ -Matrix3 SO3::ExpmapDerivative(const Vector3& omega) { +Matrix3 SO3::LogmapDerivative(const Vector3& omega) { using std::cos; using std::sin; - if(zero(omega)) return I_3x3; - double theta = omega.norm(); // rotation angle -#ifdef DUY_VERSION - /// Follow Iserles05an, B10, pg 147, with a sign change in the second term (left version) - Matrix3 X = skewSymmetric(omega); - Matrix3 X2 = X*X; - double vi = theta/2.0; - double s1 = sin(vi)/vi; - double s2 = (theta - sin(theta))/(theta*theta*theta); - return I_3x3 - 0.5*s1*s1*X + s2*X2; -#else // Luca's version - /** - * Right Jacobian for Exponential map in SO(3) - equation (10.86) and following equations in - * G.S. Chirikjian, "Stochastic Models, Information Theory, and Lie Groups", Volume 2, 2008. - * expmap(thetahat + omega) \approx expmap(thetahat) * expmap(Jr * omega) - * where Jr = ExpmapDerivative(thetahat); - * This maps a perturbation in the tangent space (omega) to - * a perturbation on the manifold (expmap(Jr * omega)) - */ - // element of Lie algebra so(3): X = omega^, normalized by normx - const Matrix3 Y = skewSymmetric(omega) / theta; - return I_3x3 - ((1 - cos(theta)) / (theta)) * Y - + (1 - sin(theta) / theta) * Y * Y; // right Jacobian -#endif -} - -/* ************************************************************************* */ -Matrix3 SO3::LogmapDerivative(const Vector3& omega) { - using std::cos; - using std::sin; - - if(zero(omega)) return I_3x3; - double theta = omega.norm(); -#ifdef DUY_VERSION - /// Follow Iserles05an, B11, pg 147, with a sign change in the second term (left version) - Matrix3 X = skewSymmetric(omega); - Matrix3 X2 = X*X; - double vi = theta/2.0; - double s2 = (theta*tan(M_PI_2-vi) - 2)/(2*theta*theta); - return I_3x3 + 0.5*X - s2*X2; -#else // Luca's version + double theta2 = omega.dot(omega); + if (theta2 <= std::numeric_limits::epsilon()) return I_3x3; + double theta = std::sqrt(theta2); // rotation angle /** Right Jacobian for Log map in SO(3) - equation (10.86) and following equations in * G.S. Chirikjian, "Stochastic Models, Information Theory, and Lie Groups", Volume 2, 2008. * logmap( Rhat * expmap(omega) ) \approx logmap( Rhat ) + Jrinv * omega @@ -159,11 +188,10 @@ Matrix3 SO3::LogmapDerivative(const Vector3& omega) { * This maps a perturbation on the manifold (expmap(omega)) * to a perturbation in the tangent space (Jrinv * omega) */ - const Matrix3 X = skewSymmetric(omega); // element of Lie algebra so(3): X = omega^ - return I_3x3 + 0.5 * X - + (1 / (theta * theta) - (1 + cos(theta)) / (2 * theta * sin(theta))) * X - * X; -#endif + const Matrix3 W = skewSymmetric(omega); // element of Lie algebra so(3): W = omega^ + return I_3x3 + 0.5 * W + + (1 / (theta * theta) - (1 + cos(theta)) / (2 * theta * sin(theta))) * + W * W; } /* ************************************************************************* */ diff --git a/gtsam/geometry/SO3.h b/gtsam/geometry/SO3.h index a08168ed8..3152fa2fb 100644 --- a/gtsam/geometry/SO3.h +++ b/gtsam/geometry/SO3.h @@ -13,6 +13,8 @@ * @file SO3.h * @brief 3*3 matrix representation of SO(3) * @author Frank Dellaert + * @author Luca Carlone + * @author Duy Nguyen Ta * @date December 2014 */ @@ -59,7 +61,7 @@ public: } /// Static, named constructor TODO think about relation with above - static SO3 Rodrigues(const Vector3& axis, double theta); + static SO3 AxisAngle(const Vector3& axis, double theta); /// @} /// @name Testable @@ -93,19 +95,19 @@ public: /** * Exponential map at identity - create a rotation from canonical coordinates - * \f$ [R_x,R_y,R_z] \f$ using Rodriguez' formula + * \f$ [R_x,R_y,R_z] \f$ using Rodrigues' formula */ static SO3 Expmap(const Vector3& omega, ChartJacobian H = boost::none); + /// Derivative of Expmap + static Matrix3 ExpmapDerivative(const Vector3& omega); + /** * Log map at identity - returns the canonical coordinates * \f$ [R_x,R_y,R_z] \f$ of this rotation */ static Vector3 Logmap(const SO3& R, ChartJacobian H = boost::none); - /// Derivative of Expmap - static Matrix3 ExpmapDerivative(const Vector3& omega); - /// Derivative of Logmap static Matrix3 LogmapDerivative(const Vector3& omega); @@ -128,6 +130,61 @@ public: /// @} }; +// This namespace exposes two functors that allow for saving computation when +// exponential map and its derivatives are needed at the same location in so<3> +// The second functor also implements dedicated methods to apply dexp and/or inv(dexp) +namespace so3 { + +/// Functor implementing Exponential map +class ExpmapFunctor { + protected: + const double theta2; + Matrix3 W, K, KK; + bool nearZero; + double theta, sin_theta, one_minus_cos; // only defined if !nearZero + + void init(bool nearZeroApprox = false); + + public: + /// Constructor with element of Lie algebra so(3) + ExpmapFunctor(const Vector3& omega, bool nearZeroApprox = false); + + /// Constructor with axis-angle + ExpmapFunctor(const Vector3& axis, double angle, bool nearZeroApprox = false); + + /// Rodrigues formula + SO3 expmap() const; +}; + +/// Functor that implements Exponential map *and* its derivatives +class DexpFunctor : public ExpmapFunctor { + const Vector3 omega; + double a, b; + Matrix3 dexp_; + + public: + /// Constructor with element of Lie algebra so(3) + DexpFunctor(const Vector3& omega, bool nearZeroApprox = false); + + // NOTE(luca): Right Jacobian for Exponential map in SO(3) - equation + // (10.86) and following equations in G.S. Chirikjian, "Stochastic Models, + // Information Theory, and Lie Groups", Volume 2, 2008. + // expmap(omega + v) \approx expmap(omega) * expmap(dexp * v) + // This maps a perturbation v in the tangent space to + // a perturbation on the manifold Expmap(dexp * v) */ + const Matrix3& dexp() const { return dexp_; } + + /// Multiplies with dexp(), with optional derivatives + Vector3 applyDexp(const Vector3& v, OptionalJacobian<3, 3> H1 = boost::none, + OptionalJacobian<3, 3> H2 = boost::none) const; + + /// Multiplies with dexp().inverse(), with optional derivatives + Vector3 applyInvDexp(const Vector3& v, + OptionalJacobian<3, 3> H1 = boost::none, + OptionalJacobian<3, 3> H2 = boost::none) const; +}; +} // namespace so3 + template<> struct traits : public internal::LieGroup { }; diff --git a/gtsam/geometry/SimpleCamera.h b/gtsam/geometry/SimpleCamera.h index a119096d4..fe493c075 100644 --- a/gtsam/geometry/SimpleCamera.h +++ b/gtsam/geometry/SimpleCamera.h @@ -18,6 +18,7 @@ #pragma once +#include #include #include @@ -125,14 +126,18 @@ public: }; -template<> -struct traits : public internal::Manifold { -}; +/// Recover camera from 3*4 camera matrix +GTSAM_EXPORT SimpleCamera simpleCamera(const Matrix34& P); -template<> -struct traits : public internal::Manifold { -}; +// manifold traits +template <> +struct traits : public internal::Manifold {}; - /// Recover camera from 3*4 camera matrix - GTSAM_EXPORT SimpleCamera simpleCamera(const Matrix34& P); -} +template <> +struct traits : public internal::Manifold {}; + +// range traits, used in RangeFactor +template +struct Range : HasRange {}; + +} // namespace gtsam diff --git a/gtsam/geometry/StereoCamera.h b/gtsam/geometry/StereoCamera.h index f09626c9d..ac32be7ae 100644 --- a/gtsam/geometry/StereoCamera.h +++ b/gtsam/geometry/StereoCamera.h @@ -66,8 +66,8 @@ public: StereoCamera(const Pose3& leftCamPose, const Cal3_S2Stereo::shared_ptr K); /// Return shared pointer to calibration - const Cal3_S2Stereo::shared_ptr calibration() const { - return K_; + const Cal3_S2Stereo& calibration() const { + return *K_; } /// @} diff --git a/gtsam/geometry/Unit3.cpp b/gtsam/geometry/Unit3.cpp index cc3865b8e..aaf0aa953 100644 --- a/gtsam/geometry/Unit3.cpp +++ b/gtsam/geometry/Unit3.cpp @@ -15,12 +15,13 @@ * @author Can Erdogan * @author Frank Dellaert * @author Alex Trevor + * @author Zhaoyang Lv * @brief The Unit3 class - basically a point on a unit sphere */ #include #include -#include +#include // for GTSAM_USE_TBB #ifdef __clang__ # pragma clang diagnostic push @@ -31,12 +32,9 @@ # pragma clang diagnostic pop #endif -#ifdef GTSAM_USE_TBB -#include -#endif - #include #include +#include using namespace std; @@ -44,14 +42,13 @@ namespace gtsam { /* ************************************************************************* */ Unit3 Unit3::FromPoint3(const Point3& point, OptionalJacobian<2,3> H) { - Unit3 direction(point); - if (H) { - // 3*3 Derivative of representation with respect to point is 3*3: - Matrix3 D_p_point; - point.normalize(D_p_point); // TODO, this calculates norm a second time :-( - // Calculate the 2*3 Jacobian + // 3*3 Derivative of representation with respect to point is 3*3: + Matrix3 D_p_point; + Point3 normalized = point.normalize(H ? &D_p_point : 0); + Unit3 direction; + direction.p_ = normalized.vector(); + if (H) *H << direction.basis().transpose() * D_p_point; - } return direction; } @@ -61,54 +58,103 @@ Unit3 Unit3::Random(boost::mt19937 & rng) { boost::uniform_on_sphere randomDirection(3); // This variate_generator object is required for versions of boost somewhere // around 1.46, instead of drawing directly using boost::uniform_on_sphere(rng). - boost::variate_generator > - generator(rng, randomDirection); + boost::variate_generator > generator( + rng, randomDirection); vector d = generator(); - Unit3 result; - result.p_ = Point3(d[0], d[1], d[2]); - return result; + return Unit3(d[0], d[1], d[2]); } -#ifdef GTSAM_USE_TBB -tbb::mutex unit3BasisMutex; -#endif - /* ************************************************************************* */ -const Matrix32& Unit3::basis() const { +const Matrix32& Unit3::basis(OptionalJacobian<6, 2> H) const { #ifdef GTSAM_USE_TBB - tbb::mutex::scoped_lock lock(unit3BasisMutex); + // NOTE(hayk): At some point it seemed like this reproducably resulted in deadlock. However, I + // can't see the reason why and I can no longer reproduce it. It may have been a red herring, or + // there is still a latent bug to watch out for. + tbb::mutex::scoped_lock lock(B_mutex_); #endif - // Return cached version if exists - if (B_) + // Return cached basis if available and the Jacobian isn't needed. + if (B_ && !H) { return *B_; + } + + // Return cached basis and derivatives if available. + if (B_ && H && H_B_) { + *H = *H_B_; + return *B_; + } + + // Get the unit vector and derivative wrt this. + // NOTE(hayk): We can't call point3(), because it would recursively call basis(). + const Point3 n(p_); // Get the axis of rotation with the minimum projected length of the point Point3 axis; - double mx = fabs(p_.x()), my = fabs(p_.y()), mz = fabs(p_.z()); - if ((mx <= my) && (mx <= mz)) + double mx = fabs(n.x()), my = fabs(n.y()), mz = fabs(n.z()); + if ((mx <= my) && (mx <= mz)) { axis = Point3(1.0, 0.0, 0.0); - else if ((my <= mx) && (my <= mz)) + } else if ((my <= mx) && (my <= mz)) { axis = Point3(0.0, 1.0, 0.0); - else if ((mz <= mx) && (mz <= my)) + } else if ((mz <= mx) && (mz <= my)) { axis = Point3(0.0, 0.0, 1.0); - else + } else { assert(false); + } - // Create the two basis vectors - Point3 b1 = p_.cross(axis); - b1 = b1 / b1.norm(); - Point3 b2 = p_.cross(b1); - b2 = b2 / b2.norm(); + // Choose the direction of the first basis vector b1 in the tangent plane by crossing n with + // the chosen axis. + Matrix33 H_B1_n; + Point3 B1 = n.cross(axis, H ? &H_B1_n : 0); - // Create the basis matrix + // Normalize result to get a unit vector: b1 = B1 / |B1|. + Matrix33 H_b1_B1; + Point3 b1 = B1.normalize(H ? &H_b1_B1 : 0); + + // Get the second basis vector b2, which is orthogonal to n and b1, by crossing them. + // No need to normalize this, p and b1 are orthogonal unit vectors. + Matrix33 H_b2_n, H_b2_b1; + Point3 b2 = n.cross(b1, H ? &H_b2_n : 0, H ? &H_b2_b1 : 0); + + // Create the basis by stacking b1 and b2. B_.reset(Matrix32()); (*B_) << b1.x(), b2.x(), b1.y(), b2.y(), b1.z(), b2.z(); + + if (H) { + // Chain rule tomfoolery to compute the derivative. + const Matrix32& H_n_p = *B_; + Matrix32 H_b1_p = H_b1_B1 * H_B1_n * H_n_p; + Matrix32 H_b2_p = H_b2_n * H_n_p + H_b2_b1 * H_b1_p; + + // Cache the derivative and fill the result. + H_B_.reset(Matrix62()); + (*H_B_) << H_b1_p, H_b2_p; + *H = *H_B_; + } + return *B_; } /* ************************************************************************* */ -/// The print fuction +Point3 Unit3::point3(OptionalJacobian<3, 2> H) const { + if (H) + *H = basis(); + return Point3(p_); +} + +/* ************************************************************************* */ +Vector3 Unit3::unitVector(OptionalJacobian<3, 2> H) const { + if (H) + *H = basis(); + return p_; +} + +/* ************************************************************************* */ +std::ostream& operator<<(std::ostream& os, const Unit3& pair) { + os << pair.p_ << endl; + return os; +} + +/* ************************************************************************* */ void Unit3::print(const std::string& s) const { cout << s << ":" << p_ << endl; } @@ -119,12 +165,72 @@ Matrix3 Unit3::skew() const { } /* ************************************************************************* */ -Vector2 Unit3::error(const Unit3& q, OptionalJacobian<2,2> H) const { +double Unit3::dot(const Unit3& q, OptionalJacobian<1,2> H_p, OptionalJacobian<1,2> H_q) const { + // Get the unit vectors of each, and the derivative. + Matrix32 H_pn_p; + Point3 pn = point3(H_p ? &H_pn_p : 0); + + Matrix32 H_qn_q; + Point3 qn = q.point3(H_q ? &H_qn_q : 0); + + // Compute the dot product of the Point3s. + Matrix13 H_dot_pn, H_dot_qn; + double d = pn.dot(qn, H_p ? &H_dot_pn : 0, H_q ? &H_dot_qn : 0); + + if (H_p) { + (*H_p) << H_dot_pn * H_pn_p; + } + + if (H_q) { + (*H_q) = H_dot_qn * H_qn_q; + } + + return d; +} + +/* ************************************************************************* */ +Vector2 Unit3::error(const Unit3& q, OptionalJacobian<2,2> H_q) const { // 2D error is equal to B'*q, as B is 3x2 matrix and q is 3x1 Matrix23 Bt = basis().transpose(); - Vector2 xi = Bt * q.p_.vector(); - if (H) - *H = Bt * q.basis(); + Vector2 xi = Bt * q.p_; + if (H_q) { + *H_q = Bt * q.basis(); + } + return xi; +} + +/* ************************************************************************* */ +Vector2 Unit3::errorVector(const Unit3& q, OptionalJacobian<2, 2> H_p, OptionalJacobian<2, 2> H_q) const { + // Get the point3 of this, and the derivative. + Matrix32 H_qn_q; + Point3 qn = q.point3(H_q ? &H_qn_q : 0); + + // 2D error here is projecting q into the tangent plane of this (p). + Matrix62 H_B_p; + Matrix23 Bt = basis(H_p ? &H_B_p : 0).transpose(); + Vector2 xi = Bt * qn.vector(); + + if (H_p) { + // Derivatives of each basis vector. + const Matrix32& H_b1_p = H_B_p.block<3, 2>(0, 0); + const Matrix32& H_b2_p = H_B_p.block<3, 2>(3, 0); + + // Derivatives of the two entries of xi wrt the basis vectors. + Matrix13 H_xi1_b1 = qn.vector().transpose(); + Matrix13 H_xi2_b2 = qn.vector().transpose(); + + // Assemble dxi/dp = dxi/dB * dB/dp. + Matrix12 H_xi1_p = H_xi1_b1 * H_b1_p; + Matrix12 H_xi2_p = H_xi2_b2 * H_b2_p; + *H_p << H_xi1_p, H_xi2_p; + } + + if (H_q) { + // dxi/dq is given by dxi/dqu * dqu/dq, where qu is the unit vector of q. + Matrix23 H_xi_qu = Bt; + *H_q = H_xi_qu * H_qn_q; + } + return xi; } @@ -140,47 +246,39 @@ double Unit3::distance(const Unit3& q, OptionalJacobian<1,2> H) const { /* ************************************************************************* */ Unit3 Unit3::retract(const Vector2& v) const { - - // Get the vector form of the point and the basis matrix - Vector3 p = p_.vector(); - Matrix32 B = basis(); - // Compute the 3D xi_hat vector - Vector3 xi_hat = v(0) * B.col(0) + v(1) * B.col(1); + Vector3 xi_hat = basis() * v; + double theta = xi_hat.norm(); - double xi_hat_norm = xi_hat.norm(); - - // Avoid nan - if (xi_hat_norm == 0.0) { - if (v.norm() == 0.0) - return Unit3(point3()); - else - return Unit3(-point3()); + // Treat case of very small v differently + if (theta < std::numeric_limits::epsilon()) { + return Unit3(cos(theta) * p_ + xi_hat); } - Vector3 exp_p_xi_hat = cos(xi_hat_norm) * p - + sin(xi_hat_norm) * (xi_hat / xi_hat_norm); + Vector3 exp_p_xi_hat = + cos(theta) * p_ + xi_hat * (sin(theta) / theta); return Unit3(exp_p_xi_hat); - } /* ************************************************************************* */ -Vector2 Unit3::localCoordinates(const Unit3& y) const { - - Vector3 p = p_.vector(), q = y.p_.vector(); - double dot = p.dot(q); - - // Check for special cases - if (std::abs(dot - 1.0) < 1e-16) - return Vector2(0, 0); - else if (std::abs(dot + 1.0) < 1e-16) - return Vector2(M_PI, 0); - else { +Vector2 Unit3::localCoordinates(const Unit3& other) const { + const double x = p_.dot(other.p_); + // Crucial quantity here is y = theta/sin(theta) with theta=acos(x) + // Now, y = acos(x) / sin(acos(x)) = acos(x)/sqrt(1-x^2) + // We treat the special case 1 and -1 below + const double x2 = x * x; + const double z = 1 - x2; + double y; + if (z < std::numeric_limits::epsilon()) { + if (x > 0) // first order expansion at x=1 + y = 1.0 - (x - 1.0) / 3.0; + else // cop out + return Vector2(M_PI, 0.0); + } else { // no special case - double theta = acos(dot); - Vector3 result_hat = (theta / sin(theta)) * (q - p * dot); - return basis().transpose() * result_hat; + y = acos(x) / sqrt(z); } + return basis().transpose() * y * (other.p_ - x * p_); } /* ************************************************************************* */ diff --git a/gtsam/geometry/Unit3.h b/gtsam/geometry/Unit3.h index 12bfac5ce..428211c6b 100644 --- a/gtsam/geometry/Unit3.h +++ b/gtsam/geometry/Unit3.h @@ -20,11 +20,21 @@ #pragma once -#include +#include #include -#include -#include +#include +#include +#include + #include +#include +#include + +#include + +#ifdef GTSAM_USE_TBB +#include +#endif namespace gtsam { @@ -33,8 +43,13 @@ class GTSAM_EXPORT Unit3 { private: - Point3 p_; ///< The location of the point on the unit sphere + Vector3 p_; ///< The location of the point on the unit sphere mutable boost::optional B_; ///< Cached basis + mutable boost::optional H_B_; ///< Cached basis derivative + +#ifdef GTSAM_USE_TBB + mutable tbb::mutex B_mutex_; ///< Mutex to protect the cached basis. +#endif public: @@ -52,18 +67,35 @@ public: /// Construct from point explicit Unit3(const Point3& p) : - p_(p / p.norm()) { + p_(p.vector().normalized()) { } /// Construct from a vector3 explicit Unit3(const Vector3& p) : - p_(p / p.norm()) { + p_(p.normalized()) { } /// Construct from x,y,z Unit3(double x, double y, double z) : p_(x, y, z) { - p_ = p_ / p_.norm(); + p_.normalize(); + } + + /// Construct from 2D point in plane at focal length f + /// Unit3(p,1) can be viewed as normalized homogeneous coordinates of 2D point + explicit Unit3(const Point2& p, double f = 1.0) : p_(p.x(), p.y(), f) { + p_.normalize(); + } + + /// Copy constructor + Unit3(const Unit3& u) { + p_ = u.p_; + } + + /// Copy assignment + Unit3& operator=(const Unit3 & u) { + p_ = u.p_; + return *this; } /// Named constructor from Point3 with optional Jacobian @@ -78,12 +110,14 @@ public: /// @name Testable /// @{ + friend std::ostream& operator<<(std::ostream& os, const Unit3& pair); + /// The print fuction void print(const std::string& s = std::string()) const; /// The equals function with tolerance bool equals(const Unit3& s, double tol = 1e-9) const { - return p_.equals(s.p_, tol); + return equal_with_abs_tol(p_, s.p_, tol); } /// @} @@ -94,37 +128,50 @@ public: * Returns the local coordinate frame to tangent plane * It is a 3*2 matrix [b1 b2] composed of two orthogonal directions * tangent to the sphere at the current direction. + * Provides derivatives of the basis with the two basis vectors stacked up as a 6x1. */ - const Matrix32& basis() const; + const Matrix32& basis(OptionalJacobian<6, 2> H = boost::none) const; /// Return skew-symmetric associated with 3D point on unit sphere Matrix3 skew() const; /// Return unit-norm Point3 - const Point3& point3(OptionalJacobian<3, 2> H = boost::none) const { - if (H) - *H = basis(); - return p_; - } + Point3 point3(OptionalJacobian<3, 2> H = boost::none) const; /// Return unit-norm Vector - Vector3 unitVector(boost::optional H = boost::none) const { - if (H) - *H = basis(); - return (p_.vector()); - } + Vector3 unitVector(OptionalJacobian<3, 2> H = boost::none) const; /// Return scaled direction as Point3 friend Point3 operator*(double s, const Unit3& d) { - return s * d.p_; + return Point3(s * d.p_); } + /// Return dot product with q + double dot(const Unit3& q, OptionalJacobian<1,2> H1 = boost::none, // + OptionalJacobian<1,2> H2 = boost::none) const; + /// Signed, vector-valued error between two directions - Vector2 error(const Unit3& q, OptionalJacobian<2, 2> H = boost::none) const; + /// @deprecated, errorVector has the proper derivatives, this confusingly has only the second. + Vector2 error(const Unit3& q, OptionalJacobian<2, 2> H_q = boost::none) const; + + /// Signed, vector-valued error between two directions + /// NOTE(hayk): This method has zero derivatives if this (p) and q are orthogonal. + Vector2 errorVector(const Unit3& q, OptionalJacobian<2, 2> H_p = boost::none, // + OptionalJacobian<2, 2> H_q = boost::none) const; /// Distance between two directions double distance(const Unit3& q, OptionalJacobian<1, 2> H = boost::none) const; + /// Cross-product between two Unit3s + Unit3 cross(const Unit3& q) const { + return Unit3(p_.cross(q.p_)); + } + + /// Cross-product w Point3 + Point3 cross(const Point3& q) const { + return point3().cross(q); + } + /// @} /// @name Manifold @@ -142,7 +189,7 @@ public: enum CoordinatesMode { EXPMAP, ///< Use the exponential map to retract - RENORM ///< Retract with vector addtion and renormalize. + RENORM ///< Retract with vector addition and renormalize. }; /// The retract function @@ -162,13 +209,6 @@ private: template void serialize(ARCHIVE & ar, const unsigned int /*version*/) { ar & BOOST_SERIALIZATION_NVP(p_); - // homebrew serialize Eigen Matrix - ar & boost::serialization::make_nvp("B11", (*B_)(0, 0)); - ar & boost::serialization::make_nvp("B12", (*B_)(0, 1)); - ar & boost::serialization::make_nvp("B21", (*B_)(1, 0)); - ar & boost::serialization::make_nvp("B22", (*B_)(1, 1)); - ar & boost::serialization::make_nvp("B31", (*B_)(2, 0)); - ar & boost::serialization::make_nvp("B32", (*B_)(2, 1)); } /// @} diff --git a/gtsam/geometry/concepts.h b/gtsam/geometry/concepts.h index 621f04592..207b48f56 100644 --- a/gtsam/geometry/concepts.h +++ b/gtsam/geometry/concepts.h @@ -59,24 +59,6 @@ private: } }; -/** - * Range measurement concept - * Given a pair of Lie variables, there must exist a function to calculate - * range with derivatives. - */ -template -class RangeMeasurementConcept { -private: - static double checkRangeMeasurement(const V1& x, const V2& p) { - return x.range(p); - } - - static double checkRangeMeasurementDerivatives(const V1& x, const V2& p) { - boost::optional H1, H2; - return x.range(p, H1, H2); - } -}; - } // \namespace gtsam /** @@ -92,7 +74,3 @@ private: #define GTSAM_CONCEPT_POSE_INST(T) template class gtsam::PoseConcept; #define GTSAM_CONCEPT_POSE_TYPE(T) typedef gtsam::PoseConcept _gtsam_PoseConcept##T; -/** Range Measurement macros */ -#define GTSAM_CONCEPT_RANGE_MEASUREMENT_INST(V1,V2) template class gtsam::RangeMeasurementConcept; -#define GTSAM_CONCEPT_RANGE_MEASUREMENT_TYPE(V1,V2) typedef gtsam::RangeMeasurementConcept _gtsam_RangeMeasurementConcept##V1##V2; - diff --git a/gtsam/geometry/tests/testBearingRange.cpp b/gtsam/geometry/tests/testBearingRange.cpp new file mode 100644 index 000000000..8c5d2208e --- /dev/null +++ b/gtsam/geometry/tests/testBearingRange.cpp @@ -0,0 +1,79 @@ +/* ---------------------------------------------------------------------------- + + * 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 testBearingRange.cpp + * @brief Unit tests for BearingRange Class + * @author Frank Dellaert + * @date July 2015 + */ + +#include +#include +#include +#include + +#include + +using namespace std; +using namespace gtsam; +using namespace serializationTestHelpers; + +typedef BearingRange BearingRange2D; +BearingRange2D br2D(1, 2); + +typedef BearingRange BearingRange3D; +BearingRange3D br3D(Pose3().bearing(Point3(1, 0, 0)), 1); + +//****************************************************************************** +TEST(BearingRange2D, Concept) { + BOOST_CONCEPT_ASSERT((IsManifold)); +} + +/* ************************************************************************* */ +TEST(BearingRange, 2D) { + BearingRange2D expected(0, 1); + BearingRange2D actual = BearingRange2D::Measure(Pose2(), Point2(1, 0)); + EXPECT(assert_equal(expected, actual)); +} + +/* ************************************************************************* */ +TEST(BearingRange, Serialization2D) { + EXPECT(equalsObj(br2D)); + EXPECT(equalsXML(br2D)); + EXPECT(equalsBinary(br2D)); +} + +//****************************************************************************** +TEST(BearingRange3D, Concept) { + BOOST_CONCEPT_ASSERT((IsManifold)); +} + +/* ************************************************************************* */ +TEST(BearingRange, 3D) { + BearingRange3D expected(Unit3(), 1); + BearingRange3D actual = BearingRange3D::Measure(Pose3(), Point3(1, 0, 0)); + EXPECT(assert_equal(expected, actual)); +} + +/* ************************************************************************* */ +TEST(BearingRange, Serialization3D) { + EXPECT(equalsObj(br3D)); + EXPECT(equalsXML(br3D)); + EXPECT(equalsBinary(br3D)); +} + +/* ************************************************************************* */ +int main() { + TestResult tr; + return TestRegistry::runAllTests(tr); +} +/* ************************************************************************* */ diff --git a/gtsam/geometry/tests/testCal3_S2.cpp b/gtsam/geometry/tests/testCal3_S2.cpp index aa06a2e29..3e93dedc1 100644 --- a/gtsam/geometry/tests/testCal3_S2.cpp +++ b/gtsam/geometry/tests/testCal3_S2.cpp @@ -26,6 +26,8 @@ GTSAM_CONCEPT_MANIFOLD_INST(Cal3_S2) static Cal3_S2 K(500, 500, 0.1, 640 / 2, 480 / 2); static Point2 p(1, -2); +static Point2 p_uv(1320.3, 1740); +static Point2 p_xy(2, 3); /* ************************************************************************* */ TEST( Cal3_S2, easy_constructor) @@ -73,6 +75,27 @@ TEST( Cal3_S2, Duncalibrate2) CHECK(assert_equal(numerical,computed,1e-9)); } +Point2 calibrate_(const Cal3_S2& k, const Point2& pt) {return k.calibrate(pt); } +/* ************************************************************************* */ +TEST(Cal3_S2, Dcalibrate1) +{ + Matrix computed; + Point2 expected = K.calibrate(p_uv, computed, boost::none); + Matrix numerical = numericalDerivative21(calibrate_, K, p_uv); + CHECK(assert_equal(expected, p_xy, 1e-8)); + CHECK(assert_equal(numerical, computed, 1e-8)); +} + +/* ************************************************************************* */ +TEST(Cal3_S2, Dcalibrate2) +{ + Matrix computed; + Point2 expected = K.calibrate(p_uv, boost::none, computed); + Matrix numerical = numericalDerivative22(calibrate_, K, p_uv); + CHECK(assert_equal(expected, p_xy, 1e-8)); + CHECK(assert_equal(numerical, computed, 1e-8)); +} + /* ************************************************************************* */ TEST( Cal3_S2, assert_equal) { diff --git a/gtsam/geometry/tests/testCalibratedCamera.cpp b/gtsam/geometry/tests/testCalibratedCamera.cpp index c02a11928..5bc645a58 100644 --- a/gtsam/geometry/tests/testCalibratedCamera.cpp +++ b/gtsam/geometry/tests/testCalibratedCamera.cpp @@ -30,7 +30,7 @@ using namespace gtsam; GTSAM_CONCEPT_MANIFOLD_INST(CalibratedCamera) // Camera situated at 0.5 meters high, looking down -static const Pose3 pose1((Matrix)(Matrix(3,3) << +static const Pose3 pose1((Matrix3() << 1., 0., 0., 0.,-1., 0., 0., 0.,-1. @@ -88,13 +88,30 @@ TEST( CalibratedCamera, project) } /* ************************************************************************* */ -TEST( CalibratedCamera, Dproject_to_camera1) { - Point3 pp(155,233,131); - Matrix actual; - CalibratedCamera::project_to_camera(pp, actual); - Matrix expected_numerical = numericalDerivative11( - boost::bind(CalibratedCamera::project_to_camera, _1, boost::none), pp); - CHECK(assert_equal(expected_numerical, actual)); +static Point2 Project1(const Point3& point) { + return PinholeBase::Project(point); +} + +TEST( CalibratedCamera, DProject1) { + Point3 pp(155, 233, 131); + Matrix test1; + CalibratedCamera::Project(pp, test1); + Matrix test2 = numericalDerivative11(Project1, pp); + CHECK(assert_equal(test1, test2)); +} + +/* ************************************************************************* */ +static Point2 Project2(const Unit3& point) { + return PinholeBase::Project(point); +} + +Unit3 pointAtInfinity(0, 0, 1000); +TEST( CalibratedCamera, DProjectInfinity) { + Matrix test1; + CalibratedCamera::Project(pointAtInfinity, test1); + Matrix test2 = numericalDerivative11(Project2, + pointAtInfinity); + CHECK(assert_equal(test1, test2)); } /* ************************************************************************* */ @@ -118,7 +135,7 @@ TEST( CalibratedCamera, Dproject_point_pose) // Add a test with more arbitrary rotation TEST( CalibratedCamera, Dproject_point_pose2) { - static const Pose3 pose1(Rot3::ypr(0.1, -0.1, 0.4), Point3(0, 0, -10)); + static const Pose3 pose1(Rot3::Ypr(0.1, -0.1, 0.4), Point3(0, 0, -10)); static const CalibratedCamera camera(pose1); Matrix Dpose, Dpoint; camera.project(point1, Dpose, Dpoint); @@ -128,6 +145,36 @@ TEST( CalibratedCamera, Dproject_point_pose2) CHECK(assert_equal(numerical_point, Dpoint, 1e-7)); } +/* ************************************************************************* */ +static Point2 projectAtInfinity(const CalibratedCamera& camera, const Unit3& point) { + return camera.project2(point); +} + +TEST( CalibratedCamera, Dproject_point_pose_infinity) +{ + Matrix Dpose, Dpoint; + Point2 result = camera.project2(pointAtInfinity, Dpose, Dpoint); + Matrix numerical_pose = numericalDerivative21(projectAtInfinity, camera, pointAtInfinity); + Matrix numerical_point = numericalDerivative22(projectAtInfinity, camera, pointAtInfinity); + CHECK(assert_equal(Point2(), result)); + CHECK(assert_equal(numerical_pose, Dpose, 1e-7)); + CHECK(assert_equal(numerical_point, Dpoint, 1e-7)); +} + +/* ************************************************************************* */ +// Add a test with more arbitrary rotation +TEST( CalibratedCamera, Dproject_point_pose2_infinity) +{ + static const Pose3 pose1(Rot3::Ypr(0.1, -0.1, 0.4), Point3(0, 0, -10)); + static const CalibratedCamera camera(pose1); + Matrix Dpose, Dpoint; + camera.project2(pointAtInfinity, Dpose, Dpoint); + Matrix numerical_pose = numericalDerivative21(projectAtInfinity, camera, pointAtInfinity); + Matrix numerical_point = numericalDerivative22(projectAtInfinity, camera, pointAtInfinity); + CHECK(assert_equal(numerical_pose, Dpose, 1e-7)); + CHECK(assert_equal(numerical_point, Dpoint, 1e-7)); +} + /* ************************************************************************* */ int main() { TestResult tr; return TestRegistry::runAllTests(tr); } /* ************************************************************************* */ diff --git a/gtsam/geometry/tests/testCameraSet.cpp b/gtsam/geometry/tests/testCameraSet.cpp index 42cf0f299..0afa04411 100644 --- a/gtsam/geometry/tests/testCameraSet.cpp +++ b/gtsam/geometry/tests/testCameraSet.cpp @@ -31,43 +31,105 @@ using namespace gtsam; #include TEST(CameraSet, Pinhole) { typedef PinholeCamera Camera; + typedef CameraSet Set; typedef vector ZZ; - CameraSet set; + Set set; Camera camera; set.push_back(camera); set.push_back(camera); Point3 p(0, 0, 1); - CHECK(assert_equal(set, set)); - CameraSet set2 = set; + EXPECT(assert_equal(set, set)); + Set set2 = set; set2.push_back(camera); - CHECK(!set.equals(set2)); + EXPECT(!set.equals(set2)); // Check measurements Point2 expected; - ZZ z = set.project(p); - CHECK(assert_equal(expected, z[0])); - CHECK(assert_equal(expected, z[1])); + ZZ z = set.project2(p); + EXPECT(assert_equal(expected, z[0])); + EXPECT(assert_equal(expected, z[1])); // Calculate expected derivatives using Pinhole - Matrix46 actualF; - Matrix43 actualE; - Matrix43 actualH; + Matrix actualE; + Matrix29 F1; { - Matrix26 F1; Matrix23 E1; - Matrix23 H1; - camera.project(p, F1, E1, H1); + camera.project2(p, F1, E1); + actualE.resize(4,3); actualE << E1, E1; - actualF << F1, F1; - actualH << H1, H1; } // Check computed derivatives - Matrix F, E, H; - set.project(p, F, E, H); - CHECK(assert_equal(actualF, F)); - CHECK(assert_equal(actualE, E)); - CHECK(assert_equal(actualH, H)); + Set::FBlocks Fs; + Matrix E; + set.project2(p, Fs, E); + LONGS_EQUAL(2, Fs.size()); + EXPECT(assert_equal(F1, Fs[0])); + EXPECT(assert_equal(F1, Fs[1])); + EXPECT(assert_equal(actualE, E)); + + // Check errors + ZZ measured; + measured.push_back(Point2(1, 2)); + measured.push_back(Point2(3, 4)); + Vector4 expectedV; + + // reprojectionError + expectedV << -1, -2, -3, -4; + Vector actualV = set.reprojectionError(p, measured); + EXPECT(assert_equal(expectedV, actualV)); + + // Check Schur complement + Matrix F(4, 18); + F << F1, Matrix29::Zero(), Matrix29::Zero(), F1; + Matrix Ft = F.transpose(); + Matrix34 Et = E.transpose(); + Matrix3 P = Et * E; + Matrix schur(19, 19); + Vector4 b = actualV; + Vector v = Ft * (b - E * P * Et * b); + schur << Ft * F - Ft * E * P * Et * F, v, v.transpose(), 30; + SymmetricBlockMatrix actualReduced = Set::SchurComplement(Fs, E, P, b); + EXPECT(assert_equal(schur, actualReduced.matrix())); + + // Check Schur complement update, same order, should just double + FastVector allKeys, keys; + allKeys.push_back(1); + allKeys.push_back(2); + keys.push_back(1); + keys.push_back(2); + Set::UpdateSchurComplement(Fs, E, P, b, allKeys, keys, actualReduced); + EXPECT(assert_equal((Matrix )(2.0 * schur), actualReduced.matrix())); + + // Check Schur complement update, keys reversed + FastVector keys2; + keys2.push_back(2); + keys2.push_back(1); + Set::UpdateSchurComplement(Fs, E, P, b, allKeys, keys2, actualReduced); + Vector4 reverse_b; + reverse_b << b.tail<2>(), b.head<2>(); + Vector reverse_v = Ft * (reverse_b - E * P * Et * reverse_b); + Matrix A(19, 19); + A << Ft * F - Ft * E * P * Et * F, reverse_v, reverse_v.transpose(), 30; + EXPECT(assert_equal((Matrix )(2.0 * schur + A), actualReduced.matrix())); + + // reprojectionErrorAtInfinity + Unit3 pointAtInfinity(0, 0, 1000); + EXPECT( + assert_equal(pointAtInfinity, + camera.backprojectPointAtInfinity(Point2()))); + actualV = set.reprojectionError(pointAtInfinity, measured, Fs, E); + EXPECT(assert_equal(expectedV, actualV)); + LONGS_EQUAL(2, Fs.size()); + { + Matrix22 E1; + camera.project2(pointAtInfinity, F1, E1); + actualE.resize(4,2); + actualE << E1, E1; + } + EXPECT(assert_equal(F1, Fs[0])); + EXPECT(assert_equal(F1, Fs[1])); + EXPECT(assert_equal(actualE, E)); } /* ************************************************************************* */ @@ -83,26 +145,27 @@ TEST(CameraSet, Stereo) { // Check measurements StereoPoint2 expected(0, -1, 0); - ZZ z = set.project(p); - CHECK(assert_equal(expected, z[0])); - CHECK(assert_equal(expected, z[1])); + ZZ z = set.project2(p); + EXPECT(assert_equal(expected, z[0])); + EXPECT(assert_equal(expected, z[1])); // Calculate expected derivatives using Pinhole - Matrix66 actualF; Matrix63 actualE; + Matrix F1; { - Matrix36 F1; Matrix33 E1; - camera.project(p, F1, E1); + camera.project2(p, F1, E1); actualE << E1, E1; - actualF << F1, F1; } // Check computed derivatives - Matrix F, E; - set.project(p, F, E); - CHECK(assert_equal(actualF, F)); - CHECK(assert_equal(actualE, E)); + CameraSet::FBlocks Fs; + Matrix E; + set.project2(p, Fs, E); + LONGS_EQUAL(2, Fs.size()); + EXPECT(assert_equal(F1, Fs[0])); + EXPECT(assert_equal(F1, Fs[1])); + EXPECT(assert_equal(actualE, E)); } /* ************************************************************************* */ diff --git a/gtsam/geometry/tests/testEssentialMatrix.cpp b/gtsam/geometry/tests/testEssentialMatrix.cpp index fe27b2911..bfff0a182 100644 --- a/gtsam/geometry/tests/testEssentialMatrix.cpp +++ b/gtsam/geometry/tests/testEssentialMatrix.cpp @@ -20,7 +20,7 @@ GTSAM_CONCEPT_MANIFOLD_INST(EssentialMatrix) //************************************************************************* // Create two cameras and corresponding essential matrix E -Rot3 c1Rc2 = Rot3::yaw(M_PI_2); +Rot3 c1Rc2 = Rot3::Yaw(M_PI_2); Point3 c1Tc2(0.1, 0, 0); EssentialMatrix trueE(c1Rc2, Unit3(c1Tc2)); @@ -98,8 +98,8 @@ Point3 transform_to_(const EssentialMatrix& E, const Point3& point) { } TEST (EssentialMatrix, transform_to) { // test with a more complicated EssentialMatrix - Rot3 aRb2 = Rot3::yaw(M_PI / 3.0) * Rot3::pitch(M_PI_4) - * Rot3::roll(M_PI / 6.0); + Rot3 aRb2 = Rot3::Yaw(M_PI / 3.0) * Rot3::Pitch(M_PI_4) + * Rot3::Roll(M_PI / 6.0); Point3 aTb2(19.2, 3.7, 5.9); EssentialMatrix E(aRb2, Unit3(aTb2)); //EssentialMatrix E(aRb, Unit3(aTb).retract(Vector2(0.1, 0))); @@ -159,7 +159,7 @@ TEST (EssentialMatrix, FromPose3_a) { //************************************************************************* TEST (EssentialMatrix, FromPose3_b) { Matrix actualH; - Rot3 c1Rc2 = Rot3::ypr(0.1, -0.2, 0.3); + Rot3 c1Rc2 = Rot3::Ypr(0.1, -0.2, 0.3); Point3 c1Tc2(0.4, 0.5, 0.6); EssentialMatrix E(c1Rc2, Unit3(c1Tc2)); Pose3 pose(c1Rc2, c1Tc2); // Pose between two cameras @@ -181,7 +181,7 @@ TEST (EssentialMatrix, streaming) { //************************************************************************* TEST (EssentialMatrix, epipoles) { // Create an E - Rot3 c1Rc2 = Rot3::ypr(0.1, -0.2, 0.3); + Rot3 c1Rc2 = Rot3::Ypr(0.1, -0.2, 0.3); Point3 c1Tc2(0.4, 0.5, 0.6); EssentialMatrix E(c1Rc2, Unit3(c1Tc2)); diff --git a/gtsam/geometry/tests/testOrientedPlane3.cpp b/gtsam/geometry/tests/testOrientedPlane3.cpp index b2b4ecc43..180abb0d6 100644 --- a/gtsam/geometry/tests/testOrientedPlane3.cpp +++ b/gtsam/geometry/tests/testOrientedPlane3.cpp @@ -13,6 +13,7 @@ * @file testOrientedPlane3.cpp * @date Dec 19, 2012 * @author Alex Trevor + * @author Zhaoyang Lv * @brief Tests the OrientedPlane3 class */ @@ -30,39 +31,67 @@ GTSAM_CONCEPT_TESTABLE_INST(OrientedPlane3) GTSAM_CONCEPT_MANIFOLD_INST(OrientedPlane3) //******************************************************************************* +TEST (OrientedPlane3, getMethods) { + Vector4 c; + c << -1, 0, 0, 5; + OrientedPlane3 plane1(c); + OrientedPlane3 plane2(c[0], c[1], c[2], c[3]); + Vector4 coefficient1 = plane1.planeCoefficients(); + double distance1 = plane1.distance(); + EXPECT(assert_equal(coefficient1, c, 1e-8)); + EXPECT(assert_equal(Unit3(-1,0,0).unitVector(), plane1.normal().unitVector())); + EXPECT_DOUBLES_EQUAL(distance1, 5, 1e-8); + Vector4 coefficient2 = plane2.planeCoefficients(); + double distance2 = plane2.distance(); + EXPECT(assert_equal(coefficient2, c, 1e-8)); + EXPECT_DOUBLES_EQUAL(distance2, 5, 1e-8); + EXPECT(assert_equal(Unit3(-1,0,0).unitVector(), plane2.normal().unitVector())); +} + + +//******************************************************************************* +OrientedPlane3 Transform_(const OrientedPlane3& plane, const Pose3& xr) { + return OrientedPlane3::Transform(plane, xr); +} + +OrientedPlane3 transform_(const OrientedPlane3& plane, const Pose3& xr) { + return plane.transform(xr); +} + TEST (OrientedPlane3, transform) { - // Test transforming a plane to a pose - gtsam::Pose3 pose(gtsam::Rot3::ypr(-M_PI / 4.0, 0.0, 0.0), + gtsam::Pose3 pose(gtsam::Rot3::Ypr(-M_PI / 4.0, 0.0, 0.0), gtsam::Point3(2.0, 3.0, 4.0)); OrientedPlane3 plane(-1, 0, 0, 5); - OrientedPlane3 expected_meas(-sqrt(2.0) / 2.0, -sqrt(2.0) / 2.0, 0.0, 3); - OrientedPlane3 transformed_plane = OrientedPlane3::Transform(plane, pose, + OrientedPlane3 expectedPlane(-sqrt(2.0) / 2.0, -sqrt(2.0) / 2.0, 0.0, 3); + OrientedPlane3 transformedPlane1 = OrientedPlane3::Transform(plane, pose, none, none); - EXPECT(assert_equal(expected_meas, transformed_plane, 1e-9)); + OrientedPlane3 transformedPlane2 = plane.transform(pose, none, none); + EXPECT(assert_equal(expectedPlane, transformedPlane1, 1e-9)); + EXPECT(assert_equal(expectedPlane, transformedPlane2, 1e-9)); // Test the jacobians of transform Matrix actualH1, expectedH1, actualH2, expectedH2; { - expectedH1 = numericalDerivative11( - boost::bind(&OrientedPlane3::Transform, plane, _1, none, none), pose); - - OrientedPlane3 tformed = OrientedPlane3::Transform(plane, pose, actualH1, - none); + // because the Transform class uses a wrong order of Jacobians in interface + OrientedPlane3::Transform(plane, pose, actualH1, none); + expectedH1 = numericalDerivative22(Transform_, plane, pose); EXPECT(assert_equal(expectedH1, actualH1, 1e-9)); - } - { - expectedH2 = numericalDerivative11( - boost::bind(&OrientedPlane3::Transform, _1, pose, none, none), plane); - - OrientedPlane3 tformed = OrientedPlane3::Transform(plane, pose, none, - actualH2); + OrientedPlane3::Transform(plane, pose, none, actualH2); + expectedH2 = numericalDerivative21(Transform_, plane, pose); + EXPECT(assert_equal(expectedH2, actualH2, 1e-9)); + } + { + plane.transform(pose, actualH1, none); + expectedH1 = numericalDerivative21(transform_, plane, pose); + EXPECT(assert_equal(expectedH1, actualH1, 1e-9)); + plane.transform(pose, none, actualH2); + expectedH2 = numericalDerivative22(Transform_, plane, pose); EXPECT(assert_equal(expectedH2, actualH2, 1e-9)); } - } //******************************************************************************* -// Returns a random vector -- copied from testUnit3.cpp +// Returns a any size random vector inline static Vector randomVector(const Vector& minLimits, const Vector& maxLimits) { @@ -82,11 +111,11 @@ inline static Vector randomVector(const Vector& minLimits, TEST(OrientedPlane3, localCoordinates_retract) { size_t numIterations = 10000; - gtsam::Vector minPlaneLimit(4), maxPlaneLimit(4); + Vector4 minPlaneLimit, maxPlaneLimit; minPlaneLimit << -1.0, -1.0, -1.0, 0.01; maxPlaneLimit << 1.0, 1.0, 1.0, 10.0; - Vector minXiLimit(3), maxXiLimit(3); + Vector3 minXiLimit, maxXiLimit; minXiLimit << -M_PI, -M_PI, -10.0; maxXiLimit << M_PI, M_PI, 10.0; for (size_t i = 0; i < numIterations; i++) { @@ -98,15 +127,15 @@ TEST(OrientedPlane3, localCoordinates_retract) { Vector v12 = randomVector(minXiLimit, maxXiLimit); // Magnitude of the rotation can be at most pi - if (v12.segment<3>(0).norm() > M_PI) - v12.segment<3>(0) = v12.segment<3>(0) / M_PI; + if (v12.head<3>().norm() > M_PI) + v12.head<3>() = v12.head<3>() / M_PI; OrientedPlane3 p2 = p1.retract(v12); // Check if the local coordinates and retract return the same results. Vector actual_v12 = p1.localCoordinates(p2); - EXPECT(assert_equal(v12, actual_v12, 1e-3)); + EXPECT(assert_equal(v12, actual_v12, 1e-6)); OrientedPlane3 actual_p2 = p1.retract(actual_v12); - EXPECT(assert_equal(p2, actual_p2, 1e-3)); + EXPECT(assert_equal(p2, actual_p2, 1e-6)); } } diff --git a/gtsam/geometry/tests/testPinholeCamera.cpp b/gtsam/geometry/tests/testPinholeCamera.cpp index 0e610d8d6..7293d4235 100644 --- a/gtsam/geometry/tests/testPinholeCamera.cpp +++ b/gtsam/geometry/tests/testPinholeCamera.cpp @@ -45,10 +45,10 @@ static const Point3 point2(-0.08, 0.08, 0.0); static const Point3 point3( 0.08, 0.08, 0.0); static const Point3 point4( 0.08,-0.08, 0.0); -static const Point3 point1_inf(-0.16,-0.16, -1.0); -static const Point3 point2_inf(-0.16, 0.16, -1.0); -static const Point3 point3_inf( 0.16, 0.16, -1.0); -static const Point3 point4_inf( 0.16,-0.16, -1.0); +static const Unit3 point1_inf(-0.16,-0.16, -1.0); +static const Unit3 point2_inf(-0.16, 0.16, -1.0); +static const Unit3 point3_inf( 0.16, 0.16, -1.0); +static const Unit3 point4_inf( 0.16,-0.16, -1.0); /* ************************************************************************* */ TEST( PinholeCamera, constructor) @@ -154,9 +154,9 @@ TEST( PinholeCamera, backprojectInfinity2) Rot3 rot(1., 0., 0., 0., 0., 1., 0., -1., 0.); // a camera1 looking down Camera camera(Pose3(rot, origin), K); - Point3 actual = camera.backprojectPointAtInfinity(Point2()); - Point3 expected(0., 1., 0.); - Point2 x = camera.projectPointAtInfinity(expected); + Unit3 actual = camera.backprojectPointAtInfinity(Point2()); + Unit3 expected(0., 1., 0.); + Point2 x = camera.project(expected); EXPECT(assert_equal(expected, actual)); EXPECT(assert_equal(Point2(), x)); @@ -169,9 +169,9 @@ TEST( PinholeCamera, backprojectInfinity3) Rot3 rot(1., 0., 0., 0., 1., 0., 0., 0., 1.); // identity Camera camera(Pose3(rot, origin), K); - Point3 actual = camera.backprojectPointAtInfinity(Point2()); - Point3 expected(0., 0., 1.); - Point2 x = camera.projectPointAtInfinity(expected); + Unit3 actual = camera.backprojectPointAtInfinity(Point2()); + Unit3 expected(0., 0., 1.); + Point2 x = camera.project(expected); EXPECT(assert_equal(expected, actual)); EXPECT(assert_equal(Point2(), x)); @@ -197,17 +197,17 @@ TEST( PinholeCamera, Dproject) } /* ************************************************************************* */ -static Point2 projectInfinity3(const Pose3& pose, const Point3& point3D, const Cal3_S2& cal) { - return Camera(pose,cal).projectPointAtInfinity(point3D); +static Point2 projectInfinity3(const Pose3& pose, const Unit3& point3D, const Cal3_S2& cal) { + return Camera(pose,cal).project(point3D); } TEST( PinholeCamera, Dproject_Infinity) { Matrix Dpose, Dpoint, Dcal; - Point3 point3D(point1.x(), point1.y(), -10.0); // a point in front of the camera1 + Unit3 point3D(point1.x(), point1.y(), -10.0); // a point in front of the camera1 // test Projection - Point2 actual = camera.projectPointAtInfinity(point3D, Dpose, Dpoint, Dcal); + Point2 actual = camera.project(point3D, Dpose, Dpoint, Dcal); Point2 expected(-5.0, 5.0); EXPECT(assert_equal(actual, expected, 1e-7)); @@ -242,7 +242,7 @@ TEST( PinholeCamera, Dproject2) // Add a test with more arbitrary rotation TEST( PinholeCamera, Dproject3) { - static const Pose3 pose1(Rot3::ypr(0.1, -0.1, 0.4), Point3(0, 0, -10)); + static const Pose3 pose1(Rot3::Ypr(0.1, -0.1, 0.4), Point3(0, 0, -10)); static const Camera camera(pose1); Matrix Dpose, Dpoint; camera.project2(point1, Dpose, Dpoint); diff --git a/gtsam/geometry/tests/testPinholePose.cpp b/gtsam/geometry/tests/testPinholePose.cpp index 411273c1f..8f3eadc51 100644 --- a/gtsam/geometry/tests/testPinholePose.cpp +++ b/gtsam/geometry/tests/testPinholePose.cpp @@ -46,10 +46,10 @@ static const Point3 point2(-0.08, 0.08, 0.0); static const Point3 point3( 0.08, 0.08, 0.0); static const Point3 point4( 0.08,-0.08, 0.0); -static const Point3 point1_inf(-0.16,-0.16, -1.0); -static const Point3 point2_inf(-0.16, 0.16, -1.0); -static const Point3 point3_inf( 0.16, 0.16, -1.0); -static const Point3 point4_inf( 0.16,-0.16, -1.0); +static const Unit3 point1_inf(-0.16,-0.16, -1.0); +static const Unit3 point2_inf(-0.16, 0.16, -1.0); +static const Unit3 point3_inf( 0.16, 0.16, -1.0); +static const Unit3 point4_inf( 0.16,-0.16, -1.0); /* ************************************************************************* */ TEST( PinholePose, constructor) @@ -144,11 +144,11 @@ TEST( PinholePose, Dproject) { Matrix Dpose, Dpoint; Point2 result = camera.project2(point1, Dpose, Dpoint); - Matrix numerical_pose = numericalDerivative31(project3, pose, point1, K); - Matrix Hexpected2 = numericalDerivative32(project3, pose, point1, K); + Matrix expectedDcamera = numericalDerivative31(project3, pose, point1, K); + Matrix expectedDpoint = numericalDerivative32(project3, pose, point1, K); EXPECT(assert_equal(Point2(-100, 100), result)); - EXPECT(assert_equal(numerical_pose, Dpose, 1e-7)); - EXPECT(assert_equal(Hexpected2, Dpoint, 1e-7)); + EXPECT(assert_equal(expectedDcamera, Dpose, 1e-7)); + EXPECT(assert_equal(expectedDpoint, Dpoint, 1e-7)); } /* ************************************************************************* */ @@ -161,27 +161,46 @@ TEST( PinholePose, Dproject2) { Matrix Dcamera, Dpoint; Point2 result = camera.project2(point1, Dcamera, Dpoint); - Matrix Hexpected1 = numericalDerivative21(project4, camera, point1); - Matrix Hexpected2 = numericalDerivative22(project4, camera, point1); + Matrix expectedDcamera = numericalDerivative21(project4, camera, point1); + Matrix expectedDpoint = numericalDerivative22(project4, camera, point1); EXPECT(assert_equal(result, Point2(-100, 100) )); - EXPECT(assert_equal(Hexpected1, Dcamera, 1e-7)); - EXPECT(assert_equal(Hexpected2, Dpoint, 1e-7)); + EXPECT(assert_equal(expectedDcamera, Dcamera, 1e-7)); + EXPECT(assert_equal(expectedDpoint, Dpoint, 1e-7)); } /* ************************************************************************* */ // Add a test with more arbitrary rotation TEST( CalibratedCamera, Dproject3) { - static const Pose3 pose1(Rot3::ypr(0.1, -0.1, 0.4), Point3(0, 0, -10)); + static const Pose3 pose1(Rot3::Ypr(0.1, -0.1, 0.4), Point3(0, 0, -10)); static const Camera camera(pose1); Matrix Dpose, Dpoint; camera.project2(point1, Dpose, Dpoint); - Matrix numerical_pose = numericalDerivative21(project4, camera, point1); + Matrix expectedDcamera = numericalDerivative21(project4, camera, point1); Matrix numerical_point = numericalDerivative22(project4, camera, point1); - CHECK(assert_equal(numerical_pose, Dpose, 1e-7)); + CHECK(assert_equal(expectedDcamera, Dpose, 1e-7)); CHECK(assert_equal(numerical_point, Dpoint, 1e-7)); } +/* ************************************************************************* */ +static Point2 project(const Pose3& pose, const Unit3& pointAtInfinity, + const Cal3_S2::shared_ptr& cal) { + return Camera(pose, cal).project(pointAtInfinity); +} + +/* ************************************************************************* */ +TEST( PinholePose, DprojectAtInfinity2) +{ + Unit3 pointAtInfinity(0,0,1000); + Matrix Dpose, Dpoint; + Point2 result = camera.project2(pointAtInfinity, Dpose, Dpoint); + Matrix expectedDcamera = numericalDerivative31(project, pose, pointAtInfinity, K); + Matrix expectedDpoint = numericalDerivative32(project, pose, pointAtInfinity, K); + EXPECT(assert_equal(Point2(0,0), result)); + EXPECT(assert_equal(expectedDcamera, Dpose, 1e-7)); + EXPECT(assert_equal(expectedDpoint, Dpoint, 1e-7)); +} + /* ************************************************************************* */ static double range0(const Camera& camera, const Point3& point) { return camera.range(point); @@ -191,12 +210,12 @@ static double range0(const Camera& camera, const Point3& point) { TEST( PinholePose, range0) { Matrix D1; Matrix D2; double result = camera.range(point1, D1, D2); - Matrix Hexpected1 = numericalDerivative21(range0, camera, point1); - Matrix Hexpected2 = numericalDerivative22(range0, camera, point1); + Matrix expectedDcamera = numericalDerivative21(range0, camera, point1); + Matrix expectedDpoint = numericalDerivative22(range0, camera, point1); EXPECT_DOUBLES_EQUAL(point1.distance(camera.pose().translation()), result, 1e-9); - EXPECT(assert_equal(Hexpected1, D1, 1e-7)); - EXPECT(assert_equal(Hexpected2, D2, 1e-7)); + EXPECT(assert_equal(expectedDcamera, D1, 1e-7)); + EXPECT(assert_equal(expectedDpoint, D2, 1e-7)); } /* ************************************************************************* */ @@ -208,11 +227,11 @@ static double range1(const Camera& camera, const Pose3& pose) { TEST( PinholePose, range1) { Matrix D1; Matrix D2; double result = camera.range(pose1, D1, D2); - Matrix Hexpected1 = numericalDerivative21(range1, camera, pose1); - Matrix Hexpected2 = numericalDerivative22(range1, camera, pose1); + Matrix expectedDcamera = numericalDerivative21(range1, camera, pose1); + Matrix expectedDpoint = numericalDerivative22(range1, camera, pose1); EXPECT_DOUBLES_EQUAL(1, result, 1e-9); - EXPECT(assert_equal(Hexpected1, D1, 1e-7)); - EXPECT(assert_equal(Hexpected2, D2, 1e-7)); + EXPECT(assert_equal(expectedDcamera, D1, 1e-7)); + EXPECT(assert_equal(expectedDpoint, D2, 1e-7)); } /* ************************************************************************* */ @@ -228,11 +247,11 @@ static double range2(const Camera& camera, const Camera2& camera2) { TEST( PinholePose, range2) { Matrix D1; Matrix D2; double result = camera.range(camera2, D1, D2); - Matrix Hexpected1 = numericalDerivative21(range2, camera, camera2); - Matrix Hexpected2 = numericalDerivative22(range2, camera, camera2); + Matrix expectedDcamera = numericalDerivative21(range2, camera, camera2); + Matrix expectedDpoint = numericalDerivative22(range2, camera, camera2); EXPECT_DOUBLES_EQUAL(1, result, 1e-9); - EXPECT(assert_equal(Hexpected1, D1, 1e-7)); - EXPECT(assert_equal(Hexpected2, D2, 1e-7)); + EXPECT(assert_equal(expectedDcamera, D1, 1e-7)); + EXPECT(assert_equal(expectedDpoint, D2, 1e-7)); } /* ************************************************************************* */ @@ -245,11 +264,11 @@ static double range3(const Camera& camera, const CalibratedCamera& camera3) { TEST( PinholePose, range3) { Matrix D1; Matrix D2; double result = camera.range(camera3, D1, D2); - Matrix Hexpected1 = numericalDerivative21(range3, camera, camera3); - Matrix Hexpected2 = numericalDerivative22(range3, camera, camera3); + Matrix expectedDcamera = numericalDerivative21(range3, camera, camera3); + Matrix expectedDpoint = numericalDerivative22(range3, camera, camera3); EXPECT_DOUBLES_EQUAL(1, result, 1e-9); - EXPECT(assert_equal(Hexpected1, D1, 1e-7)); - EXPECT(assert_equal(Hexpected2, D2, 1e-7)); + EXPECT(assert_equal(expectedDcamera, D1, 1e-7)); + EXPECT(assert_equal(expectedDpoint, D2, 1e-7)); } /* ************************************************************************* */ diff --git a/gtsam/geometry/tests/testPinholeSet.cpp b/gtsam/geometry/tests/testPinholeSet.cpp new file mode 100644 index 000000000..b8f001f1c --- /dev/null +++ b/gtsam/geometry/tests/testPinholeSet.cpp @@ -0,0 +1,158 @@ +/* ---------------------------------------------------------------------------- + + * 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 testCameraSet.cpp + * @brief Unit tests for testCameraSet Class + * @author Frank Dellaert + * @date Feb 19, 2015 + */ + +#include +#include +#include +#include +#include + +using namespace std; +using namespace gtsam; + +/* ************************************************************************* */ +#include +TEST(PinholeSet, Stereo) { + typedef vector ZZ; + PinholeSet set; + CalibratedCamera camera; + set.push_back(camera); + set.push_back(camera); + // set.print("set: "); + Point3 p(0, 0, 1); + EXPECT_LONGS_EQUAL(6, traits::dimension); + + // Check measurements + Point2 expected(0, 0); + ZZ z = set.project2(p); + EXPECT(assert_equal(expected, z[0])); + EXPECT(assert_equal(expected, z[1])); + + // Calculate expected derivatives using Pinhole + Matrix43 actualE; + Matrix F1; + { + Matrix23 E1; + camera.project2(p, F1, E1); + actualE << E1, E1; + } + + // Check computed derivatives + PinholeSet::FBlocks Fs; + Matrix E; + set.project2(p, Fs, E); + LONGS_EQUAL(2, Fs.size()); + EXPECT(assert_equal(F1, Fs[0])); + EXPECT(assert_equal(F1, Fs[1])); + EXPECT(assert_equal(actualE, E)); + + // Instantiate triangulateSafe + // TODO triangulation does not work yet for CalibratedCamera + // PinholeSet::Result actual = set.triangulateSafe(z); +} + +/* ************************************************************************* */ +// Cal3Bundler test +#include +#include +TEST(PinholeSet, Pinhole) { + typedef PinholeCamera Camera; + typedef vector ZZ; + PinholeSet set; + Camera camera; + set.push_back(camera); + set.push_back(camera); + Point3 p(0, 0, 1); + EXPECT(assert_equal(set, set)); + PinholeSet set2 = set; + set2.push_back(camera); + EXPECT(!set.equals(set2)); + + // Check measurements + Point2 expected; + ZZ z = set.project2(p); + EXPECT(assert_equal(expected, z[0])); + EXPECT(assert_equal(expected, z[1])); + + // Calculate expected derivatives using Pinhole + Matrix actualE; + Matrix F1; + { + Matrix23 E1; + camera.project2(p, F1, E1); + actualE.resize(4, 3); + actualE << E1, E1; + } + + // Check computed derivatives + { + PinholeSet::FBlocks Fs; + Matrix E; + set.project2(p, Fs, E); + EXPECT(assert_equal(actualE, E)); + LONGS_EQUAL(2, Fs.size()); + EXPECT(assert_equal(F1, Fs[0])); + EXPECT(assert_equal(F1, Fs[1])); + } + + // Check errors + ZZ measured; + measured.push_back(Point2(1, 2)); + measured.push_back(Point2(3, 4)); + Vector4 expectedV; + + // reprojectionError + expectedV << -1, -2, -3, -4; + Vector actualV = set.reprojectionError(p, measured); + EXPECT(assert_equal(expectedV, actualV)); + + // reprojectionErrorAtInfinity + Unit3 pointAtInfinity(0, 0, 1000); + { + Matrix22 E1; + camera.project2(pointAtInfinity, F1, E1); + actualE.resize(4, 2); + actualE << E1, E1; + } + EXPECT( + assert_equal(pointAtInfinity, + camera.backprojectPointAtInfinity(Point2()))); + { + PinholeSet::FBlocks Fs; + Matrix E; + actualV = set.reprojectionError(pointAtInfinity, measured, Fs, E); + EXPECT(assert_equal(actualE, E)); + LONGS_EQUAL(2, Fs.size()); + EXPECT(assert_equal(F1, Fs[0])); + EXPECT(assert_equal(F1, Fs[1])); + } + EXPECT(assert_equal(expectedV, actualV)); + + // Instantiate triangulateSafe + TriangulationParameters params; + TriangulationResult actual = set.triangulateSafe(z, params); + CHECK(actual.degenerate()); +} + +/* ************************************************************************* */ +int main() { + TestResult tr; + return TestRegistry::runAllTests(tr); +} +/* ************************************************************************* */ + diff --git a/gtsam/geometry/tests/testPoint3.cpp b/gtsam/geometry/tests/testPoint3.cpp index 6811ed122..246d23c9a 100644 --- a/gtsam/geometry/tests/testPoint3.cpp +++ b/gtsam/geometry/tests/testPoint3.cpp @@ -133,6 +133,17 @@ TEST (Point3, distance) { EXPECT(assert_equal(numH2, H2, 1e-8)); } +/* ************************************************************************* */ +TEST(Point3, cross) { + Matrix aH1, aH2; + boost::function f = + boost::bind(&Point3::cross, _1, _2, boost::none, boost::none); + const Point3 omega(0, 1, 0), theta(4, 6, 8); + omega.cross(theta, aH1, aH2); + EXPECT(assert_equal(numericalDerivative21(f, omega, theta), aH1)); + EXPECT(assert_equal(numericalDerivative22(f, omega, theta), aH2)); +} + /* ************************************************************************* */ int main() { TestResult tr; diff --git a/gtsam/geometry/tests/testPose3.cpp b/gtsam/geometry/tests/testPose3.cpp index 98c80e356..56e1e022c 100644 --- a/gtsam/geometry/tests/testPose3.cpp +++ b/gtsam/geometry/tests/testPose3.cpp @@ -32,10 +32,10 @@ GTSAM_CONCEPT_TESTABLE_INST(Pose3) GTSAM_CONCEPT_LIE_INST(Pose3) static Point3 P(0.2,0.7,-2); -static Rot3 R = Rot3::rodriguez(0.3,0,0); +static Rot3 R = Rot3::Rodrigues(0.3,0,0); static Pose3 T(R,Point3(3.5,-8.2,4.2)); -static Pose3 T2(Rot3::rodriguez(0.3,0.2,0.1),Point3(3.5,-8.2,4.2)); -static Pose3 T3(Rot3::rodriguez(-90, 0, 0), Point3(1, 2, 3)); +static Pose3 T2(Rot3::Rodrigues(0.3,0.2,0.1),Point3(3.5,-8.2,4.2)); +static Pose3 T3(Rot3::Rodrigues(-90, 0, 0), Point3(1, 2, 3)); const double tol=1e-5; /* ************************************************************************* */ @@ -50,7 +50,7 @@ TEST( Pose3, equals) /* ************************************************************************* */ TEST( Pose3, constructors) { - Pose3 expected(Rot3::rodriguez(0,0,3),Point3(1,2,0)); + Pose3 expected(Rot3::Rodrigues(0,0,3),Point3(1,2,0)); Pose2 pose2(1,2,3); EXPECT(assert_equal(expected,Pose3(pose2))); } @@ -103,7 +103,7 @@ TEST(Pose3, expmap_b) { Pose3 p1(Rot3(), Point3(100, 0, 0)); Pose3 p2 = p1.retract((Vector(6) << 0.0, 0.0, 0.1, 0.0, 0.0, 0.0).finished()); - Pose3 expected(Rot3::rodriguez(0.0, 0.0, 0.1), Point3(100.0, 0.0, 0.0)); + Pose3 expected(Rot3::Rodrigues(0.0, 0.0, 0.1), Point3(100.0, 0.0, 0.0)); EXPECT(assert_equal(expected, p2,1e-2)); } @@ -182,8 +182,8 @@ TEST(Pose3, expmaps_galore_full) xi = (Vector(6) << 0.2, 0.3, -0.8, 100.0, 120.0, -60.0).finished(); actual = Pose3::Expmap(xi); EXPECT(assert_equal(expm(xi,10), actual,1e-5)); - EXPECT(assert_equal(Agrawal06iros(xi), actual,1e-6)); - EXPECT(assert_equal(xi, Pose3::Logmap(actual),1e-6)); + EXPECT(assert_equal(Agrawal06iros(xi), actual,1e-9)); + EXPECT(assert_equal(xi, Pose3::Logmap(actual),1e-9)); } /* ************************************************************************* */ @@ -266,7 +266,7 @@ TEST( Pose3, inverse) /* ************************************************************************* */ TEST( Pose3, inverseDerivatives2) { - Rot3 R = Rot3::rodriguez(0.3,0.4,-0.5); + Rot3 R = Rot3::Rodrigues(0.3,0.4,-0.5); Point3 t(3.5,-8.2,4.2); Pose3 T(R,t); @@ -388,7 +388,7 @@ TEST( Pose3, transform_to_translate) /* ************************************************************************* */ TEST( Pose3, transform_to_rotate) { - Pose3 transform(Rot3::rodriguez(0,0,-1.570796), Point3()); + Pose3 transform(Rot3::Rodrigues(0,0,-1.570796), Point3()); Point3 actual = transform.transform_to(Point3(2,1,10)); Point3 expected(-1,2,10); EXPECT(assert_equal(expected, actual, 0.001)); @@ -397,7 +397,7 @@ TEST( Pose3, transform_to_rotate) /* ************************************************************************* */ TEST( Pose3, transform_to) { - Pose3 transform(Rot3::rodriguez(0,0,-1.570796), Point3(2,4, 0)); + Pose3 transform(Rot3::Rodrigues(0,0,-1.570796), Point3(2,4, 0)); Point3 actual = transform.transform_to(Point3(3,2,10)); Point3 expected(2,1,10); EXPECT(assert_equal(expected, actual, 0.001)); @@ -439,7 +439,7 @@ TEST( Pose3, transformPose_to_itself) TEST( Pose3, transformPose_to_translation) { // transform translation only - Rot3 r = Rot3::rodriguez(-1.570796,0,0); + Rot3 r = Rot3::Rodrigues(-1.570796,0,0); Pose3 pose2(r, Point3(21.,32.,13.)); Pose3 actual = pose2.transform_to(Pose3(Rot3(), Point3(1,2,3))); Pose3 expected(r, Point3(20.,30.,10.)); @@ -450,7 +450,7 @@ TEST( Pose3, transformPose_to_translation) TEST( Pose3, transformPose_to_simple_rotate) { // transform translation only - Rot3 r = Rot3::rodriguez(0,0,-1.570796); + Rot3 r = Rot3::Rodrigues(0,0,-1.570796); Pose3 pose2(r, Point3(21.,32.,13.)); Pose3 transform(r, Point3(1,2,3)); Pose3 actual = pose2.transform_to(transform); @@ -462,12 +462,12 @@ TEST( Pose3, transformPose_to_simple_rotate) TEST( Pose3, transformPose_to) { // transform to - Rot3 r = Rot3::rodriguez(0,0,-1.570796); //-90 degree yaw - Rot3 r2 = Rot3::rodriguez(0,0,0.698131701); //40 degree yaw + Rot3 r = Rot3::Rodrigues(0,0,-1.570796); //-90 degree yaw + Rot3 r2 = Rot3::Rodrigues(0,0,0.698131701); //40 degree yaw Pose3 pose2(r2, Point3(21.,32.,13.)); Pose3 transform(r, Point3(1,2,3)); Pose3 actual = pose2.transform_to(transform); - Pose3 expected(Rot3::rodriguez(0,0,2.26892803), Point3(-30.,20.,10.)); + Pose3 expected(Rot3::Rodrigues(0,0,2.26892803), Point3(-30.,20.,10.)); EXPECT(assert_equal(expected, actual, 0.001)); } @@ -556,12 +556,12 @@ TEST( Pose3, between ) /* ************************************************************************* */ // some shared test values - pulled from equivalent test in Pose2 Point3 l1(1, 0, 0), l2(1, 1, 0), l3(2, 2, 0), l4(1, 4,-4); -Pose3 x1, x2(Rot3::ypr(0.0, 0.0, 0.0), l2), x3(Rot3::ypr(M_PI/4.0, 0.0, 0.0), l2); +Pose3 x1, x2(Rot3::Ypr(0.0, 0.0, 0.0), l2), x3(Rot3::Ypr(M_PI/4.0, 0.0, 0.0), l2); Pose3 - xl1(Rot3::ypr(0.0, 0.0, 0.0), Point3(1, 0, 0)), - xl2(Rot3::ypr(0.0, 1.0, 0.0), Point3(1, 1, 0)), - xl3(Rot3::ypr(1.0, 0.0, 0.0), Point3(2, 2, 0)), - xl4(Rot3::ypr(0.0, 0.0, 1.0), Point3(1, 4,-4)); + xl1(Rot3::Ypr(0.0, 0.0, 0.0), Point3(1, 0, 0)), + xl2(Rot3::Ypr(0.0, 1.0, 0.0), Point3(1, 1, 0)), + xl3(Rot3::Ypr(1.0, 0.0, 0.0), Point3(2, 2, 0)), + xl4(Rot3::Ypr(0.0, 0.0, 1.0), Point3(1, 4,-4)); /* ************************************************************************* */ double range_proxy(const Pose3& pose, const Point3& point) { @@ -633,14 +633,30 @@ TEST( Pose3, range_pose ) EXPECT(assert_equal(expectedH2,actualH2)); } +/* ************************************************************************* */ +Unit3 bearing_proxy(const Pose3& pose, const Point3& point) { + return pose.bearing(point); +} +TEST( Pose3, bearing ) +{ + Matrix expectedH1, actualH1, expectedH2, actualH2; + EXPECT(assert_equal(Unit3(1,0,0),x1.bearing(l1, actualH1, actualH2),1e-9)); + + // Check numerical derivatives + expectedH1 = numericalDerivative21(bearing_proxy, x1, l1); + expectedH2 = numericalDerivative22(bearing_proxy, x1, l1); + EXPECT(assert_equal(expectedH1,actualH1)); + EXPECT(assert_equal(expectedH2,actualH2)); +} + /* ************************************************************************* */ TEST( Pose3, unicycle ) { // velocity in X should be X in inertial frame, rather than global frame Vector x_step = delta(6,3,1.0); - EXPECT(assert_equal(Pose3(Rot3::ypr(0,0,0), l1), expmap_default(x1, x_step), tol)); - EXPECT(assert_equal(Pose3(Rot3::ypr(0,0,0), Point3(2,1,0)), expmap_default(x2, x_step), tol)); - EXPECT(assert_equal(Pose3(Rot3::ypr(M_PI/4.0,0,0), Point3(2,2,0)), expmap_default(x3, sqrt(2.0) * x_step), tol)); + EXPECT(assert_equal(Pose3(Rot3::Ypr(0,0,0), l1), expmap_default(x1, x_step), tol)); + EXPECT(assert_equal(Pose3(Rot3::Ypr(0,0,0), Point3(2,1,0)), expmap_default(x2, x_step), tol)); + EXPECT(assert_equal(Pose3(Rot3::Ypr(M_PI/4.0,0,0), Point3(2,2,0)), expmap_default(x3, sqrt(2.0) * x_step), tol)); } /* ************************************************************************* */ @@ -699,7 +715,42 @@ TEST( Pose3, ExpmapDerivative1) { } /* ************************************************************************* */ -TEST( Pose3, LogmapDerivative1) { +TEST(Pose3, ExpmapDerivative2) { + // Iserles05an (Lie-group Methods) says: + // scalar is easy: d exp(a(t)) / dt = exp(a(t)) a'(t) + // matrix is hard: d exp(A(t)) / dt = exp(A(t)) dexp[-A(t)] A'(t) + // where A(t): T -> se(3) is a trajectory in the tangent space of SE(3) + // and dexp[A] is a linear map from 4*4 to 4*4 derivatives of se(3) + // Hence, the above matrix equation is typed: 4*4 = SE(3) * linear_map(4*4) + + // In GTSAM, we don't work with the Lie-algebra elements A directly, but with 6-vectors. + // xi is easy: d Expmap(xi(t)) / dt = ExmapDerivative[xi(t)] * xi'(t) + + // Let's verify the above formula. + + auto xi = [](double t) { + Vector6 v; + v << 2 * t, sin(t), 4 * t * t, 2 * t, sin(t), 4 * t * t; + return v; + }; + auto xi_dot = [](double t) { + Vector6 v; + v << 2, cos(t), 8 * t, 2, cos(t), 8 * t; + return v; + }; + + // We define a function T + auto T = [xi](double t) { return Pose3::Expmap(xi(t)); }; + + for (double t = -2.0; t < 2.0; t += 0.3) { + const Matrix expected = numericalDerivative11(T, t); + const Matrix actual = Pose3::ExpmapDerivative(xi(t)) * xi_dot(t); + CHECK(assert_equal(expected, actual, 1e-7)); + } +} + +/* ************************************************************************* */ +TEST( Pose3, LogmapDerivative) { Matrix6 actualH; Vector6 w; w << 0.1, 0.2, 0.3, 4.0, 5.0, 6.0; Pose3 p = Pose3::Expmap(w); diff --git a/gtsam/geometry/tests/testRot3.cpp b/gtsam/geometry/tests/testRot3.cpp index 349f87029..4b3c84e01 100644 --- a/gtsam/geometry/tests/testRot3.cpp +++ b/gtsam/geometry/tests/testRot3.cpp @@ -33,7 +33,7 @@ using namespace gtsam; GTSAM_CONCEPT_TESTABLE_INST(Rot3) GTSAM_CONCEPT_LIE_INST(Rot3) -static Rot3 R = Rot3::rodriguez(0.1, 0.4, 0.2); +static Rot3 R = Rot3::Rodrigues(0.1, 0.4, 0.2); static Point3 P(0.2, 0.7, -2.0); static double error = 1e-9, epsilon = 0.001; @@ -95,7 +95,7 @@ TEST( Rot3, equals) /* ************************************************************************* */ // Notice this uses J^2 whereas fast uses w*w', and has cos(t)*I + .... -Rot3 slow_but_correct_rodriguez(const Vector& w) { +Rot3 slow_but_correct_Rodrigues(const Vector& w) { double t = norm_2(w); Matrix J = skewSymmetric(w / t); if (t < 1e-5) return Rot3(); @@ -104,20 +104,20 @@ Rot3 slow_but_correct_rodriguez(const Vector& w) { } /* ************************************************************************* */ -TEST( Rot3, rodriguez) +TEST( Rot3, Rodrigues) { - Rot3 R1 = Rot3::rodriguez(epsilon, 0, 0); + Rot3 R1 = Rot3::Rodrigues(epsilon, 0, 0); Vector w = (Vector(3) << epsilon, 0., 0.).finished(); - Rot3 R2 = slow_but_correct_rodriguez(w); + Rot3 R2 = slow_but_correct_Rodrigues(w); CHECK(assert_equal(R2,R1)); } /* ************************************************************************* */ -TEST( Rot3, rodriguez2) +TEST( Rot3, Rodrigues2) { Vector axis = Vector3(0., 1., 0.); // rotation around Y double angle = 3.14 / 4.0; - Rot3 actual = Rot3::rodriguez(axis, angle); + Rot3 actual = Rot3::AxisAngle(axis, angle); Rot3 expected(0.707388, 0, 0.706825, 0, 1, 0, -0.706825, 0, 0.707388); @@ -125,26 +125,26 @@ TEST( Rot3, rodriguez2) } /* ************************************************************************* */ -TEST( Rot3, rodriguez3) +TEST( Rot3, Rodrigues3) { Vector w = Vector3(0.1, 0.2, 0.3); - Rot3 R1 = Rot3::rodriguez(w / norm_2(w), norm_2(w)); - Rot3 R2 = slow_but_correct_rodriguez(w); + Rot3 R1 = Rot3::AxisAngle(w / norm_2(w), norm_2(w)); + Rot3 R2 = slow_but_correct_Rodrigues(w); CHECK(assert_equal(R2,R1)); } /* ************************************************************************* */ -TEST( Rot3, rodriguez4) +TEST( Rot3, Rodrigues4) { Vector axis = Vector3(0., 0., 1.); // rotation around Z double angle = M_PI/2.0; - Rot3 actual = Rot3::rodriguez(axis, angle); + Rot3 actual = Rot3::AxisAngle(axis, angle); double c=cos(angle),s=sin(angle); Rot3 expected(c,-s, 0, s, c, 0, 0, 0, 1); CHECK(assert_equal(expected,actual)); - CHECK(assert_equal(slow_but_correct_rodriguez(axis*angle),actual)); + CHECK(assert_equal(slow_but_correct_Rodrigues(axis*angle),actual)); } /* ************************************************************************* */ @@ -168,7 +168,7 @@ TEST(Rot3, log) #define CHECK_OMEGA(X,Y,Z) \ w = (Vector(3) << (double)X, (double)Y, double(Z)).finished(); \ - R = Rot3::rodriguez(w); \ + R = Rot3::Rodrigues(w); \ EXPECT(assert_equal(w, Rot3::Logmap(R),1e-12)); // Check zero @@ -201,7 +201,7 @@ TEST(Rot3, log) // Windows and Linux have flipped sign in quaternion mode #if !defined(__APPLE__) && defined (GTSAM_USE_QUATERNIONS) w = (Vector(3) << x*PI, y*PI, z*PI).finished(); - R = Rot3::rodriguez(w); + R = Rot3::Rodrigues(w); EXPECT(assert_equal(Vector(-w), Rot3::Logmap(R),1e-12)); #else CHECK_OMEGA(x*PI,y*PI,z*PI) @@ -210,7 +210,7 @@ TEST(Rot3, log) // Check 360 degree rotations #define CHECK_OMEGA_ZERO(X,Y,Z) \ w = (Vector(3) << (double)X, (double)Y, double(Z)).finished(); \ - R = Rot3::rodriguez(w); \ + R = Rot3::Rodrigues(w); \ EXPECT(assert_equal(zero(3), Rot3::Logmap(R))); CHECK_OMEGA_ZERO( 2.0*PI, 0, 0) @@ -243,77 +243,11 @@ TEST(Rot3, retract_localCoordinates2) Vector d21 = t2.localCoordinates(t1); EXPECT(assert_equal(t1, t2.retract(d21))); } -/* ************************************************************************* */ -Vector w = Vector3(0.1, 0.27, -0.2); - -// Left trivialization Derivative of exp(w) wrpt w: -// How does exp(w) change when w changes? -// We find a y such that: exp(w) exp(y) = exp(w + dw) for dw --> 0 -// => y = log (exp(-w) * exp(w+dw)) -Vector3 testDexpL(const Vector3& dw) { - return Rot3::Logmap(Rot3::Expmap(-w) * Rot3::Expmap(w + dw)); -} - -TEST( Rot3, ExpmapDerivative) { - Matrix actualDexpL = Rot3::ExpmapDerivative(w); - Matrix expectedDexpL = numericalDerivative11(testDexpL, - Vector3::Zero(), 1e-2); - EXPECT(assert_equal(expectedDexpL, actualDexpL,1e-7)); - - Matrix actualDexpInvL = Rot3::LogmapDerivative(w); - EXPECT(assert_equal(expectedDexpL.inverse(), actualDexpInvL,1e-7)); -} - -/* ************************************************************************* */ -Vector3 thetahat(0.1, 0, 0.1); -TEST( Rot3, ExpmapDerivative2) -{ - Matrix Jexpected = numericalDerivative11( - boost::bind(&Rot3::Expmap, _1, boost::none), thetahat); - - Matrix Jactual = Rot3::ExpmapDerivative(thetahat); - CHECK(assert_equal(Jexpected, Jactual)); - - Matrix Jactual2 = Rot3::ExpmapDerivative(thetahat); - CHECK(assert_equal(Jexpected, Jactual2)); -} - -/* ************************************************************************* */ -TEST( Rot3, jacobianExpmap ) -{ - Matrix Jexpected = numericalDerivative11(boost::bind( - &Rot3::Expmap, _1, boost::none), thetahat); - Matrix3 Jactual; - const Rot3 R = Rot3::Expmap(thetahat, Jactual); - EXPECT(assert_equal(Jexpected, Jactual)); -} - -/* ************************************************************************* */ -TEST( Rot3, LogmapDerivative ) -{ - Rot3 R = Rot3::Expmap(thetahat); // some rotation - Matrix Jexpected = numericalDerivative11(boost::bind( - &Rot3::Logmap, _1, boost::none), R); - Matrix3 Jactual = Rot3::LogmapDerivative(thetahat); - EXPECT(assert_equal(Jexpected, Jactual)); -} - -/* ************************************************************************* */ -TEST( Rot3, jacobianLogmap ) -{ - Rot3 R = Rot3::Expmap(thetahat); // some rotation - Matrix Jexpected = numericalDerivative11(boost::bind( - &Rot3::Logmap, _1, boost::none), R); - Matrix3 Jactual; - Rot3::Logmap(R, Jactual); - EXPECT(assert_equal(Jexpected, Jactual)); -} - /* ************************************************************************* */ TEST(Rot3, manifold_expmap) { - Rot3 gR1 = Rot3::rodriguez(0.1, 0.4, 0.2); - Rot3 gR2 = Rot3::rodriguez(0.3, 0.1, 0.7); + Rot3 gR1 = Rot3::Rodrigues(0.1, 0.4, 0.2); + Rot3 gR2 = Rot3::Rodrigues(0.3, 0.1, 0.7); Rot3 origin; // log behaves correctly @@ -399,8 +333,8 @@ TEST( Rot3, unrotate) /* ************************************************************************* */ TEST( Rot3, compose ) { - Rot3 R1 = Rot3::rodriguez(0.1, 0.2, 0.3); - Rot3 R2 = Rot3::rodriguez(0.2, 0.3, 0.5); + Rot3 R1 = Rot3::Rodrigues(0.1, 0.2, 0.3); + Rot3 R2 = Rot3::Rodrigues(0.2, 0.3, 0.5); Rot3 expected = R1 * R2; Matrix actualH1, actualH2; @@ -419,7 +353,7 @@ TEST( Rot3, compose ) /* ************************************************************************* */ TEST( Rot3, inverse ) { - Rot3 R = Rot3::rodriguez(0.1, 0.2, 0.3); + Rot3 R = Rot3::Rodrigues(0.1, 0.2, 0.3); Rot3 I; Matrix3 actualH; @@ -444,13 +378,13 @@ TEST( Rot3, between ) 0.0, 0.0, 1.0).finished(); EXPECT(assert_equal(expectedr1, r1.matrix())); - Rot3 R = Rot3::rodriguez(0.1, 0.4, 0.2); + Rot3 R = Rot3::Rodrigues(0.1, 0.4, 0.2); Rot3 origin; EXPECT(assert_equal(R, origin.between(R))); EXPECT(assert_equal(R.inverse(), R.between(origin))); - Rot3 R1 = Rot3::rodriguez(0.1, 0.2, 0.3); - Rot3 R2 = Rot3::rodriguez(0.2, 0.3, 0.5); + Rot3 R1 = Rot3::Rodrigues(0.1, 0.2, 0.3); + Rot3 R2 = Rot3::Rodrigues(0.2, 0.3, 0.5); Rot3 expected = R1.inverse() * R2; Matrix actualH1, actualH2; @@ -501,17 +435,17 @@ TEST( Rot3, yaw_pitch_roll ) double t = 0.1; // yaw is around z axis - CHECK(assert_equal(Rot3::Rz(t),Rot3::yaw(t))); + CHECK(assert_equal(Rot3::Rz(t),Rot3::Yaw(t))); // pitch is around y axis - CHECK(assert_equal(Rot3::Ry(t),Rot3::pitch(t))); + CHECK(assert_equal(Rot3::Ry(t),Rot3::Pitch(t))); // roll is around x axis - CHECK(assert_equal(Rot3::Rx(t),Rot3::roll(t))); + CHECK(assert_equal(Rot3::Rx(t),Rot3::Roll(t))); // Check compound rotation - Rot3 expected = Rot3::yaw(0.1) * Rot3::pitch(0.2) * Rot3::roll(0.3); - CHECK(assert_equal(expected,Rot3::ypr(0.1,0.2,0.3))); + Rot3 expected = Rot3::Yaw(0.1) * Rot3::Pitch(0.2) * Rot3::Roll(0.3); + CHECK(assert_equal(expected,Rot3::Ypr(0.1,0.2,0.3))); CHECK(assert_equal((Vector)Vector3(0.1, 0.2, 0.3),expected.ypr())); } @@ -531,14 +465,14 @@ TEST( Rot3, RQ) CHECK(assert_equal(expected,R.xyz(),1e-6)); CHECK(assert_equal((Vector)Vector3(0.1,0.2,0.3),Rot3::RzRyRx(0.1,0.2,0.3).xyz())); - // Try using ypr call, asserting that Rot3::ypr(y,p,r).ypr()==[y;p;r] - CHECK(assert_equal((Vector)Vector3(0.1,0.2,0.3),Rot3::ypr(0.1,0.2,0.3).ypr())); - CHECK(assert_equal((Vector)Vector3(0.3,0.2,0.1),Rot3::ypr(0.1,0.2,0.3).rpy())); + // Try using ypr call, asserting that Rot3::Ypr(y,p,r).ypr()==[y;p;r] + CHECK(assert_equal((Vector)Vector3(0.1,0.2,0.3),Rot3::Ypr(0.1,0.2,0.3).ypr())); + CHECK(assert_equal((Vector)Vector3(0.3,0.2,0.1),Rot3::Ypr(0.1,0.2,0.3).rpy())); // Try ypr for pure yaw-pitch-roll matrices - CHECK(assert_equal((Vector)Vector3(0.1,0.0,0.0),Rot3::yaw (0.1).ypr())); - CHECK(assert_equal((Vector)Vector3(0.0,0.1,0.0),Rot3::pitch(0.1).ypr())); - CHECK(assert_equal((Vector)Vector3(0.0,0.0,0.1),Rot3::roll (0.1).ypr())); + CHECK(assert_equal((Vector)Vector3(0.1,0.0,0.0),Rot3::Yaw (0.1).ypr())); + CHECK(assert_equal((Vector)Vector3(0.0,0.1,0.0),Rot3::Pitch(0.1).ypr())); + CHECK(assert_equal((Vector)Vector3(0.0,0.0,0.1),Rot3::Roll (0.1).ypr())); // Try RQ to recover calibration from 3*3 sub-block of projection matrix Matrix K = (Matrix(3, 3) << 500.0, 0.0, 320.0, 0.0, 500.0, 240.0, 0.0, 0.0, 1.0).finished(); @@ -594,9 +528,9 @@ TEST(Rot3, quaternion) { // Check creating Rot3 from quaternion EXPECT(assert_equal(R1, Rot3(q1))); - EXPECT(assert_equal(R1, Rot3::quaternion(q1.w(), q1.x(), q1.y(), q1.z()))); + EXPECT(assert_equal(R1, Rot3::Quaternion(q1.w(), q1.x(), q1.y(), q1.z()))); EXPECT(assert_equal(R2, Rot3(q2))); - EXPECT(assert_equal(R2, Rot3::quaternion(q2.w(), q2.x(), q2.y(), q2.z()))); + EXPECT(assert_equal(R2, Rot3::Quaternion(q2.w(), q2.x(), q2.y(), q2.z()))); // Check converting Rot3 to quaterion EXPECT(assert_equal(Vector(R1.toQuaternion().coeffs()), Vector(q1.coeffs()))); @@ -652,8 +586,8 @@ TEST( Rot3, slerp) } //****************************************************************************** -Rot3 T1(Rot3::rodriguez(Vector3(0, 0, 1), 1)); -Rot3 T2(Rot3::rodriguez(Vector3(0, 1, 0), 2)); +Rot3 T1(Rot3::AxisAngle(Vector3(0, 0, 1), 1)); +Rot3 T2(Rot3::AxisAngle(Vector3(0, 1, 0), 2)); //****************************************************************************** TEST(Rot3 , Invariants) { diff --git a/gtsam/geometry/tests/testRot3M.cpp b/gtsam/geometry/tests/testRot3M.cpp index 12fb94bbc..d05356271 100644 --- a/gtsam/geometry/tests/testRot3M.cpp +++ b/gtsam/geometry/tests/testRot3M.cpp @@ -28,14 +28,14 @@ using namespace gtsam; GTSAM_CONCEPT_TESTABLE_INST(Rot3) GTSAM_CONCEPT_LIE_INST(Rot3) -static Rot3 R = Rot3::rodriguez(0.1, 0.4, 0.2); +static Rot3 R = Rot3::Rodrigues(0.1, 0.4, 0.2); static Point3 P(0.2, 0.7, -2.0); /* ************************************************************************* */ TEST(Rot3, manifold_cayley) { - Rot3 gR1 = Rot3::rodriguez(0.1, 0.4, 0.2); - Rot3 gR2 = Rot3::rodriguez(0.3, 0.1, 0.7); + Rot3 gR1 = Rot3::Rodrigues(0.1, 0.4, 0.2); + Rot3 gR2 = Rot3::Rodrigues(0.3, 0.1, 0.7); Rot3 origin; // log behaves correctly diff --git a/gtsam/geometry/tests/testSO3.cpp b/gtsam/geometry/tests/testSO3.cpp index bc32e0df0..68e87d5ba 100644 --- a/gtsam/geometry/tests/testSO3.cpp +++ b/gtsam/geometry/tests/testSO3.cpp @@ -1,6 +1,6 @@ /* ---------------------------------------------------------------------------- - * GTSAM Copyright 2010, Georgia Tech Research Corporation, + * 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) @@ -24,16 +24,14 @@ using namespace std; using namespace gtsam; //****************************************************************************** -TEST(SO3 , Concept) { - BOOST_CONCEPT_ASSERT((IsGroup)); - BOOST_CONCEPT_ASSERT((IsManifold)); - BOOST_CONCEPT_ASSERT((IsLieGroup)); +TEST(SO3, Concept) { + BOOST_CONCEPT_ASSERT((IsGroup)); + BOOST_CONCEPT_ASSERT((IsManifold)); + BOOST_CONCEPT_ASSERT((IsLieGroup)); } //****************************************************************************** -TEST(SO3 , Constructor) { - SO3 q(Eigen::AngleAxisd(1, Vector3(0, 0, 1))); -} +TEST(SO3, Constructor) { SO3 q(Eigen::AngleAxisd(1, Vector3(0, 0, 1))); } //****************************************************************************** SO3 id; @@ -42,46 +40,214 @@ SO3 R1(Eigen::AngleAxisd(0.1, z_axis)); SO3 R2(Eigen::AngleAxisd(0.2, z_axis)); //****************************************************************************** -TEST(SO3 , Local) { +TEST(SO3, Local) { Vector3 expected(0, 0, 0.1); Vector3 actual = traits::Local(R1, R2); - EXPECT(assert_equal((Vector)expected,actual)); + EXPECT(assert_equal((Vector)expected, actual)); } //****************************************************************************** -TEST(SO3 , Retract) { +TEST(SO3, Retract) { Vector3 v(0, 0, 0.1); SO3 actual = traits::Retract(R1, v); EXPECT(actual.isApprox(R2)); } //****************************************************************************** -TEST(SO3 , Invariants) { - EXPECT(check_group_invariants(id,id)); - EXPECT(check_group_invariants(id,R1)); - EXPECT(check_group_invariants(R2,id)); - EXPECT(check_group_invariants(R2,R1)); +TEST(SO3, Invariants) { + EXPECT(check_group_invariants(id, id)); + EXPECT(check_group_invariants(id, R1)); + EXPECT(check_group_invariants(R2, id)); + EXPECT(check_group_invariants(R2, R1)); - EXPECT(check_manifold_invariants(id,id)); - EXPECT(check_manifold_invariants(id,R1)); - EXPECT(check_manifold_invariants(R2,id)); - EXPECT(check_manifold_invariants(R2,R1)); + EXPECT(check_manifold_invariants(id, id)); + EXPECT(check_manifold_invariants(id, R1)); + EXPECT(check_manifold_invariants(R2, id)); + EXPECT(check_manifold_invariants(R2, R1)); } //****************************************************************************** -TEST(SO3 , LieGroupDerivatives) { - CHECK_LIE_GROUP_DERIVATIVES(id,id); - CHECK_LIE_GROUP_DERIVATIVES(id,R2); - CHECK_LIE_GROUP_DERIVATIVES(R2,id); - CHECK_LIE_GROUP_DERIVATIVES(R2,R1); +TEST(SO3, LieGroupDerivatives) { + CHECK_LIE_GROUP_DERIVATIVES(id, id); + CHECK_LIE_GROUP_DERIVATIVES(id, R2); + CHECK_LIE_GROUP_DERIVATIVES(R2, id); + CHECK_LIE_GROUP_DERIVATIVES(R2, R1); } //****************************************************************************** -TEST(SO3 , ChartDerivatives) { - CHECK_CHART_DERIVATIVES(id,id); - CHECK_CHART_DERIVATIVES(id,R2); - CHECK_CHART_DERIVATIVES(R2,id); - CHECK_CHART_DERIVATIVES(R2,R1); +TEST(SO3, ChartDerivatives) { + CHECK_CHART_DERIVATIVES(id, id); + CHECK_CHART_DERIVATIVES(id, R2); + CHECK_CHART_DERIVATIVES(R2, id); + CHECK_CHART_DERIVATIVES(R2, R1); +} + +/* ************************************************************************* */ +namespace exmap_derivative { +static const Vector3 w(0.1, 0.27, -0.2); +} +// Left trivialized Derivative of exp(w) wrpt w: +// How does exp(w) change when w changes? +// We find a y such that: exp(w) exp(y) = exp(w + dw) for dw --> 0 +// => y = log (exp(-w) * exp(w+dw)) +Vector3 testDexpL(const Vector3& dw) { + using exmap_derivative::w; + return SO3::Logmap(SO3::Expmap(-w) * SO3::Expmap(w + dw)); +} + +TEST(SO3, ExpmapDerivative) { + using exmap_derivative::w; + const Matrix actualDexpL = SO3::ExpmapDerivative(w); + const Matrix expectedDexpL = + numericalDerivative11(testDexpL, Vector3::Zero(), 1e-2); + EXPECT(assert_equal(expectedDexpL, actualDexpL, 1e-7)); + + const Matrix actualDexpInvL = SO3::LogmapDerivative(w); + EXPECT(assert_equal(expectedDexpL.inverse(), actualDexpInvL, 1e-7)); +} + +/* ************************************************************************* */ +TEST(SO3, ExpmapDerivative2) { + const Vector3 theta(0.1, 0, 0.1); + const Matrix Jexpected = numericalDerivative11( + boost::bind(&SO3::Expmap, _1, boost::none), theta); + + CHECK(assert_equal(Jexpected, SO3::ExpmapDerivative(theta))); + CHECK(assert_equal(Matrix3(Jexpected.transpose()), + SO3::ExpmapDerivative(-theta))); +} + +/* ************************************************************************* */ +TEST(SO3, ExpmapDerivative3) { + const Vector3 theta(10, 20, 30); + const Matrix Jexpected = numericalDerivative11( + boost::bind(&SO3::Expmap, _1, boost::none), theta); + + CHECK(assert_equal(Jexpected, SO3::ExpmapDerivative(theta))); + CHECK(assert_equal(Matrix3(Jexpected.transpose()), + SO3::ExpmapDerivative(-theta))); +} + +/* ************************************************************************* */ +TEST(SO3, ExpmapDerivative4) { + // Iserles05an (Lie-group Methods) says: + // scalar is easy: d exp(a(t)) / dt = exp(a(t)) a'(t) + // matrix is hard: d exp(A(t)) / dt = exp(A(t)) dexp[-A(t)] A'(t) + // where A(t): R -> so(3) is a trajectory in the tangent space of SO(3) + // and dexp[A] is a linear map from 3*3 to 3*3 derivatives of se(3) + // Hence, the above matrix equation is typed: 3*3 = SO(3) * linear_map(3*3) + + // In GTSAM, we don't work with the skew-symmetric matrices A directly, but + // with 3-vectors. + // omega is easy: d Expmap(w(t)) / dt = ExmapDerivative[w(t)] * w'(t) + + // Let's verify the above formula. + + auto w = [](double t) { return Vector3(2 * t, sin(t), 4 * t * t); }; + auto w_dot = [](double t) { return Vector3(2, cos(t), 8 * t); }; + + // We define a function R + auto R = [w](double t) { return SO3::Expmap(w(t)); }; + + for (double t = -2.0; t < 2.0; t += 0.3) { + const Matrix expected = numericalDerivative11(R, t); + const Matrix actual = SO3::ExpmapDerivative(w(t)) * w_dot(t); + CHECK(assert_equal(expected, actual, 1e-7)); + } +} + +/* ************************************************************************* */ +TEST(SO3, ExpmapDerivative5) { + auto w = [](double t) { return Vector3(2 * t, sin(t), 4 * t * t); }; + auto w_dot = [](double t) { return Vector3(2, cos(t), 8 * t); }; + + // Now define R as mapping local coordinates to neighborhood around R0. + const SO3 R0 = SO3::Expmap(Vector3(0.1, 0.4, 0.2)); + auto R = [R0, w](double t) { return R0.expmap(w(t)); }; + + for (double t = -2.0; t < 2.0; t += 0.3) { + const Matrix expected = numericalDerivative11(R, t); + const Matrix actual = SO3::ExpmapDerivative(w(t)) * w_dot(t); + CHECK(assert_equal(expected, actual, 1e-7)); + } +} + +/* ************************************************************************* */ +TEST(SO3, ExpmapDerivative6) { + const Vector3 thetahat(0.1, 0, 0.1); + const Matrix Jexpected = numericalDerivative11( + boost::bind(&SO3::Expmap, _1, boost::none), thetahat); + Matrix3 Jactual; + SO3::Expmap(thetahat, Jactual); + EXPECT(assert_equal(Jexpected, Jactual)); +} + +/* ************************************************************************* */ +TEST(SO3, LogmapDerivative) { + const Vector3 thetahat(0.1, 0, 0.1); + const SO3 R = SO3::Expmap(thetahat); // some rotation + const Matrix Jexpected = numericalDerivative11( + boost::bind(&SO3::Logmap, _1, boost::none), R); + const Matrix3 Jactual = SO3::LogmapDerivative(thetahat); + EXPECT(assert_equal(Jexpected, Jactual)); +} + +/* ************************************************************************* */ +TEST(SO3, JacobianLogmap) { + const Vector3 thetahat(0.1, 0, 0.1); + const SO3 R = SO3::Expmap(thetahat); // some rotation + const Matrix Jexpected = numericalDerivative11( + boost::bind(&SO3::Logmap, _1, boost::none), R); + Matrix3 Jactual; + SO3::Logmap(R, Jactual); + EXPECT(assert_equal(Jexpected, Jactual)); +} + +/* ************************************************************************* */ +TEST(SO3, ApplyDexp) { + Matrix aH1, aH2; + for (bool nearZeroApprox : {true, false}) { + boost::function f = + [=](const Vector3& omega, const Vector3& v) { + return so3::DexpFunctor(omega, nearZeroApprox).applyDexp(v); + }; + for (Vector3 omega : {Vector3(0, 0, 0), Vector3(1, 0, 0), Vector3(0, 1, 0), + Vector3(0, 0, 1), Vector3(0.1, 0.2, 0.3)}) { + so3::DexpFunctor local(omega, nearZeroApprox); + for (Vector3 v : {Vector3(1, 0, 0), Vector3(0, 1, 0), Vector3(0, 0, 1), + Vector3(0.4, 0.3, 0.2)}) { + EXPECT(assert_equal(Vector3(local.dexp() * v), + local.applyDexp(v, aH1, aH2))); + EXPECT(assert_equal(numericalDerivative21(f, omega, v), aH1)); + EXPECT(assert_equal(numericalDerivative22(f, omega, v), aH2)); + EXPECT(assert_equal(local.dexp(), aH2)); + } + } + } +} + +/* ************************************************************************* */ +TEST(SO3, ApplyInvDexp) { + Matrix aH1, aH2; + for (bool nearZeroApprox : {true, false}) { + boost::function f = + [=](const Vector3& omega, const Vector3& v) { + return so3::DexpFunctor(omega, nearZeroApprox).applyInvDexp(v); + }; + for (Vector3 omega : {Vector3(0, 0, 0), Vector3(1, 0, 0), Vector3(0, 1, 0), + Vector3(0, 0, 1), Vector3(0.1, 0.2, 0.3)}) { + so3::DexpFunctor local(omega, nearZeroApprox); + Matrix invDexp = local.dexp().inverse(); + for (Vector3 v : {Vector3(1, 0, 0), Vector3(0, 1, 0), Vector3(0, 0, 1), + Vector3(0.4, 0.3, 0.2)}) { + EXPECT(assert_equal(Vector3(invDexp * v), + local.applyInvDexp(v, aH1, aH2))); + EXPECT(assert_equal(numericalDerivative21(f, omega, v), aH1)); + EXPECT(assert_equal(numericalDerivative22(f, omega, v), aH2)); + EXPECT(assert_equal(invDexp, aH2)); + } + } + } } //****************************************************************************** @@ -90,4 +256,3 @@ int main() { return TestRegistry::runAllTests(tr); } //****************************************************************************** - diff --git a/gtsam/geometry/tests/testSimpleCamera.cpp b/gtsam/geometry/tests/testSimpleCamera.cpp index 71979481c..515542298 100644 --- a/gtsam/geometry/tests/testSimpleCamera.cpp +++ b/gtsam/geometry/tests/testSimpleCamera.cpp @@ -28,7 +28,7 @@ using namespace gtsam; static const Cal3_S2 K(625, 625, 0, 0, 0); -static const Pose3 pose1((Matrix)(Matrix(3,3) << +static const Pose3 pose1((Matrix3() << 1., 0., 0., 0.,-1., 0., 0., 0.,-1. diff --git a/gtsam/geometry/tests/testTriangulation.cpp b/gtsam/geometry/tests/testTriangulation.cpp index f986cca1d..c3df95abc 100644 --- a/gtsam/geometry/tests/testTriangulation.cpp +++ b/gtsam/geometry/tests/testTriangulation.cpp @@ -17,9 +17,16 @@ */ #include +#include +#include +#include #include +#include +#include +#include #include + #include #include @@ -33,7 +40,7 @@ static const boost::shared_ptr sharedCal = // boost::make_shared(1500, 1200, 0, 640, 480); // Looking along X-axis, 1 meter above ground plane (x-y) -static const Rot3 upright = Rot3::ypr(-M_PI / 2, 0., -M_PI / 2); +static const Rot3 upright = Rot3::Ypr(-M_PI / 2, 0., -M_PI / 2); static const Pose3 pose1 = Pose3(upright, gtsam::Point3(0, 0, 1)); PinholeCamera camera1(pose1, *sharedCal); @@ -49,6 +56,7 @@ Point2 z1 = camera1.project(landmark); Point2 z2 = camera2.project(landmark); //****************************************************************************** +// Simple test with a well-behaved two camera situation TEST( triangulation, twoPoses) { vector poses; @@ -57,24 +65,37 @@ TEST( triangulation, twoPoses) { poses += pose1, pose2; measurements += z1, z2; - bool optimize = true; double rank_tol = 1e-9; - boost::optional triangulated_landmark = triangulatePoint3(poses, - sharedCal, measurements, rank_tol, optimize); - EXPECT(assert_equal(landmark, *triangulated_landmark, 1e-2)); + // 1. Test simple DLT, perfect in no noise situation + bool optimize = false; + boost::optional actual1 = // + triangulatePoint3(poses, sharedCal, measurements, rank_tol, optimize); + EXPECT(assert_equal(landmark, *actual1, 1e-7)); - // 2. Add some noise and try again: result should be ~ (4.995, 0.499167, 1.19814) + // 2. test with optimization on, same answer + optimize = true; + boost::optional actual2 = // + triangulatePoint3(poses, sharedCal, measurements, rank_tol, optimize); + EXPECT(assert_equal(landmark, *actual2, 1e-7)); + + // 3. Add some noise and try again: result should be ~ (4.995, 0.499167, 1.19814) measurements.at(0) += Point2(0.1, 0.5); measurements.at(1) += Point2(-0.2, 0.3); + optimize = false; + boost::optional actual3 = // + triangulatePoint3(poses, sharedCal, measurements, rank_tol, optimize); + EXPECT(assert_equal(Point3(4.995, 0.499167, 1.19814), *actual3, 1e-4)); - boost::optional triangulated_landmark_noise = triangulatePoint3(poses, - sharedCal, measurements, rank_tol, optimize); - EXPECT(assert_equal(landmark, *triangulated_landmark_noise, 1e-2)); + // 4. Now with optimization on + optimize = true; + boost::optional actual4 = // + triangulatePoint3(poses, sharedCal, measurements, rank_tol, optimize); + EXPECT(assert_equal(Point3(4.995, 0.499167, 1.19814), *actual4, 1e-4)); } //****************************************************************************** - +// Similar, but now with Bundler calibration TEST( triangulation, twoPosesBundler) { boost::shared_ptr bundlerCal = // @@ -95,17 +116,17 @@ TEST( triangulation, twoPosesBundler) { bool optimize = true; double rank_tol = 1e-9; - boost::optional triangulated_landmark = triangulatePoint3(poses, - bundlerCal, measurements, rank_tol, optimize); - EXPECT(assert_equal(landmark, *triangulated_landmark, 1e-2)); + boost::optional actual = // + triangulatePoint3(poses, bundlerCal, measurements, rank_tol, optimize); + EXPECT(assert_equal(landmark, *actual, 1e-7)); - // 2. Add some noise and try again: result should be ~ (4.995, 0.499167, 1.19814) + // Add some noise and try again measurements.at(0) += Point2(0.1, 0.5); measurements.at(1) += Point2(-0.2, 0.3); - boost::optional triangulated_landmark_noise = triangulatePoint3(poses, - bundlerCal, measurements, rank_tol, optimize); - EXPECT(assert_equal(landmark, *triangulated_landmark_noise, 1e-2)); + boost::optional actual2 = // + triangulatePoint3(poses, bundlerCal, measurements, rank_tol, optimize); + EXPECT(assert_equal(Point3(4.995, 0.499167, 1.19847), *actual2, 1e-4)); } //****************************************************************************** @@ -116,20 +137,20 @@ TEST( triangulation, fourPoses) { poses += pose1, pose2; measurements += z1, z2; - boost::optional triangulated_landmark = triangulatePoint3(poses, - sharedCal, measurements); - EXPECT(assert_equal(landmark, *triangulated_landmark, 1e-2)); + boost::optional actual = triangulatePoint3(poses, sharedCal, + measurements); + EXPECT(assert_equal(landmark, *actual, 1e-2)); // 2. Add some noise and try again: result should be ~ (4.995, 0.499167, 1.19814) measurements.at(0) += Point2(0.1, 0.5); measurements.at(1) += Point2(-0.2, 0.3); - boost::optional triangulated_landmark_noise = // + boost::optional actual2 = // triangulatePoint3(poses, sharedCal, measurements); - EXPECT(assert_equal(landmark, *triangulated_landmark_noise, 1e-2)); + EXPECT(assert_equal(landmark, *actual2, 1e-2)); // 3. Add a slightly rotated third camera above, again with measurement noise - Pose3 pose3 = pose1 * Pose3(Rot3::ypr(0.1, 0.2, 0.1), Point3(0.1, -2, -.1)); + Pose3 pose3 = pose1 * Pose3(Rot3::Ypr(0.1, 0.2, 0.1), Point3(0.1, -2, -.1)); SimpleCamera camera3(pose3, *sharedCal); Point2 z3 = camera3.project(landmark); @@ -146,11 +167,11 @@ TEST( triangulation, fourPoses) { EXPECT(assert_equal(landmark, *triangulated_3cameras_opt, 1e-2)); // 4. Test failure: Add a 4th camera facing the wrong way - Pose3 pose4 = Pose3(Rot3::ypr(M_PI / 2, 0., -M_PI / 2), Point3(0, 0, 1)); + Pose3 pose4 = Pose3(Rot3::Ypr(M_PI / 2, 0., -M_PI / 2), Point3(0, 0, 1)); SimpleCamera camera4(pose4, *sharedCal); #ifdef GTSAM_THROW_CHEIRALITY_EXCEPTION - CHECK_EXCEPTION(camera4.project(landmark);, CheiralityException); + CHECK_EXCEPTION(camera4.project(landmark), CheiralityException); poses += pose4; measurements += Point2(400, 400); @@ -180,20 +201,20 @@ TEST( triangulation, fourPoses_distinct_Ks) { cameras += camera1, camera2; measurements += z1, z2; - boost::optional triangulated_landmark = // + boost::optional actual = // triangulatePoint3(cameras, measurements); - EXPECT(assert_equal(landmark, *triangulated_landmark, 1e-2)); + EXPECT(assert_equal(landmark, *actual, 1e-2)); // 2. Add some noise and try again: result should be ~ (4.995, 0.499167, 1.19814) measurements.at(0) += Point2(0.1, 0.5); measurements.at(1) += Point2(-0.2, 0.3); - boost::optional triangulated_landmark_noise = // + boost::optional actual2 = // triangulatePoint3(cameras, measurements); - EXPECT(assert_equal(landmark, *triangulated_landmark_noise, 1e-2)); + EXPECT(assert_equal(landmark, *actual2, 1e-2)); // 3. Add a slightly rotated third camera above, again with measurement noise - Pose3 pose3 = pose1 * Pose3(Rot3::ypr(0.1, 0.2, 0.1), Point3(0.1, -2, -.1)); + Pose3 pose3 = pose1 * Pose3(Rot3::Ypr(0.1, 0.2, 0.1), Point3(0.1, -2, -.1)); Cal3_S2 K3(700, 500, 0, 640, 480); SimpleCamera camera3(pose3, K3); Point2 z3 = camera3.project(landmark); @@ -211,12 +232,12 @@ TEST( triangulation, fourPoses_distinct_Ks) { EXPECT(assert_equal(landmark, *triangulated_3cameras_opt, 1e-2)); // 4. Test failure: Add a 4th camera facing the wrong way - Pose3 pose4 = Pose3(Rot3::ypr(M_PI / 2, 0., -M_PI / 2), Point3(0, 0, 1)); + Pose3 pose4 = Pose3(Rot3::Ypr(M_PI / 2, 0., -M_PI / 2), Point3(0, 0, 1)); Cal3_S2 K4(700, 500, 0, 640, 480); SimpleCamera camera4(pose4, K4); #ifdef GTSAM_THROW_CHEIRALITY_EXCEPTION - CHECK_EXCEPTION(camera4.project(landmark);, CheiralityException); + CHECK_EXCEPTION(camera4.project(landmark), CheiralityException); cameras += camera4; measurements += Point2(400, 400); @@ -244,23 +265,119 @@ TEST( triangulation, twoIdenticalPoses) { } //****************************************************************************** -/* - TEST( triangulation, onePose) { - // we expect this test to fail with a TriangulationUnderconstrainedException - // because there's only one camera observation +TEST( triangulation, onePose) { + // we expect this test to fail with a TriangulationUnderconstrainedException + // because there's only one camera observation - Cal3_S2 *sharedCal(1500, 1200, 0, 640, 480); + vector poses; + vector measurements; - vector poses; - vector measurements; + poses += Pose3(); + measurements += Point2(); - poses += Pose3(); - measurements += Point2(); + CHECK_EXCEPTION(triangulatePoint3(poses, sharedCal, measurements), + TriangulationUnderconstrainedException); +} - CHECK_EXCEPTION(triangulatePoint3(poses, measurements, *sharedCal), - TriangulationUnderconstrainedException); - } - */ +//****************************************************************************** +TEST( triangulation, StereotriangulateNonlinear ) { + + Cal3_S2Stereo::shared_ptr stereoK(new Cal3_S2Stereo(1733.75, 1733.75, 0, 689.645, 508.835, 0.0699612)); + + // two camera poses m1, m2 + Matrix4 m1, m2; + m1 << 0.796888717, 0.603404026, -0.0295271487, 46.6673779, + 0.592783835, -0.77156583, 0.230856632, 66.2186159, + 0.116517574, -0.201470143, -0.9725393, -4.28382528, + 0, 0, 0, 1; + + m2 << -0.955959025, -0.29288915, -0.0189328569, 45.7169799, + -0.29277519, 0.947083213, 0.131587097, 65.843136, + -0.0206094928, 0.131334858, -0.991123524, -4.3525033, + 0, 0, 0, 1; + + typedef CameraSet Cameras; + Cameras cameras; + cameras.push_back(StereoCamera(Pose3(m1), stereoK)); + cameras.push_back(StereoCamera(Pose3(m2), stereoK)); + + vector measurements; + measurements += StereoPoint2(226.936, 175.212, 424.469); + measurements += StereoPoint2(339.571, 285.547, 669.973); + + Point3 initial = Point3(46.0536958, 66.4621179, -6.56285929); // error: 96.5715555191 + + Point3 actual = triangulateNonlinear(cameras, measurements, initial); + + Point3 expected(46.0484569, 66.4710686, -6.55046613); // error: 0.763510644187 + + EXPECT(assert_equal(expected, actual, 1e-4)); + + + // regular stereo factor comparison - expect very similar result as above + { + typedef GenericStereoFactor StereoFactor; + + Values values; + values.insert(Symbol('x', 1), Pose3(m1)); + values.insert(Symbol('x', 2), Pose3(m2)); + values.insert(Symbol('l', 1), initial); + + NonlinearFactorGraph graph; + static SharedNoiseModel unit(noiseModel::Unit::Create(3)); + graph.push_back(StereoFactor::shared_ptr(new StereoFactor(measurements[0], unit, Symbol('x',1), Symbol('l',1), stereoK))); + graph.push_back(StereoFactor::shared_ptr(new StereoFactor(measurements[1], unit, Symbol('x',2), Symbol('l',1), stereoK))); + + const SharedDiagonal posePrior = noiseModel::Isotropic::Sigma(6, 1e-9); + graph.push_back(PriorFactor(Symbol('x',1), Pose3(m1), posePrior)); + graph.push_back(PriorFactor(Symbol('x',2), Pose3(m2), posePrior)); + + LevenbergMarquardtOptimizer optimizer(graph, values); + Values result = optimizer.optimize(); + + EXPECT(assert_equal(expected, result.at(Symbol('l',1)), 1e-4)); + } + + // use Triangulation Factor directly - expect same result as above + { + Values values; + values.insert(Symbol('l', 1), initial); + + NonlinearFactorGraph graph; + static SharedNoiseModel unit(noiseModel::Unit::Create(3)); + + graph.push_back(TriangulationFactor(cameras[0], measurements[0], unit, Symbol('l',1))); + graph.push_back(TriangulationFactor(cameras[1], measurements[1], unit, Symbol('l',1))); + + LevenbergMarquardtOptimizer optimizer(graph, values); + Values result = optimizer.optimize(); + + EXPECT(assert_equal(expected, result.at(Symbol('l',1)), 1e-4)); + } + + // use ExpressionFactor - expect same result as above + { + Values values; + values.insert(Symbol('l', 1), initial); + + NonlinearFactorGraph graph; + static SharedNoiseModel unit(noiseModel::Unit::Create(3)); + + Expression point_(Symbol('l',1)); + Expression camera0_(cameras[0]); + Expression camera1_(cameras[1]); + Expression project0_(camera0_, &StereoCamera::project2, point_); + Expression project1_(camera1_, &StereoCamera::project2, point_); + + graph.addExpressionFactor(unit, measurements[0], project0_); + graph.addExpressionFactor(unit, measurements[1], project1_); + + LevenbergMarquardtOptimizer optimizer(graph, values); + Values result = optimizer.optimize(); + + EXPECT(assert_equal(expected, result.at(Symbol('l',1)), 1e-4)); + } +} //****************************************************************************** int main() { diff --git a/gtsam/geometry/tests/testUnit3.cpp b/gtsam/geometry/tests/testUnit3.cpp index 1d0c28ded..dbe315807 100644 --- a/gtsam/geometry/tests/testUnit3.cpp +++ b/gtsam/geometry/tests/testUnit3.cpp @@ -18,21 +18,30 @@ * @brief Tests the Unit3 class */ -#include -#include #include #include +#include +#include +#include +#include +#include +#include +#include +#include + + #include + #include #include #include -//#include #include #include using namespace boost::assign; using namespace gtsam; using namespace std; +using gtsam::symbol_shorthand::U; GTSAM_CONCEPT_TESTABLE_INST(Unit3) GTSAM_CONCEPT_MANIFOLD_INST(Unit3) @@ -41,6 +50,7 @@ GTSAM_CONCEPT_MANIFOLD_INST(Unit3) Point3 point3_(const Unit3& p) { return p.point3(); } + TEST(Unit3, point3) { vector ps; ps += Point3(1, 0, 0), Point3(0, 1, 0), Point3(0, 0, 1), Point3(1, 1, 0) @@ -60,7 +70,7 @@ static Unit3 rotate_(const Rot3& R, const Unit3& p) { } TEST(Unit3, rotate) { - Rot3 R = Rot3::yaw(0.5); + Rot3 R = Rot3::Yaw(0.5); Unit3 p(1, 0, 0); Unit3 expected = Unit3(R.column(1)); Unit3 actual = R * p; @@ -85,11 +95,12 @@ static Unit3 unrotate_(const Rot3& R, const Unit3& p) { } TEST(Unit3, unrotate) { - Rot3 R = Rot3::yaw(-M_PI / 4.0); + Rot3 R = Rot3::Yaw(-M_PI / 4.0); Unit3 p(1, 0, 0); Unit3 expected = Unit3(1, 1, 0); Unit3 actual = R.unrotate(p); EXPECT(assert_equal(expected, actual, 1e-8)); + Matrix actualH, expectedH; // Use numerical derivatives to calculate the expected Jacobian { @@ -104,6 +115,37 @@ TEST(Unit3, unrotate) { } } +TEST(Unit3, dot) { + Unit3 p(1, 0.2, 0.3); + Unit3 q = p.retract(Vector2(0.5, 0)); + Unit3 r = p.retract(Vector2(0.8, 0)); + Unit3 t = p.retract(Vector2(0, 0.3)); + EXPECT(assert_equal(1.0, p.dot(p), 1e-8)); + EXPECT(assert_equal(0.877583, p.dot(q), 1e-5)); + EXPECT(assert_equal(0.696707, p.dot(r), 1e-5)); + EXPECT(assert_equal(0.955336, p.dot(t), 1e-5)); + + // Use numerical derivatives to calculate the expected Jacobians + Matrix H1, H2; + boost::function f = boost::bind(&Unit3::dot, _1, _2, // + boost::none, boost::none); + { + p.dot(q, H1, H2); + EXPECT(assert_equal(numericalDerivative21(f, p, q), H1, 1e-9)); + EXPECT(assert_equal(numericalDerivative22(f, p, q), H2, 1e-9)); + } + { + p.dot(r, H1, H2); + EXPECT(assert_equal(numericalDerivative21(f, p, r), H1, 1e-9)); + EXPECT(assert_equal(numericalDerivative22(f, p, r), H2, 1e-9)); + } + { + p.dot(t, H1, H2); + EXPECT(assert_equal(numericalDerivative21(f, p, t), H1, 1e-9)); + EXPECT(assert_equal(numericalDerivative22(f, p, t), H2, 1e-9)); + } +} + //******************************************************************************* TEST(Unit3, error) { Unit3 p(1, 0, 0), q = p.retract(Vector2(0.5, 0)), // @@ -128,6 +170,45 @@ TEST(Unit3, error) { } } +//******************************************************************************* +TEST(Unit3, error2) { + Unit3 p(0.1, -0.2, 0.8); + Unit3 q = p.retract(Vector2(0.2, -0.1)); + Unit3 r = p.retract(Vector2(0.8, 0)); + + // Hard-coded as simple regression values + EXPECT(assert_equal((Vector)(Vector2(0.0, 0.0)), p.errorVector(p), 1e-8)); + EXPECT(assert_equal((Vector)(Vector2(0.198337495, -0.0991687475)), p.errorVector(q), 1e-5)); + EXPECT(assert_equal((Vector)(Vector2(0.717356, 0)), p.errorVector(r), 1e-5)); + + Matrix actual, expected; + // Use numerical derivatives to calculate the expected Jacobian + { + expected = numericalDerivative21( + boost::bind(&Unit3::errorVector, _1, _2, boost::none, boost::none), p, q); + p.errorVector(q, actual, boost::none); + EXPECT(assert_equal(expected, actual, 1e-9)); + } + { + expected = numericalDerivative21( + boost::bind(&Unit3::errorVector, _1, _2, boost::none, boost::none), p, r); + p.errorVector(r, actual, boost::none); + EXPECT(assert_equal(expected, actual, 1e-9)); + } + { + expected = numericalDerivative22( + boost::bind(&Unit3::errorVector, _1, _2, boost::none, boost::none), p, q); + p.errorVector(q, boost::none, actual); + EXPECT(assert_equal(expected, actual, 1e-9)); + } + { + expected = numericalDerivative22( + boost::bind(&Unit3::errorVector, _1, _2, boost::none, boost::none), p, r); + p.errorVector(r, boost::none, actual); + EXPECT(assert_equal(expected, actual, 1e-9)); + } +} + //******************************************************************************* TEST(Unit3, distance) { Unit3 p(1, 0, 0), q = p.retract(Vector2(0.5, 0)), // @@ -159,172 +240,139 @@ TEST(Unit3, localCoordinates0) { EXPECT(assert_equal(zero(2), actual, 1e-8)); } -//******************************************************************************* -TEST(Unit3, localCoordinates1) { - Unit3 p, q(1, 6.12385e-21, 0); - Vector actual = p.localCoordinates(q); - CHECK(assert_equal(zero(2), actual, 1e-8)); +TEST(Unit3, localCoordinates) { + { + Unit3 p, q; + Vector2 expected = Vector2::Zero(); + Vector2 actual = p.localCoordinates(q); + EXPECT(assert_equal(zero(2), actual, 1e-8)); + EXPECT(assert_equal(q, p.retract(expected), 1e-8)); + } + { + Unit3 p, q(1, 6.12385e-21, 0); + Vector2 expected = Vector2::Zero(); + Vector2 actual = p.localCoordinates(q); + EXPECT(assert_equal(zero(2), actual, 1e-8)); + EXPECT(assert_equal(q, p.retract(expected), 1e-8)); + } + { + Unit3 p, q(-1, 0, 0); + Vector2 expected(M_PI, 0); + Vector2 actual = p.localCoordinates(q); + EXPECT(assert_equal(expected, actual, 1e-8)); + EXPECT(assert_equal(q, p.retract(expected), 1e-8)); + } + { + Unit3 p, q(0, 1, 0); + Vector2 expected(0,-M_PI_2); + Vector2 actual = p.localCoordinates(q); + EXPECT(assert_equal(expected, actual, 1e-8)); + EXPECT(assert_equal(q, p.retract(expected), 1e-8)); + } + { + Unit3 p, q(0, -1, 0); + Vector2 expected(0, M_PI_2); + Vector2 actual = p.localCoordinates(q); + EXPECT(assert_equal(expected, actual, 1e-8)); + EXPECT(assert_equal(q, p.retract(expected), 1e-8)); + } + { + Unit3 p(0,1,0), q(0,-1,0); + Vector2 actual = p.localCoordinates(q); + EXPECT(assert_equal(q, p.retract(actual), 1e-8)); + } + { + Unit3 p(0,0,1), q(0,0,-1); + Vector2 actual = p.localCoordinates(q); + EXPECT(assert_equal(q, p.retract(actual), 1e-8)); + } + + double twist = 1e-4; + { + Unit3 p(0, 1, 0), q(0 - twist, -1 + twist, 0); + Vector2 actual = p.localCoordinates(q); + EXPECT(actual(0) < 1e-2); + EXPECT(actual(1) > M_PI - 1e-2) + } + { + Unit3 p(0, 1, 0), q(0 + twist, -1 - twist, 0); + Vector2 actual = p.localCoordinates(q); + EXPECT(actual(0) < 1e-2); + EXPECT(actual(1) < -M_PI + 1e-2) + } } //******************************************************************************* -TEST(Unit3, localCoordinates2) { - Unit3 p, q(-1, 0, 0); - Vector expected = (Vector(2) << M_PI, 0).finished(); - Vector actual = p.localCoordinates(q); - CHECK(assert_equal(expected, actual, 1e-8)); +// Wrapper to make basis return a vector6 so we can test numerical derivatives. +Vector6 BasisTest(const Unit3& p, OptionalJacobian<6, 2> H) { + Matrix32 B = p.basis(H); + Vector6 B_vec; + B_vec << B.col(0), B.col(1); + return B_vec; } -//******************************************************************************* TEST(Unit3, basis) { - Unit3 p; + Unit3 p(0.1, -0.2, 0.9); + Matrix expected(3, 2); - expected << 0, 0, 0, -1, 1, 0; - Matrix actual = p.basis(); - EXPECT(assert_equal(expected, actual, 1e-8)); + expected << 0.0, -0.994169047, 0.97618706, + -0.0233922129, 0.216930458, 0.105264958; + + Matrix62 actualH; + Matrix actual = p.basis(actualH); + EXPECT(assert_equal(expected, actual, 1e-6)); + + Matrix62 expectedH = numericalDerivative11( + boost::bind(BasisTest, _1, boost::none), p); + EXPECT(assert_equal(expectedH, actualH, 1e-8)); +} + +//******************************************************************************* +/// Check the basis derivatives of a bunch of random Unit3s. +TEST(Unit3, basis_derivatives) { + int num_tests = 100; + boost::mt19937 rng(42); + for (int i = 0; i < num_tests; i++) { + Unit3 p = Unit3::Random(rng); + + Matrix62 actualH; + p.basis(actualH); + + Matrix62 expectedH = numericalDerivative11( + boost::bind(BasisTest, _1, boost::none), p); + EXPECT(assert_equal(expectedH, actualH, 1e-8)); + } } //******************************************************************************* TEST(Unit3, retract) { - Unit3 p; - Vector v(2); - v << 0.5, 0; - Unit3 expected(0.877583, 0, 0.479426); - Unit3 actual = p.retract(v); - EXPECT(assert_equal(expected, actual, 1e-6)); - EXPECT(assert_equal(v, p.localCoordinates(actual), 1e-8)); + { + Unit3 p; + Vector2 v(0.5, 0); + Unit3 expected(0.877583, 0, 0.479426); + Unit3 actual = p.retract(v); + EXPECT(assert_equal(expected, actual, 1e-6)); + EXPECT(assert_equal(v, p.localCoordinates(actual), 1e-8)); + } + { + Unit3 p; + Vector2 v(0, 0); + Unit3 actual = p.retract(v); + EXPECT(assert_equal(p, actual, 1e-6)); + EXPECT(assert_equal(v, p.localCoordinates(actual), 1e-8)); + } } //******************************************************************************* TEST(Unit3, retract_expmap) { Unit3 p; - Vector v(2); - v << (M_PI / 2.0), 0; + Vector2 v((M_PI / 2.0), 0); Unit3 expected(Point3(0, 0, 1)); Unit3 actual = p.retract(v); EXPECT(assert_equal(expected, actual, 1e-8)); EXPECT(assert_equal(v, p.localCoordinates(actual), 1e-8)); } -//******************************************************************************* -/// Returns a random vector -inline static Vector randomVector(const Vector& minLimits, - const Vector& maxLimits) { - - // Get the number of dimensions and create the return vector - size_t numDims = dim(minLimits); - Vector vector = zero(numDims); - - // Create the random vector - for (size_t i = 0; i < numDims; i++) { - double range = maxLimits(i) - minLimits(i); - vector(i) = (((double) rand()) / RAND_MAX) * range + minLimits(i); - } - return vector; -} - -//******************************************************************************* -// Let x and y be two Unit3's. -// The equality x.localCoordinates(x.retract(v)) == v should hold. -TEST(Unit3, localCoordinates_retract) { - - size_t numIterations = 10000; - Vector minSphereLimit = Vector3(-1.0, -1.0, -1.0), maxSphereLimit = - Vector3(1.0, 1.0, 1.0); - Vector minXiLimit = Vector2(-1.0, -1.0), maxXiLimit = Vector2(1.0, 1.0); - for (size_t i = 0; i < numIterations; i++) { - - // Sleep for the random number generator (TODO?: Better create all of them first). -// boost::this_thread::sleep(boost::posix_time::milliseconds(0)); - - // Create the two Unit3s. - // NOTE: You can not create two totally random Unit3's because you cannot always compute - // between two any Unit3's. (For instance, they might be at the different sides of the circle). - Unit3 s1(Point3(randomVector(minSphereLimit, maxSphereLimit))); -// Unit3 s2 (Point3(randomVector(minSphereLimit, maxSphereLimit))); - Vector v12 = randomVector(minXiLimit, maxXiLimit); - Unit3 s2 = s1.retract(v12); - - // Check if the local coordinates and retract return the same results. - Vector actual_v12 = s1.localCoordinates(s2); - EXPECT(assert_equal(v12, actual_v12, 1e-3)); - Unit3 actual_s2 = s1.retract(actual_v12); - EXPECT(assert_equal(s2, actual_s2, 1e-3)); - } -} - -//******************************************************************************* -// Let x and y be two Unit3's. -// The equality x.localCoordinates(x.retract(v)) == v should hold. -TEST(Unit3, localCoordinates_retract_expmap) { - - size_t numIterations = 10000; - Vector minSphereLimit = Vector3(-1.0, -1.0, -1.0), maxSphereLimit = - Vector3(1.0, 1.0, 1.0); - Vector minXiLimit = (Vector(2) << -M_PI, -M_PI).finished(), maxXiLimit = (Vector(2) << M_PI, M_PI).finished(); - for (size_t i = 0; i < numIterations; i++) { - - // Sleep for the random number generator (TODO?: Better create all of them first). -// boost::this_thread::sleep(boost::posix_time::milliseconds(0)); - - // Create the two Unit3s. - // Unlike the above case, we can use any two Unit3's. - Unit3 s1(Point3(randomVector(minSphereLimit, maxSphereLimit))); -// Unit3 s2 (Point3(randomVector(minSphereLimit, maxSphereLimit))); - Vector v12 = randomVector(minXiLimit, maxXiLimit); - - // Magnitude of the rotation can be at most pi - if (v12.norm() > M_PI) - v12 = v12 / M_PI; - Unit3 s2 = s1.retract(v12); - - // Check if the local coordinates and retract return the same results. - Vector actual_v12 = s1.localCoordinates(s2); - EXPECT(assert_equal(v12, actual_v12, 1e-3)); - Unit3 actual_s2 = s1.retract(actual_v12); - EXPECT(assert_equal(s2, actual_s2, 1e-3)); - } -} - -//******************************************************************************* -//TEST( Pose2, between ) -//{ -// // < -// // -// // ^ -// // -// // *--0--*--* -// Pose2 gT1(M_PI/2.0, Point2(1,2)); // robot at (1,2) looking towards y -// Pose2 gT2(M_PI, Point2(-1,4)); // robot at (-1,4) loooking at negative x -// -// Matrix actualH1,actualH2; -// Pose2 expected(M_PI/2.0, Point2(2,2)); -// Pose2 actual1 = gT1.between(gT2); -// Pose2 actual2 = gT1.between(gT2,actualH1,actualH2); -// EXPECT(assert_equal(expected,actual1)); -// EXPECT(assert_equal(expected,actual2)); -// -// Matrix expectedH1 = (Matrix(3,3) << -// 0.0,-1.0,-2.0, -// 1.0, 0.0,-2.0, -// 0.0, 0.0,-1.0 -// ); -// Matrix numericalH1 = numericalDerivative21(testing::between, gT1, gT2); -// EXPECT(assert_equal(expectedH1,actualH1)); -// EXPECT(assert_equal(numericalH1,actualH1)); -// // Assert H1 = -AdjointMap(between(p2,p1)) as in doc/math.lyx -// EXPECT(assert_equal(-gT2.between(gT1).AdjointMap(),actualH1)); -// -// Matrix expectedH2 = (Matrix(3,3) << -// 1.0, 0.0, 0.0, -// 0.0, 1.0, 0.0, -// 0.0, 0.0, 1.0 -// ); -// Matrix numericalH2 = numericalDerivative22(testing::between, gT1, gT2); -// EXPECT(assert_equal(expectedH2,actualH2)); -// EXPECT(assert_equal(numericalH2,actualH2)); -// -//} - //******************************************************************************* TEST(Unit3, Random) { boost::mt19937 rng(42); @@ -336,6 +384,26 @@ TEST(Unit3, Random) { EXPECT(assert_equal(expectedMean,actualMean,0.1)); } +//******************************************************************************* +// New test that uses Unit3::Random +TEST(Unit3, localCoordinates_retract) { + boost::mt19937 rng(42); + size_t numIterations = 10000; + + for (size_t i = 0; i < numIterations; i++) { + // Create two random Unit3s + const Unit3 s1 = Unit3::Random(rng); + const Unit3 s2 = Unit3::Random(rng); + // Check that they are not at opposite ends of the sphere, which is ill defined + if (s1.unitVector().dot(s2.unitVector())<-0.9) continue; + + // Check if the local coordinates and retract return consistent results. + Vector v12 = s1.localCoordinates(s2); + Unit3 actual_s2 = s1.retract(v12); + EXPECT(assert_equal(s2, actual_s2, 1e-9)); + } +} + //************************************************************************* TEST (Unit3, FromPoint3) { Matrix actualH; @@ -347,6 +415,54 @@ TEST (Unit3, FromPoint3) { EXPECT(assert_equal(expectedH, actualH, 1e-8)); } +//******************************************************************************* +TEST(Unit3, ErrorBetweenFactor) { + std::vector data; + data.push_back(Unit3(1.0, 0.0, 0.0)); + data.push_back(Unit3(0.0, 0.0, 1.0)); + + NonlinearFactorGraph graph; + Values initial_values; + + // Add prior factors. + SharedNoiseModel R_prior = noiseModel::Unit::Create(2); + for (size_t i = 0; i < data.size(); i++) { + graph.add(PriorFactor(U(i), data[i], R_prior)); + } + + // Add process factors using the dot product error function. + SharedNoiseModel R_process = noiseModel::Isotropic::Sigma(2, 0.01); + for (size_t i = 0; i < data.size() - 1; i++) { + Expression exp(Expression(U(i)), &Unit3::errorVector, Expression(U(i + 1))); + graph.addExpressionFactor(R_process, Vector2::Zero(), exp); + } + + // Add initial values. Since there is no identity, just pick something. + for (size_t i = 0; i < data.size(); i++) { + initial_values.insert(U(i), Unit3(0.0, 1.0, 0.0)); + } + + Values values = GaussNewtonOptimizer(graph, initial_values).optimize(); + + // Check that the y-value is very small for each. + for (size_t i = 0; i < data.size(); i++) { + EXPECT(assert_equal(0.0, values.at(U(i)).unitVector().y(), 1e-3)); + } + + // Check that the dot product between variables is close to 1. + for (size_t i = 0; i < data.size() - 1; i++) { + EXPECT(assert_equal(1.0, values.at(U(i)).dot(values.at(U(i + 1))), 1e-2)); + } +} + +/* ************************************************************************* */ +TEST(actualH, Serialization) { + Unit3 p(0, 1, 0); + EXPECT(serializationTestHelpers::equalsObj(p)); + EXPECT(serializationTestHelpers::equalsXML(p)); + EXPECT(serializationTestHelpers::equalsBinary(p)); +} + /* ************************************************************************* */ int main() { srand(time(NULL)); diff --git a/gtsam/geometry/triangulation.cpp b/gtsam/geometry/triangulation.cpp index c0f69217c..c92aa8237 100644 --- a/gtsam/geometry/triangulation.cpp +++ b/gtsam/geometry/triangulation.cpp @@ -46,7 +46,6 @@ Vector4 triangulateHomogeneousDLT( double error; Vector v; boost::tie(rank, error, v) = DLT(A, rank_tol); - // std::cout << "s " << s.transpose() << std:endl; if (rank < 3) throw(TriangulationUnderconstrainedException()); diff --git a/gtsam/geometry/triangulation.h b/gtsam/geometry/triangulation.h index f4f40ccba..c6e613b14 100644 --- a/gtsam/geometry/triangulation.h +++ b/gtsam/geometry/triangulation.h @@ -18,6 +18,8 @@ #pragma once +#include +#include #include #include #include @@ -64,11 +66,10 @@ GTSAM_EXPORT Point3 triangulateDLT( const std::vector& projection_matrices, const std::vector& measurements, double rank_tol = 1e-9); -/// /** * Create a factor graph with projection factors from poses and one calibration * @param poses Camera poses - * @param sharedCal shared pointer to single calibration object + * @param sharedCal shared pointer to single calibration object (monocular only!) * @param measurements 2D measurements * @param landmarkKey to refer to landmark * @param initialEstimate @@ -86,8 +87,9 @@ std::pair triangulationGraph( static SharedNoiseModel prior_model(noiseModel::Isotropic::Sigma(6, 1e-6)); for (size_t i = 0; i < measurements.size(); i++) { const Pose3& pose_i = poses[i]; - PinholeCamera camera_i(pose_i, *sharedCal); - graph.push_back(TriangulationFactor // + typedef PinholePose Camera; + Camera camera_i(pose_i, sharedCal); + graph.push_back(TriangulationFactor // (camera_i, measurements[i], unit2, landmarkKey)); } return std::make_pair(graph, values); @@ -96,7 +98,7 @@ std::pair triangulationGraph( /** * Create a factor graph with projection factors from pinhole cameras * (each camera has a pose and calibration) - * @param cameras pinhole cameras + * @param cameras pinhole cameras (monocular or stereo) * @param measurements 2D measurements * @param landmarkKey to refer to landmark * @param initialEstimate @@ -105,22 +107,30 @@ std::pair triangulationGraph( template std::pair triangulationGraph( const std::vector& cameras, - const std::vector& measurements, Key landmarkKey, + const std::vector& measurements, Key landmarkKey, const Point3& initialEstimate) { Values values; values.insert(landmarkKey, initialEstimate); // Initial landmark value NonlinearFactorGraph graph; - static SharedNoiseModel unit2(noiseModel::Unit::Create(2)); - static SharedNoiseModel prior_model(noiseModel::Isotropic::Sigma(6, 1e-6)); + static SharedNoiseModel unit(noiseModel::Unit::Create(CAMERA::Measurement::dimension)); for (size_t i = 0; i < measurements.size(); i++) { const CAMERA& camera_i = cameras[i]; - graph.push_back(TriangulationFactor // - (camera_i, measurements[i], unit2, landmarkKey)); + graph.push_back(TriangulationFactor // + (camera_i, measurements[i], unit, landmarkKey)); } return std::make_pair(graph, values); } -/// +/// PinholeCamera specific version // TODO: (chris) why does this exist? +template +std::pair triangulationGraph( + const std::vector >& cameras, + const std::vector& measurements, Key landmarkKey, + const Point3& initialEstimate) { + return triangulationGraph > // + (cameras, measurements, landmarkKey, initialEstimate); +} + /** * Optimize for triangulation * @param graph nonlinear factors for projection @@ -147,15 +157,15 @@ Point3 triangulateNonlinear(const std::vector& poses, // Create a factor graph and initial values Values values; NonlinearFactorGraph graph; - boost::tie(graph, values) = triangulationGraph(poses, sharedCal, measurements, - Symbol('p', 0), initialEstimate); + boost::tie(graph, values) = triangulationGraph // + (poses, sharedCal, measurements, Symbol('p', 0), initialEstimate); return optimize(graph, values, Symbol('p', 0)); } /** * Given an initial estimate , refine a point using measurements in several cameras - * @param cameras pinhole cameras + * @param cameras pinhole cameras (monocular or stereo) * @param measurements 2D measurements * @param initialEstimate * @return refined Point3 @@ -163,17 +173,26 @@ Point3 triangulateNonlinear(const std::vector& poses, template Point3 triangulateNonlinear( const std::vector& cameras, - const std::vector& measurements, const Point3& initialEstimate) { + const std::vector& measurements, const Point3& initialEstimate) { // Create a factor graph and initial values Values values; NonlinearFactorGraph graph; - boost::tie(graph, values) = triangulationGraph(cameras, measurements, - Symbol('p', 0), initialEstimate); + boost::tie(graph, values) = triangulationGraph // + (cameras, measurements, Symbol('p', 0), initialEstimate); return optimize(graph, values, Symbol('p', 0)); } +/// PinholeCamera specific version // TODO: (chris) why does this exist? +template +Point3 triangulateNonlinear( + const std::vector >& cameras, + const std::vector& measurements, const Point3& initialEstimate) { + return triangulateNonlinear > // + (cameras, measurements, initialEstimate); +} + /** * Create a 3*4 camera projection matrix from calibration and pose. * Functor for partial application on calibration @@ -224,12 +243,13 @@ Point3 triangulatePoint3(const std::vector& poses, // Triangulate linearly Point3 point = triangulateDLT(projection_matrices, measurements, rank_tol); - // The n refine using non-linear optimization + // Then refine using non-linear optimization if (optimize) - point = triangulateNonlinear(poses, sharedCal, measurements, point); + point = triangulateNonlinear // + (poses, sharedCal, measurements, point); #ifdef GTSAM_THROW_CHEIRALITY_EXCEPTION - // verify that the triangulated point lies infront of all cameras + // verify that the triangulated point lies in front of all cameras BOOST_FOREACH(const Pose3& pose, poses) { const Point3& p_local = pose.transform_to(point); if (p_local.z() <= 0) @@ -265,9 +285,8 @@ Point3 triangulatePoint3( throw(TriangulationUnderconstrainedException()); // construct projection matrices from poses & calibration - typedef PinholeCamera Camera; std::vector projection_matrices; - BOOST_FOREACH(const Camera& camera, cameras) + BOOST_FOREACH(const CAMERA& camera, cameras) projection_matrices.push_back( CameraProjectionMatrix(camera.calibration())( camera.pose())); @@ -275,11 +294,11 @@ Point3 triangulatePoint3( // The n refine using non-linear optimization if (optimize) - point = triangulateNonlinear(cameras, measurements, point); + point = triangulateNonlinear(cameras, measurements, point); #ifdef GTSAM_THROW_CHEIRALITY_EXCEPTION - // verify that the triangulated point lies infront of all cameras - BOOST_FOREACH(const Camera& camera, cameras) { + // verify that the triangulated point lies in front of all cameras + BOOST_FOREACH(const CAMERA& camera, cameras) { const Point3& p_local = camera.pose().transform_to(point); if (p_local.z() <= 0) throw(TriangulationCheiralityException()); @@ -289,5 +308,169 @@ Point3 triangulatePoint3( return point; } +/// Pinhole-specific version +template +Point3 triangulatePoint3( + const std::vector >& cameras, + const std::vector& measurements, double rank_tol = 1e-9, + bool optimize = false) { + return triangulatePoint3 > // + (cameras, measurements, rank_tol, optimize); +} + +struct TriangulationParameters { + + double rankTolerance; ///< threshold to decide whether triangulation is result.degenerate + bool enableEPI; ///< if set to true, will refine triangulation using LM + + /** + * if the landmark is triangulated at distance larger than this, + * result is flagged as degenerate. + */ + double landmarkDistanceThreshold; // + + /** + * If this is nonnegative the we will check if the average reprojection error + * is smaller than this threshold after triangulation, otherwise result is + * flagged as degenerate. + */ + double dynamicOutlierRejectionThreshold; + + /** + * Constructor + * @param rankTol tolerance used to check if point triangulation is degenerate + * @param enableEPI if true refine triangulation with embedded LM iterations + * @param landmarkDistanceThreshold flag as degenerate if point further than this + * @param dynamicOutlierRejectionThreshold or if average error larger than this + * + */ + TriangulationParameters(const double _rankTolerance = 1.0, + const bool _enableEPI = false, double _landmarkDistanceThreshold = -1, + double _dynamicOutlierRejectionThreshold = -1) : + rankTolerance(_rankTolerance), enableEPI(_enableEPI), // + landmarkDistanceThreshold(_landmarkDistanceThreshold), // + dynamicOutlierRejectionThreshold(_dynamicOutlierRejectionThreshold) { + } + + // stream to output + friend std::ostream &operator<<(std::ostream &os, + const TriangulationParameters& p) { + os << "rankTolerance = " << p.rankTolerance << std::endl; + os << "enableEPI = " << p.enableEPI << std::endl; + os << "landmarkDistanceThreshold = " << p.landmarkDistanceThreshold + << std::endl; + os << "dynamicOutlierRejectionThreshold = " + << p.dynamicOutlierRejectionThreshold << std::endl; + return os; + } +}; + +/** + * TriangulationResult is an optional point, along with the reasons why it is invalid. + */ +class TriangulationResult: public boost::optional { + enum Status { + VALID, DEGENERATE, BEHIND_CAMERA + }; + Status status_; + TriangulationResult(Status s) : + status_(s) { + } +public: + + /** + * Default constructor, only for serialization + */ + TriangulationResult() {} + + /** + * Constructor + */ + TriangulationResult(const Point3& p) : + status_(VALID) { + reset(p); + } + static TriangulationResult Degenerate() { + return TriangulationResult(DEGENERATE); + } + static TriangulationResult BehindCamera() { + return TriangulationResult(BEHIND_CAMERA); + } + bool degenerate() const { + return status_ == DEGENERATE; + } + bool behindCamera() const { + return status_ == BEHIND_CAMERA; + } + // stream to output + friend std::ostream &operator<<(std::ostream &os, + const TriangulationResult& result) { + if (result) + os << "point = " << *result << std::endl; + else + os << "no point, status = " << result.status_ << std::endl; + return os; + } +}; + +/// triangulateSafe: extensive checking of the outcome +template +TriangulationResult triangulateSafe(const std::vector& cameras, + const std::vector& measured, + const TriangulationParameters& params) { + + size_t m = cameras.size(); + + // if we have a single pose the corresponding factor is uninformative + if (m < 2) + return TriangulationResult::Degenerate(); + else + // We triangulate the 3D position of the landmark + try { + Point3 point = triangulatePoint3(cameras, measured, + params.rankTolerance, params.enableEPI); + + // Check landmark distance and re-projection errors to avoid outliers + size_t i = 0; + double totalReprojError = 0.0; + BOOST_FOREACH(const CAMERA& camera, cameras) { + const Pose3& pose = camera.pose(); + if (params.landmarkDistanceThreshold > 0 + && pose.translation().distance(point) + > params.landmarkDistanceThreshold) + return TriangulationResult::Degenerate(); +#ifdef GTSAM_THROW_CHEIRALITY_EXCEPTION + // verify that the triangulated point lies in front of all cameras + // Only needed if this was not yet handled by exception + const Point3& p_local = pose.transform_to(point); + if (p_local.z() <= 0) + return TriangulationResult::BehindCamera(); +#endif + // Check reprojection error + if (params.dynamicOutlierRejectionThreshold > 0) { + const Point2& zi = measured.at(i); + Point2 reprojectionError(camera.project(point) - zi); + totalReprojError += reprojectionError.vector().norm(); + } + i += 1; + } + // Flag as degenerate if average reprojection error is too large + if (params.dynamicOutlierRejectionThreshold > 0 + && totalReprojError / m > params.dynamicOutlierRejectionThreshold) + return TriangulationResult::Degenerate(); + + // all good! + return TriangulationResult(point); + } catch (TriangulationUnderconstrainedException&) { + // This exception is thrown if + // 1) There is a single pose for triangulation - this should not happen because we checked the number of poses before + // 2) The rank of the matrix used for triangulation is < 3: rotation-only, parallel cameras (or motion towards the landmark) + return TriangulationResult::Degenerate(); + } catch (TriangulationCheiralityException&) { + // point is behind one of the cameras: can be the case of close-to-parallel cameras or may depend on outliers + return TriangulationResult::BehindCamera(); + } +} + } // \namespace gtsam diff --git a/gtsam/inference/BayesTree-inst.h b/gtsam/inference/BayesTree-inst.h index 281648409..3a3e1317c 100644 --- a/gtsam/inference/BayesTree-inst.h +++ b/gtsam/inference/BayesTree-inst.h @@ -344,7 +344,7 @@ namespace gtsam { gttic(Full_root_factoring); boost::shared_ptr p_C1_B; { FastVector C1_minus_B; { - FastSet C1_minus_B_set(C1->conditional()->beginParents(), C1->conditional()->endParents()); + KeySet C1_minus_B_set(C1->conditional()->beginParents(), C1->conditional()->endParents()); BOOST_FOREACH(const Key j, *B->conditional()) { C1_minus_B_set.erase(j); } C1_minus_B.assign(C1_minus_B_set.begin(), C1_minus_B_set.end()); @@ -356,7 +356,7 @@ namespace gtsam { } boost::shared_ptr p_C2_B; { FastVector C2_minus_B; { - FastSet C2_minus_B_set(C2->conditional()->beginParents(), C2->conditional()->endParents()); + KeySet C2_minus_B_set(C2->conditional()->beginParents(), C2->conditional()->endParents()); BOOST_FOREACH(const Key j, *B->conditional()) { C2_minus_B_set.erase(j); } C2_minus_B.assign(C2_minus_B_set.begin(), C2_minus_B_set.end()); diff --git a/gtsam/inference/BayesTree.h b/gtsam/inference/BayesTree.h index ff50c9781..4d68acb5b 100644 --- a/gtsam/inference/BayesTree.h +++ b/gtsam/inference/BayesTree.h @@ -19,13 +19,13 @@ #pragma once -#include - -#include +#include #include #include #include +#include + namespace gtsam { // Forward declarations diff --git a/gtsam/inference/BayesTreeCliqueBase-inst.h b/gtsam/inference/BayesTreeCliqueBase-inst.h index 274886c21..256ff983d 100644 --- a/gtsam/inference/BayesTreeCliqueBase-inst.h +++ b/gtsam/inference/BayesTreeCliqueBase-inst.h @@ -44,8 +44,8 @@ namespace gtsam { FastVector BayesTreeCliqueBase::separator_setminus_B(const derived_ptr& B) const { - FastSet p_F_S_parents(this->conditional()->beginParents(), this->conditional()->endParents()); - FastSet indicesB(B->conditional()->begin(), B->conditional()->end()); + KeySet p_F_S_parents(this->conditional()->beginParents(), this->conditional()->endParents()); + KeySet indicesB(B->conditional()->begin(), B->conditional()->end()); FastVector S_setminus_B; std::set_difference(p_F_S_parents.begin(), p_F_S_parents.end(), indicesB.begin(), indicesB.end(), back_inserter(S_setminus_B)); @@ -58,8 +58,8 @@ namespace gtsam { const derived_ptr& B, const FactorGraphType& p_Cp_B) const { gttic(shortcut_indices); - FastSet allKeys = p_Cp_B.keys(); - FastSet indicesB(B->conditional()->begin(), B->conditional()->end()); + KeySet allKeys = p_Cp_B.keys(); + KeySet indicesB(B->conditional()->begin(), B->conditional()->end()); FastVector S_setminus_B = separator_setminus_B(B); FastVector keep; // keep = S\B intersect allKeys (S_setminus_B is already sorted) diff --git a/gtsam/inference/ClusterTree-inst.h b/gtsam/inference/ClusterTree-inst.h index 13130bf2e..6b28f2dbf 100644 --- a/gtsam/inference/ClusterTree-inst.h +++ b/gtsam/inference/ClusterTree-inst.h @@ -7,180 +7,233 @@ * @brief Collects factorgraph fragments defined on variable clusters, arranged in a tree */ -#include -#include #include #include #include +#include +#include #include #include -namespace gtsam -{ - namespace - { - /* ************************************************************************* */ - // Elimination traversal data - stores a pointer to the parent data and collects the factors - // resulting from elimination of the children. Also sets up BayesTree cliques with parent and - // child pointers. - template - struct EliminationData { - EliminationData* const parentData; - size_t myIndexInParent; - FastVector childFactors; - boost::shared_ptr bayesTreeNode; - EliminationData(EliminationData* _parentData, size_t nChildren) : - parentData(_parentData), - bayesTreeNode(boost::make_shared()) - { - if(parentData) { - myIndexInParent = parentData->childFactors.size(); - parentData->childFactors.push_back(typename CLUSTERTREE::sharedFactor()); - } else { - myIndexInParent = 0; - } - // Set up BayesTree parent and child pointers - if(parentData) { - if(parentData->parentData) // If our parent is not the dummy node - bayesTreeNode->parent_ = parentData->bayesTreeNode; - parentData->bayesTreeNode->children.push_back(bayesTreeNode); - } - } - }; +namespace gtsam { - /* ************************************************************************* */ - // Elimination pre-order visitor - just creates the EliminationData structure for the visited - // node. - template - EliminationData eliminationPreOrderVisitor( - const typename CLUSTERTREE::sharedNode& node, EliminationData& parentData) - { - EliminationData myData(&parentData, node->children.size()); - myData.bayesTreeNode->problemSize_ = node->problemSize(); - return myData; +/* ************************************************************************* */ +// Elimination traversal data - stores a pointer to the parent data and collects +// the factors resulting from elimination of the children. Also sets up BayesTree +// cliques with parent and child pointers. +template +struct EliminationData { + // Typedefs + typedef typename CLUSTERTREE::sharedFactor sharedFactor; + typedef typename CLUSTERTREE::FactorType FactorType; + typedef typename CLUSTERTREE::FactorGraphType FactorGraphType; + typedef typename CLUSTERTREE::ConditionalType ConditionalType; + typedef typename CLUSTERTREE::BayesTreeType::Node BTNode; + + EliminationData* const parentData; + size_t myIndexInParent; + FastVector childFactors; + boost::shared_ptr bayesTreeNode; + EliminationData(EliminationData* _parentData, size_t nChildren) : + parentData(_parentData), bayesTreeNode(boost::make_shared()) { + if (parentData) { + myIndexInParent = parentData->childFactors.size(); + parentData->childFactors.push_back(sharedFactor()); + } else { + myIndexInParent = 0; } + // Set up BayesTree parent and child pointers + if (parentData) { + if (parentData->parentData) // If our parent is not the dummy node + bayesTreeNode->parent_ = parentData->bayesTreeNode; + parentData->bayesTreeNode->children.push_back(bayesTreeNode); + } + } - /* ************************************************************************* */ - // Elimination post-order visitor - combine the child factors with our own factors, add the - // resulting conditional to the BayesTree, and add the remaining factor to the parent. - template - struct EliminationPostOrderVisitor - { - const typename CLUSTERTREE::Eliminate& eliminationFunction; - typename CLUSTERTREE::BayesTreeType::Nodes& nodesIndex; - EliminationPostOrderVisitor(const typename CLUSTERTREE::Eliminate& eliminationFunction, + // Elimination pre-order visitor - creates the EliminationData structure for the visited node. + static EliminationData EliminationPreOrderVisitor( + const typename CLUSTERTREE::sharedNode& node, + EliminationData& parentData) { + assert(node); + EliminationData myData(&parentData, node->children.size()); + myData.bayesTreeNode->problemSize_ = node->problemSize(); + return myData; + } + + // Elimination post-order visitor - combine the child factors with our own factors, add the + // resulting conditional to the BayesTree, and add the remaining factor to the parent. + class EliminationPostOrderVisitor { + const typename CLUSTERTREE::Eliminate& eliminationFunction_; + typename CLUSTERTREE::BayesTreeType::Nodes& nodesIndex_; + + public: + // Construct functor + EliminationPostOrderVisitor( + const typename CLUSTERTREE::Eliminate& eliminationFunction, typename CLUSTERTREE::BayesTreeType::Nodes& nodesIndex) : - eliminationFunction(eliminationFunction), nodesIndex(nodesIndex) {} - void operator()(const typename CLUSTERTREE::sharedNode& node, EliminationData& myData) - { - // Typedefs - typedef typename CLUSTERTREE::sharedFactor sharedFactor; - typedef typename CLUSTERTREE::FactorType FactorType; - typedef typename CLUSTERTREE::FactorGraphType FactorGraphType; - typedef typename CLUSTERTREE::ConditionalType ConditionalType; - typedef typename CLUSTERTREE::BayesTreeType::Node BTNode; - - // Gather factors - FactorGraphType gatheredFactors; - gatheredFactors.reserve(node->factors.size() + node->children.size()); - gatheredFactors += node->factors; - gatheredFactors += myData.childFactors; - - // Check for Bayes tree orphan subtrees, and add them to our children - BOOST_FOREACH(const sharedFactor& f, node->factors) - { - if(const BayesTreeOrphanWrapper* asSubtree = dynamic_cast*>(f.get())) - { - myData.bayesTreeNode->children.push_back(asSubtree->clique); - asSubtree->clique->parent_ = myData.bayesTreeNode; - } - } - - // Do dense elimination step - std::pair, boost::shared_ptr > eliminationResult = - eliminationFunction(gatheredFactors, Ordering(node->keys)); - - // Store conditional in BayesTree clique, and in the case of ISAM2Clique also store the remaining factor - myData.bayesTreeNode->setEliminationResult(eliminationResult); - - // Fill nodes index - we do this here instead of calling insertRoot at the end to avoid - // putting orphan subtrees in the index - they'll already be in the index of the ISAM2 - // object they're added to. - BOOST_FOREACH(const Key& j, myData.bayesTreeNode->conditional()->frontals()) - nodesIndex.insert(std::make_pair(j, myData.bayesTreeNode)); - - // Store remaining factor in parent's gathered factors - if(!eliminationResult.second->empty()) - myData.parentData->childFactors[myData.myIndexInParent] = eliminationResult.second; - } - }; - } - - /* ************************************************************************* */ - template - void ClusterTree::Cluster::print( - const std::string& s, const KeyFormatter& keyFormatter) const - { - std::cout << s; - BOOST_FOREACH(Key j, keys) - std::cout << j << " "; - std::cout << "problemSize = " << problemSize_ << std::endl; - } - - /* ************************************************************************* */ - template - void ClusterTree::print( - const std::string& s, const KeyFormatter& keyFormatter) const - { - treeTraversal::PrintForest(*this, s, keyFormatter); - } - - /* ************************************************************************* */ - template - ClusterTree& ClusterTree::operator=(const This& other) - { - // Start by duplicating the tree. - roots_ = treeTraversal::CloneForest(other); - - // Assign the remaining factors - these are pointers to factors in the original factor graph and - // we do not clone them. - remainingFactors_ = other.remainingFactors_; - - return *this; - } - - /* ************************************************************************* */ - template - std::pair, boost::shared_ptr > - ClusterTree::eliminate(const Eliminate& function) const - { - gttic(ClusterTree_eliminate); - // Do elimination (depth-first traversal). The rootsContainer stores a 'dummy' BayesTree node - // that contains all of the roots as its children. rootsContainer also stores the remaining - // uneliminated factors passed up from the roots. - boost::shared_ptr result = boost::make_shared(); - EliminationData rootsContainer(0, roots_.size()); - EliminationPostOrderVisitor visitorPost(function, result->nodes_); - { - TbbOpenMPMixedScope threadLimiter; // Limits OpenMP threads since we're mixing TBB and OpenMP - treeTraversal::DepthFirstForestParallel(*this, rootsContainer, - eliminationPreOrderVisitor, visitorPost, 10); + eliminationFunction_(eliminationFunction), nodesIndex_(nodesIndex) { } - // Create BayesTree from roots stored in the dummy BayesTree node. - result->roots_.insert(result->roots_.end(), rootsContainer.bayesTreeNode->children.begin(), rootsContainer.bayesTreeNode->children.end()); + // Function that does the HEAVY lifting + void operator()(const typename CLUSTERTREE::sharedNode& node, + EliminationData& myData) { + assert(node); - // Add remaining factors that were not involved with eliminated variables - boost::shared_ptr allRemainingFactors = boost::make_shared(); - allRemainingFactors->reserve(remainingFactors_.size() + rootsContainer.childFactors.size()); - allRemainingFactors->push_back(remainingFactors_.begin(), remainingFactors_.end()); - BOOST_FOREACH(const sharedFactor& factor, rootsContainer.childFactors) - if(factor) - allRemainingFactors->push_back(factor); + // Gather factors + FactorGraphType gatheredFactors; + gatheredFactors.reserve(node->factors.size() + node->children.size()); + gatheredFactors += node->factors; + gatheredFactors += myData.childFactors; - // Return result - return std::make_pair(result, allRemainingFactors); + // Check for Bayes tree orphan subtrees, and add them to our children + BOOST_FOREACH(const sharedFactor& f, node->factors) { + if (const BayesTreeOrphanWrapper* asSubtree = + dynamic_cast*>(f.get())) { + myData.bayesTreeNode->children.push_back(asSubtree->clique); + asSubtree->clique->parent_ = myData.bayesTreeNode; + } + } + + // >>>>>>>>>>>>>> Do dense elimination step >>>>>>>>>>>>>>>>>>>>>>>>>>>>> + std::pair, + boost::shared_ptr > eliminationResult = + eliminationFunction_(gatheredFactors, node->orderedFrontalKeys); + // <<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<< + + // Store conditional in BayesTree clique, and in the case of ISAM2Clique also store the remaining factor + myData.bayesTreeNode->setEliminationResult(eliminationResult); + + // Fill nodes index - we do this here instead of calling insertRoot at the end to avoid + // putting orphan subtrees in the index - they'll already be in the index of the ISAM2 + // object they're added to. + BOOST_FOREACH(const Key& j, myData.bayesTreeNode->conditional()->frontals()) + nodesIndex_.insert(std::make_pair(j, myData.bayesTreeNode)); + + // Store remaining factor in parent's gathered factors + if (!eliminationResult.second->empty()) + myData.parentData->childFactors[myData.myIndexInParent] = + eliminationResult.second; + } + }; +}; + +/* ************************************************************************* */ +template +void ClusterTree::Cluster::print(const std::string& s, + const KeyFormatter& keyFormatter) const { + std::cout << s << " (" << problemSize_ << ")"; + PrintKeyVector(orderedFrontalKeys); +} + +/* ************************************************************************* */ +template +void ClusterTree::Cluster::mergeChildren( + const std::vector& merge) { + gttic(Cluster_mergeChildren); + + // Count how many keys, factors and children we'll end up with + size_t nrKeys = orderedFrontalKeys.size(); + size_t nrFactors = factors.size(); + size_t nrNewChildren = 0; + // Loop over children + size_t i = 0; + BOOST_FOREACH(const sharedNode& child, children) { + if (merge[i]) { + nrKeys += child->orderedFrontalKeys.size(); + nrFactors += child->factors.size(); + nrNewChildren += child->children.size(); + } else { + nrNewChildren += 1; // we keep the child + } + ++i; } + // now reserve space, and really merge + orderedFrontalKeys.reserve(nrKeys); + factors.reserve(nrFactors); + typename Node::Children newChildren; + newChildren.reserve(nrNewChildren); + i = 0; + BOOST_FOREACH(const sharedNode& child, children) { + if (merge[i]) { + // Merge keys. For efficiency, we add keys in reverse order at end, calling reverse after.. + orderedFrontalKeys.insert(orderedFrontalKeys.end(), + child->orderedFrontalKeys.rbegin(), child->orderedFrontalKeys.rend()); + // Merge keys, factors, and children. + factors.insert(factors.end(), child->factors.begin(), + child->factors.end()); + newChildren.insert(newChildren.end(), child->children.begin(), + child->children.end()); + // Increment problem size + problemSize_ = std::max(problemSize_, child->problemSize_); + // Increment number of frontal variables + } else { + newChildren.push_back(child); // we keep the child + } + ++i; + } + children = newChildren; + std::reverse(orderedFrontalKeys.begin(), orderedFrontalKeys.end()); +} + +/* ************************************************************************* */ +template +void ClusterTree::print(const std::string& s, + const KeyFormatter& keyFormatter) const { + treeTraversal::PrintForest(*this, s, keyFormatter); +} + +/* ************************************************************************* */ +template +ClusterTree& ClusterTree::operator=( + const This& other) { + // Start by duplicating the tree. + roots_ = treeTraversal::CloneForest(other); + + // Assign the remaining factors - these are pointers to factors in the original factor graph and + // we do not clone them. + remainingFactors_ = other.remainingFactors_; + + return *this; +} + +/* ************************************************************************* */ +template +std::pair, boost::shared_ptr > ClusterTree< + BAYESTREE, GRAPH>::eliminate(const Eliminate& function) const { + gttic(ClusterTree_eliminate); + // Do elimination (depth-first traversal). The rootsContainer stores a 'dummy' BayesTree node + // that contains all of the roots as its children. rootsContainer also stores the remaining + // uneliminated factors passed up from the roots. + boost::shared_ptr result = boost::make_shared(); + typedef EliminationData Data; + Data rootsContainer(0, roots_.size()); + typename Data::EliminationPostOrderVisitor visitorPost(function, + result->nodes_); + { + TbbOpenMPMixedScope threadLimiter; // Limits OpenMP threads since we're mixing TBB and OpenMP + treeTraversal::DepthFirstForestParallel(*this, rootsContainer, + Data::EliminationPreOrderVisitor, visitorPost, 10); + } + + // Create BayesTree from roots stored in the dummy BayesTree node. + result->roots_.insert(result->roots_.end(), + rootsContainer.bayesTreeNode->children.begin(), + rootsContainer.bayesTreeNode->children.end()); + + // Add remaining factors that were not involved with eliminated variables + boost::shared_ptr remaining = boost::make_shared< + FactorGraphType>(); + remaining->reserve( + remainingFactors_.size() + rootsContainer.childFactors.size()); + remaining->push_back(remainingFactors_.begin(), remainingFactors_.end()); + BOOST_FOREACH(const sharedFactor& factor, rootsContainer.childFactors) { + if (factor) + remaining->push_back(factor); + } + // Return result + return std::make_pair(result, remaining); +} + } diff --git a/gtsam/inference/ClusterTree.h b/gtsam/inference/ClusterTree.h index 5a412a79e..b00532d22 100644 --- a/gtsam/inference/ClusterTree.h +++ b/gtsam/inference/ClusterTree.h @@ -11,115 +11,124 @@ #include #include -#include +#include -namespace gtsam -{ +namespace gtsam { - /** - * A cluster-tree is associated with a factor graph and is defined as in Koller-Friedman: - * each node k represents a subset \f$ C_k \sub X \f$, and the tree is family preserving, in that - * each factor \f$ f_i \f$ is associated with a single cluster and \f$ scope(f_i) \sub C_k \f$. - * \nosubgrouping - */ - template - class ClusterTree - { - public: - typedef GRAPH FactorGraphType; ///< The factor graph type - typedef typename GRAPH::FactorType FactorType; ///< The type of factors - typedef ClusterTree This; ///< This class - typedef boost::shared_ptr shared_ptr; ///< Shared pointer to this class - typedef boost::shared_ptr sharedFactor; ///< Shared pointer to a factor - typedef BAYESTREE BayesTreeType; ///< The BayesTree type produced by elimination - typedef typename BayesTreeType::ConditionalType ConditionalType; ///< The type of conditionals - typedef boost::shared_ptr sharedConditional; ///< Shared pointer to a conditional - typedef typename FactorGraphType::Eliminate Eliminate; ///< Typedef for an eliminate subroutine +/** + * A cluster-tree is associated with a factor graph and is defined as in Koller-Friedman: + * each node k represents a subset \f$ C_k \sub X \f$, and the tree is family preserving, in that + * each factor \f$ f_i \f$ is associated with a single cluster and \f$ scope(f_i) \sub C_k \f$. + * \nosubgrouping + */ +template +class ClusterTree { +public: + typedef GRAPH FactorGraphType; ///< The factor graph type + typedef typename GRAPH::FactorType FactorType; ///< The type of factors + typedef ClusterTree This; ///< This class + typedef boost::shared_ptr shared_ptr; ///< Shared pointer to this class + typedef boost::shared_ptr sharedFactor; ///< Shared pointer to a factor + typedef BAYESTREE BayesTreeType; ///< The BayesTree type produced by elimination + typedef typename BayesTreeType::ConditionalType ConditionalType; ///< The type of conditionals + typedef boost::shared_ptr sharedConditional; ///< Shared pointer to a conditional + typedef typename FactorGraphType::Eliminate Eliminate; ///< Typedef for an eliminate subroutine - struct Cluster { - typedef FastVector Keys; - typedef FastVector Factors; - typedef FastVector > Children; + struct Cluster { + typedef Ordering Keys; + typedef FastVector Factors; + typedef FastVector > Children; - Keys keys; ///< Frontal keys of this node - Factors factors; ///< Factors associated with this node - Children children; ///< sub-trees - int problemSize_; + Cluster() { + } + Cluster(Key key, const Factors& factors) : + factors(factors) { + orderedFrontalKeys.push_back(key); + } - int problemSize() const { return problemSize_; } + Keys orderedFrontalKeys; ///< Frontal keys of this node + Factors factors; ///< Factors associated with this node + Children children; ///< sub-trees + int problemSize_; - /** print this node */ - void print(const std::string& s = "", const KeyFormatter& keyFormatter = DefaultKeyFormatter) const; - }; + int problemSize() const { + return problemSize_; + } - typedef boost::shared_ptr sharedCluster; ///< Shared pointer to Cluster - typedef Cluster Node; ///< Define Node=Cluster for compatibility with tree traversal functions - typedef sharedCluster sharedNode; ///< Define Node=Cluster for compatibility with tree traversal functions - - /** concept check */ - GTSAM_CONCEPT_TESTABLE_TYPE(FactorType); - - protected: - FastVector roots_; - FastVector remainingFactors_; - - /// @name Standard Constructors - /// @{ - - /** Copy constructor - makes a deep copy of the tree structure, but only pointers to factors are - * copied, factors are not cloned. */ - ClusterTree(const This& other) { *this = other; } - - /// @} - - public: - /// @name Testable - /// @{ - - /** Print the cluster tree */ - void print(const std::string& s = "", const KeyFormatter& keyFormatter = DefaultKeyFormatter) const; - - /// @} - - /// @name Standard Interface - /// @{ - - /** Eliminate the factors to a Bayes tree and remaining factor graph - * @param function The function to use to eliminate, see the namespace functions - * in GaussianFactorGraph.h - * @return The Bayes tree and factor graph resulting from elimination - */ - std::pair, boost::shared_ptr > - eliminate(const Eliminate& function) const; - - /// @} - - /// @name Advanced Interface - /// @{ - - /** Return the set of roots (one for a tree, multiple for a forest) */ - const FastVector& roots() const { return roots_; } - - /** Return the remaining factors that are not pulled into elimination */ - const FastVector& remainingFactors() const { return remainingFactors_; } - - /// @} - - protected: - /// @name Details - - /// Assignment operator - makes a deep copy of the tree structure, but only pointers to factors - /// are copied, factors are not cloned. - This& operator=(const This& other); - - /// Default constructor to be used in derived classes - ClusterTree() {} - - /// @} + /// print this node + void print(const std::string& s = "", const KeyFormatter& keyFormatter = + DefaultKeyFormatter) const; + /// Merge all children for which bit is set into this node + void mergeChildren(const std::vector& merge); }; + typedef boost::shared_ptr sharedCluster; ///< Shared pointer to Cluster + typedef Cluster Node; ///< Define Node=Cluster for compatibility with tree traversal functions + typedef sharedCluster sharedNode; ///< Define Node=Cluster for compatibility with tree traversal functions + + /** concept check */ + GTSAM_CONCEPT_TESTABLE_TYPE(FactorType); + +protected: + FastVector roots_; + FastVector remainingFactors_; + + /// @name Standard Constructors + /// @{ + + /** Copy constructor - makes a deep copy of the tree structure, but only pointers to factors are + * copied, factors are not cloned. */ + ClusterTree(const This& other) {*this = other;} + + /// @} + +public: + /// @name Testable + /// @{ + + /** Print the cluster tree */ + void print(const std::string& s = "", const KeyFormatter& keyFormatter = DefaultKeyFormatter) const; + + /// @} + + /// @name Standard Interface + /// @{ + + /** Eliminate the factors to a Bayes tree and remaining factor graph + * @param function The function to use to eliminate, see the namespace functions + * in GaussianFactorGraph.h + * @return The Bayes tree and factor graph resulting from elimination + */ + std::pair, boost::shared_ptr > + eliminate(const Eliminate& function) const; + + /// @} + + /// @name Advanced Interface + /// @{ + + /** Return the set of roots (one for a tree, multiple for a forest) */ + const FastVector& roots() const {return roots_;} + + /** Return the remaining factors that are not pulled into elimination */ + const FastVector& remainingFactors() const {return remainingFactors_;} + + /// @} + +protected: + /// @name Details + + /// Assignment operator - makes a deep copy of the tree structure, but only pointers to factors + /// are copied, factors are not cloned. + This& operator=(const This& other); + + /// Default constructor to be used in derived classes + ClusterTree() {} + + /// @} + +}; } - diff --git a/gtsam/inference/EliminateableFactorGraph-inst.h b/gtsam/inference/EliminateableFactorGraph-inst.h index 5e261e200..b4fc3b3a6 100644 --- a/gtsam/inference/EliminateableFactorGraph-inst.h +++ b/gtsam/inference/EliminateableFactorGraph-inst.h @@ -55,9 +55,9 @@ namespace gtsam { // have a VariableIndex already here because we computed one if needed in the previous 'else' // block. if (orderingType == Ordering::METIS) - return eliminateSequential(Ordering::metis(asDerived()), function, variableIndex, orderingType); - else - return eliminateSequential(Ordering::colamd(*variableIndex), function, variableIndex, orderingType); + return eliminateSequential(Ordering::Metis(asDerived()), function, variableIndex, orderingType); + else + return eliminateSequential(Ordering::Colamd(*variableIndex), function, variableIndex, orderingType); } } @@ -93,9 +93,9 @@ namespace gtsam { // have a VariableIndex already here because we computed one if needed in the previous 'else' // block. if (orderingType == Ordering::METIS) - return eliminateMultifrontal(Ordering::metis(asDerived()), function, variableIndex, orderingType); + return eliminateMultifrontal(Ordering::Metis(asDerived()), function, variableIndex, orderingType); else - return eliminateMultifrontal(Ordering::colamd(*variableIndex), function, variableIndex, orderingType); + return eliminateMultifrontal(Ordering::Colamd(*variableIndex), function, variableIndex, orderingType); } } @@ -125,7 +125,7 @@ namespace gtsam { if(variableIndex) { gttic(eliminatePartialSequential); // Compute full ordering - Ordering fullOrdering = Ordering::colamdConstrainedFirst(*variableIndex, variables); + Ordering fullOrdering = Ordering::ColamdConstrainedFirst(*variableIndex, variables); // Split off the part of the ordering for the variables being eliminated Ordering ordering(fullOrdering.begin(), fullOrdering.begin() + variables.size()); @@ -163,7 +163,7 @@ namespace gtsam { if(variableIndex) { gttic(eliminatePartialMultifrontal); // Compute full ordering - Ordering fullOrdering = Ordering::colamdConstrainedFirst(*variableIndex, variables); + Ordering fullOrdering = Ordering::ColamdConstrainedFirst(*variableIndex, variables); // Split off the part of the ordering for the variables being eliminated Ordering ordering(fullOrdering.begin(), fullOrdering.begin() + variables.size()); @@ -216,7 +216,7 @@ namespace gtsam { boost::get(&variables) : boost::get&>(&variables); Ordering totalOrdering = - Ordering::colamdConstrainedLast(*variableIndex, *variablesOrOrdering, unmarginalizedAreOrdered); + Ordering::ColamdConstrainedLast(*variableIndex, *variablesOrOrdering, unmarginalizedAreOrdered); // Split up ordering const size_t nVars = variablesOrOrdering->size(); @@ -275,7 +275,7 @@ namespace gtsam { boost::get(&variables) : boost::get&>(&variables); Ordering totalOrdering = - Ordering::colamdConstrainedLast(*variableIndex, *variablesOrOrdering, unmarginalizedAreOrdered); + Ordering::ColamdConstrainedLast(*variableIndex, *variablesOrOrdering, unmarginalizedAreOrdered); // Split up ordering const size_t nVars = variablesOrOrdering->size(); @@ -301,7 +301,7 @@ namespace gtsam { if(variableIndex) { // Compute a total ordering for all variables - Ordering totalOrdering = Ordering::colamdConstrainedLast(*variableIndex, variables); + Ordering totalOrdering = Ordering::ColamdConstrainedLast(*variableIndex, variables); // Split out the part for the marginalized variables Ordering marginalizationOrdering(totalOrdering.begin(), totalOrdering.end() - variables.size()); diff --git a/gtsam/inference/EliminateableFactorGraph.h b/gtsam/inference/EliminateableFactorGraph.h index 5fb5fbdb1..f5431db3d 100644 --- a/gtsam/inference/EliminateableFactorGraph.h +++ b/gtsam/inference/EliminateableFactorGraph.h @@ -128,7 +128,8 @@ namespace gtsam { OptionalOrderingType orderingType = boost::none) const; /** Do multifrontal elimination of all variables to produce a Bayes tree. If an ordering is not - * provided, the ordering provided by COLAMD will be used. + * provided, the ordering will be computed using either COLAMD or METIS, dependeing on + * the parameter orderingType (Ordering::COLAMD or Ordering::METIS) * * Example - Full Cholesky elimination in COLAMD order: * \code diff --git a/gtsam/inference/EliminationTree-inst.h b/gtsam/inference/EliminationTree-inst.h index 70b0dd393..68e623b68 100644 --- a/gtsam/inference/EliminationTree-inst.h +++ b/gtsam/inference/EliminationTree-inst.h @@ -101,10 +101,12 @@ namespace gtsam { { // Retrieve the factors involving this variable and create the current node const VariableIndex::Factors& factors = structure[order[j]]; - nodes[j] = boost::make_shared(); - nodes[j]->key = order[j]; + const sharedNode node = boost::make_shared(); + node->key = order[j]; // for row i \in Struct[A*j] do + node->children.reserve(factors.size()); + node->factors.reserve(factors.size()); BOOST_FOREACH(const size_t i, factors) { // If we already hit a variable in this factor, make the subtree containing the previous // variable in this factor a child of the current node. This means that the variables @@ -123,16 +125,16 @@ namespace gtsam { if (r != j) { // Now that we found the root, hook up parent and child pointers in the nodes. parents[r] = j; - nodes[j]->children.push_back(nodes[r]); + node->children.push_back(nodes[r]); } } else { - // Add the current factor to the current node since we are at the first variable in this - // factor. - nodes[j]->factors.push_back(graph[i]); + // Add the factor to the current node since we are at the first variable in this factor. + node->factors.push_back(graph[i]); factorUsed[i] = true; } prevCol[i] = j; } + nodes[j] = node; } } catch(std::invalid_argument& e) { // If this is thrown from structure[order[j]] above, it means that it was requested to diff --git a/gtsam/inference/FactorGraph-inst.h b/gtsam/inference/FactorGraph-inst.h index 8c19d4ff4..c629d336a 100644 --- a/gtsam/inference/FactorGraph-inst.h +++ b/gtsam/inference/FactorGraph-inst.h @@ -28,6 +28,7 @@ #include #include +#include // for cout :-( namespace gtsam { @@ -72,8 +73,8 @@ namespace gtsam { /* ************************************************************************* */ template - FastSet FactorGraph::keys() const { - FastSet allKeys; + KeySet FactorGraph::keys() const { + KeySet allKeys; BOOST_FOREACH(const sharedFactor& factor, factors_) if (factor) allKeys.insert(factor->begin(), factor->end()); diff --git a/gtsam/inference/FactorGraph.h b/gtsam/inference/FactorGraph.h index 4d5428e5c..e97860eaa 100644 --- a/gtsam/inference/FactorGraph.h +++ b/gtsam/inference/FactorGraph.h @@ -332,7 +332,7 @@ namespace gtsam { size_t nrFactors() const; /** Potentially very slow function to return all keys involved */ - FastSet keys() const; + KeySet keys() const; /** MATLAB interface utility: Checks whether a factor index idx exists in the graph and is a live pointer */ inline bool exists(size_t idx) const { return idx < size() && at(idx); } diff --git a/gtsam/inference/ISAM-inst.h b/gtsam/inference/ISAM-inst.h index 7cb3d9817..99f668591 100644 --- a/gtsam/inference/ISAM-inst.h +++ b/gtsam/inference/ISAM-inst.h @@ -29,7 +29,7 @@ namespace gtsam { // Remove the contaminated part of the Bayes tree BayesNetType bn; if (!this->empty()) { - const FastSet newFactorKeys = newFactors.keys(); + const KeySet newFactorKeys = newFactors.keys(); this->removeTop(std::vector(newFactorKeys.begin(), newFactorKeys.end()), bn, orphans); } @@ -44,9 +44,9 @@ namespace gtsam { // eliminate into a Bayes net const VariableIndex varIndex(factors); - const FastSet newFactorKeys = newFactors.keys(); + const KeySet newFactorKeys = newFactors.keys(); const Ordering constrainedOrdering = - Ordering::colamdConstrainedLast(varIndex, std::vector(newFactorKeys.begin(), newFactorKeys.end())); + Ordering::ColamdConstrainedLast(varIndex, std::vector(newFactorKeys.begin(), newFactorKeys.end())); Base bayesTree = *factors.eliminateMultifrontal(constrainedOrdering, function, varIndex); this->roots_.insert(this->roots_.end(), bayesTree.roots().begin(), bayesTree.roots().end()); this->nodes_.insert(bayesTree.nodes().begin(), bayesTree.nodes().end()); diff --git a/gtsam/inference/JunctionTree-inst.h b/gtsam/inference/JunctionTree-inst.h index 9d96c5b9c..352a8dded 100644 --- a/gtsam/inference/JunctionTree-inst.h +++ b/gtsam/inference/JunctionTree-inst.h @@ -1,6 +1,6 @@ /* ---------------------------------------------------------------------------- - * GTSAM Copyright 2010, Georgia Tech Research Corporation, + * 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) @@ -26,123 +26,132 @@ #include namespace gtsam { - - namespace { - /* ************************************************************************* */ - template - struct ConstructorTraversalData { - ConstructorTraversalData* const parentData; - typename JunctionTree::sharedNode myJTNode; - FastVector childSymbolicConditionals; - FastVector childSymbolicFactors; - ConstructorTraversalData(ConstructorTraversalData* _parentData) : parentData(_parentData) {} - }; - /* ************************************************************************* */ - // Pre-order visitor function - template - ConstructorTraversalData ConstructorTraversalVisitorPre( +template +struct ConstructorTraversalData { + typedef typename JunctionTree::Node Node; + typedef typename JunctionTree::sharedNode sharedNode; + + ConstructorTraversalData* const parentData; + sharedNode myJTNode; + FastVector childSymbolicConditionals; + FastVector childSymbolicFactors; + + // Small inner class to store symbolic factors + class SymbolicFactors: public FactorGraph { + }; + + ConstructorTraversalData(ConstructorTraversalData* _parentData) : + parentData(_parentData) { + } + + // Pre-order visitor function + static ConstructorTraversalData ConstructorTraversalVisitorPre( const boost::shared_ptr& node, - ConstructorTraversalData& parentData) - { - // On the pre-order pass, before children have been visited, we just set up a traversal data - // structure with its own JT node, and create a child pointer in its parent. - ConstructorTraversalData myData = ConstructorTraversalData(&parentData); - myData.myJTNode = boost::make_shared::Node>(); - myData.myJTNode->keys.push_back(node->key); - myData.myJTNode->factors.insert(myData.myJTNode->factors.begin(), node->factors.begin(), node->factors.end()); - parentData.myJTNode->children.push_back(myData.myJTNode); - return myData; - } + ConstructorTraversalData& parentData) { + // On the pre-order pass, before children have been visited, we just set up + // a traversal data structure with its own JT node, and create a child + // pointer in its parent. + ConstructorTraversalData myData = ConstructorTraversalData(&parentData); + myData.myJTNode = boost::make_shared(node->key, node->factors); + parentData.myJTNode->children.push_back(myData.myJTNode); + return myData; + } - /* ************************************************************************* */ - // Post-order visitor function - template - void ConstructorTraversalVisitorPostAlg2( + // Post-order visitor function + static void ConstructorTraversalVisitorPostAlg2( const boost::shared_ptr& ETreeNode, - const ConstructorTraversalData& myData) - { - // In this post-order visitor, we combine the symbolic elimination results from the - // elimination tree children and symbolically eliminate the current elimination tree node. We - // then check whether each of our elimination tree child nodes should be merged with us. The - // check for this is that our number of symbolic elimination parents is exactly 1 less than - // our child's symbolic elimination parents - this condition indicates that eliminating the - // current node did not introduce any parents beyond those already in the child. + const ConstructorTraversalData& myData) { + // In this post-order visitor, we combine the symbolic elimination results + // from the elimination tree children and symbolically eliminate the current + // elimination tree node. We then check whether each of our elimination + // tree child nodes should be merged with us. The check for this is that + // our number of symbolic elimination parents is exactly 1 less than + // our child's symbolic elimination parents - this condition indicates that + // eliminating the current node did not introduce any parents beyond those + // already in the child-> - // Do symbolic elimination for this node - class : public FactorGraph {} symbolicFactors; - symbolicFactors.reserve(ETreeNode->factors.size() + myData.childSymbolicFactors.size()); - // Add ETree node factors - symbolicFactors += ETreeNode->factors; - // Add symbolic factors passed up from children - symbolicFactors += myData.childSymbolicFactors; + // Do symbolic elimination for this node + SymbolicFactors symbolicFactors; + symbolicFactors.reserve( + ETreeNode->factors.size() + myData.childSymbolicFactors.size()); + // Add ETree node factors + symbolicFactors += ETreeNode->factors; + // Add symbolic factors passed up from children + symbolicFactors += myData.childSymbolicFactors; - Ordering keyAsOrdering; keyAsOrdering.push_back(ETreeNode->key); - std::pair symbolicElimResult = - internal::EliminateSymbolic(symbolicFactors, keyAsOrdering); + Ordering keyAsOrdering; + keyAsOrdering.push_back(ETreeNode->key); + SymbolicConditional::shared_ptr myConditional; + SymbolicFactor::shared_ptr mySeparatorFactor; + boost::tie(myConditional, mySeparatorFactor) = internal::EliminateSymbolic( + symbolicFactors, keyAsOrdering); - // Store symbolic elimination results in the parent - myData.parentData->childSymbolicConditionals.push_back(symbolicElimResult.first); - myData.parentData->childSymbolicFactors.push_back(symbolicElimResult.second); + // Store symbolic elimination results in the parent + myData.parentData->childSymbolicConditionals.push_back(myConditional); + myData.parentData->childSymbolicFactors.push_back(mySeparatorFactor); - // Merge our children if they are in our clique - if our conditional has exactly one fewer - // parent than our child's conditional. - size_t myNrFrontals = 1; - const size_t myNrParents = symbolicElimResult.first->nrParents(); - size_t nrMergedChildren = 0; - assert(myData.myJTNode->children.size() == myData.childSymbolicConditionals.size()); - // Loop over children - int combinedProblemSize = (int) (symbolicElimResult.first->size() * symbolicFactors.size()); - for(size_t child = 0; child < myData.childSymbolicConditionals.size(); ++child) { - // Check if we should merge the child - if(myNrParents + myNrFrontals == myData.childSymbolicConditionals[child]->nrParents()) { - // Get a reference to the child, adjusting the index to account for children previously - // merged and removed from the child list. - const typename JunctionTree::Node& childToMerge = - *myData.myJTNode->children[child - nrMergedChildren]; - // Merge keys, factors, and children. - myData.myJTNode->keys.insert(myData.myJTNode->keys.begin(), childToMerge.keys.begin(), childToMerge.keys.end()); - myData.myJTNode->factors.insert(myData.myJTNode->factors.end(), childToMerge.factors.begin(), childToMerge.factors.end()); - myData.myJTNode->children.insert(myData.myJTNode->children.end(), childToMerge.children.begin(), childToMerge.children.end()); - // Increment problem size - combinedProblemSize = std::max(combinedProblemSize, childToMerge.problemSize_); - // Increment number of frontal variables - myNrFrontals += childToMerge.keys.size(); - // Remove child from list. - myData.myJTNode->children.erase(myData.myJTNode->children.begin() + (child - nrMergedChildren)); - // Increment number of merged children - ++ nrMergedChildren; - } + sharedNode node = myData.myJTNode; + const FastVector& childConditionals = + myData.childSymbolicConditionals; + node->problemSize_ = (int) (myConditional->size() * symbolicFactors.size()); + + // Merge our children if they are in our clique - if our conditional has + // exactly one fewer parent than our child's conditional. + const size_t myNrParents = myConditional->nrParents(); + const size_t nrChildren = node->children.size(); + assert(childConditionals.size() == nrChildren); + + // decide which children to merge, as index into children + std::vector merge(nrChildren, false); + size_t myNrFrontals = 1, i = 0; + BOOST_FOREACH(const sharedNode& child, node->children) { + // Check if we should merge the i^th child + if (myNrParents + myNrFrontals == childConditionals[i]->nrParents()) { + // Increment number of frontal variables + myNrFrontals += child->orderedFrontalKeys.size(); + merge[i] = true; } - myData.myJTNode->problemSize_ = combinedProblemSize; + ++i; } + + // now really merge + node->mergeChildren(merge); } +}; - /* ************************************************************************* */ - template - template - JunctionTree::JunctionTree(const EliminationTree& eliminationTree) - { - gttic(JunctionTree_FromEliminationTree); - // Here we rely on the BayesNet having been produced by this elimination tree, such that the - // conditionals are arranged in DFS post-order. We traverse the elimination tree, and inspect - // the symbolic conditional corresponding to each node. The elimination tree node is added to - // the same clique with its parent if it has exactly one more Bayes net conditional parent than - // does its elimination tree parent. +/* ************************************************************************* */ +template +template +JunctionTree::JunctionTree( + const EliminationTree& eliminationTree) { + gttic(JunctionTree_FromEliminationTree); + // Here we rely on the BayesNet having been produced by this elimination tree, + // such that the conditionals are arranged in DFS post-order. We traverse the + // elimination tree, and inspect the symbolic conditional corresponding to + // each node. The elimination tree node is added to the same clique with its + // parent if it has exactly one more Bayes net conditional parent than + // does its elimination tree parent. - // Traverse the elimination tree, doing symbolic elimination and merging nodes as we go. Gather - // the created junction tree roots in a dummy Node. - typedef typename EliminationTree::Node ETreeNode; - ConstructorTraversalData rootData(0); - rootData.myJTNode = boost::make_shared(); // Make a dummy node to gather the junction tree roots - treeTraversal::DepthFirstForest(eliminationTree, rootData, - ConstructorTraversalVisitorPre, ConstructorTraversalVisitorPostAlg2); + // Traverse the elimination tree, doing symbolic elimination and merging nodes + // as we go. Gather the created junction tree roots in a dummy Node. + typedef typename EliminationTree::Node ETreeNode; + typedef ConstructorTraversalData Data; + Data rootData(0); + rootData.myJTNode = boost::make_shared(); // Make a dummy node to gather + // the junction tree roots + treeTraversal::DepthFirstForest(eliminationTree, rootData, + Data::ConstructorTraversalVisitorPre, + Data::ConstructorTraversalVisitorPostAlg2); - // Assign roots from the dummy node - Base::roots_ = rootData.myJTNode->children; + // Assign roots from the dummy node + typedef typename JunctionTree::Node Node; + const typename Node::Children& children = rootData.myJTNode->children; + Base::roots_.reserve(children.size()); + Base::roots_.insert(Base::roots_.begin(), children.begin(), children.end()); - // Transfer remaining factors from elimination tree - Base::remainingFactors_ = eliminationTree.remainingFactors(); - } + // Transfer remaining factors from elimination tree + Base::remainingFactors_ = eliminationTree.remainingFactors(); +} -} //namespace gtsam +} // namespace gtsam diff --git a/gtsam/inference/Key.cpp b/gtsam/inference/Key.cpp index 0b9be2f1c..a2a6906d1 100644 --- a/gtsam/inference/Key.cpp +++ b/gtsam/inference/Key.cpp @@ -17,57 +17,72 @@ * @date Feb 20, 2012 */ -#include - -#include -#include - #include #include +#include +#include +#include + +using namespace std; + namespace gtsam { /* ************************************************************************* */ -std::string _multirobotKeyFormatter(Key key) { +string _defaultKeyFormatter(Key key) { + const Symbol asSymbol(key); + if (asSymbol.chr() > 0) + return (string) asSymbol; + else + return boost::lexical_cast(key); +} + +/* ************************************************************************* */ +void PrintKey(Key key, const string& s, const KeyFormatter& keyFormatter) { + cout << s << keyFormatter(key); +} + +/* ************************************************************************* */ +string _multirobotKeyFormatter(Key key) { const LabeledSymbol asLabeledSymbol(key); if (asLabeledSymbol.chr() > 0 && asLabeledSymbol.label() > 0) - return (std::string) asLabeledSymbol; + return (string) asLabeledSymbol; const Symbol asSymbol(key); if (asLabeledSymbol.chr() > 0) - return (std::string) asSymbol; + return (string) asSymbol; else - return boost::lexical_cast(key); + return boost::lexical_cast(key); } /* ************************************************************************* */ template -static void print(const CONTAINER& keys, const std::string& s, +static void Print(const CONTAINER& keys, const string& s, const KeyFormatter& keyFormatter) { - std::cout << s << " "; + cout << s << " "; if (keys.empty()) - std::cout << "(none)" << std::endl; + cout << "(none)" << endl; else { BOOST_FOREACH(const Key& key, keys) - std::cout << keyFormatter(key) << " "; - std::cout << std::endl; + cout << keyFormatter(key) << " "; + cout << endl; } } /* ************************************************************************* */ -void printKeyList(const KeyList& keys, const std::string& s, +void PrintKeyList(const KeyList& keys, const string& s, const KeyFormatter& keyFormatter) { - print(keys, s, keyFormatter); + Print(keys, s, keyFormatter); } /* ************************************************************************* */ -void printKeyVector(const KeyVector& keys, const std::string& s, +void PrintKeyVector(const KeyVector& keys, const string& s, const KeyFormatter& keyFormatter) { - print(keys, s, keyFormatter); + Print(keys, s, keyFormatter); } /* ************************************************************************* */ -void printKeySet(const KeySet& keys, const std::string& s, +void PrintKeySet(const KeySet& keys, const string& s, const KeyFormatter& keyFormatter) { - print(keys, s, keyFormatter); + Print(keys, s, keyFormatter); } /* ************************************************************************* */ diff --git a/gtsam/inference/Key.h b/gtsam/inference/Key.h index e2be79dc7..d2b342575 100644 --- a/gtsam/inference/Key.h +++ b/gtsam/inference/Key.h @@ -17,45 +17,75 @@ */ #pragma once -#include -#include - -#include -#include #include -#include #include +#include +#include +#include +#include +#include + +#include namespace gtsam { +/// Typedef for a function to format a key, i.e. to convert it to a string +typedef boost::function KeyFormatter; - // Helper function for Multi-robot Key Formatter - GTSAM_EXPORT std::string _multirobotKeyFormatter(gtsam::Key key); +// Helper function for DefaultKeyFormatter +GTSAM_EXPORT std::string _defaultKeyFormatter(Key key); - /// - /// A KeyFormatter that will check for LabeledSymbol keys, as well as Symbol and plain - /// integer keys. This keyformatter will need to be passed in to override the default - /// formatter in print functions. - /// - /// Checks for LabeledSymbol, Symbol and then plain keys, in order. - static const gtsam::KeyFormatter MultiRobotKeyFormatter = &_multirobotKeyFormatter; +/// The default KeyFormatter, which is used if no KeyFormatter is passed to +/// a nonlinear 'print' function. Automatically detects plain integer keys +/// and Symbol keys. +static const KeyFormatter DefaultKeyFormatter = &_defaultKeyFormatter; - /// Useful typedefs for operations with Values - allow for matlab interfaces - typedef FastList KeyList; - typedef FastVector KeyVector; - typedef FastSet KeySet; - typedef FastMap KeyGroupMap; +// Helper function for Multi-robot Key Formatter +GTSAM_EXPORT std::string _multirobotKeyFormatter(gtsam::Key key); - /// Utility function to print sets of keys with optional prefix - GTSAM_EXPORT void printKeyList(const KeyList& keys, const std::string& s = "", - const KeyFormatter& keyFormatter = DefaultKeyFormatter); +/// +/// A KeyFormatter that will check for LabeledSymbol keys, as well as Symbol and plain +/// integer keys. This keyformatter will need to be passed in to override the default +/// formatter in print functions. +/// +/// Checks for LabeledSymbol, Symbol and then plain keys, in order. +static const gtsam::KeyFormatter MultiRobotKeyFormatter = + &_multirobotKeyFormatter; - /// Utility function to print sets of keys with optional prefix - GTSAM_EXPORT void printKeyVector(const KeyVector& keys, const std::string& s = "", - const KeyFormatter& keyFormatter = DefaultKeyFormatter); +/// Useful typedef for operations with Values - allows for matlab interface +typedef FastVector KeyVector; - /// Utility function to print sets of keys with optional prefix - GTSAM_EXPORT void printKeySet(const KeySet& keys, const std::string& s = "", - const KeyFormatter& keyFormatter = DefaultKeyFormatter); -} +// TODO(frank): Nothing fast about these :-( +typedef FastList KeyList; +typedef FastSet KeySet; +typedef FastMap KeyGroupMap; + +/// Utility function to print one key with optional prefix +GTSAM_EXPORT void PrintKey(Key key, const std::string& s = "", + const KeyFormatter& keyFormatter = DefaultKeyFormatter); + +/// Utility function to print sets of keys with optional prefix +GTSAM_EXPORT void PrintKeyList(const KeyList& keys, const std::string& s = "", + const KeyFormatter& keyFormatter = DefaultKeyFormatter); + +/// Utility function to print sets of keys with optional prefix +GTSAM_EXPORT void PrintKeyVector(const KeyVector& keys, const std::string& s = + "", const KeyFormatter& keyFormatter = DefaultKeyFormatter); + +/// Utility function to print sets of keys with optional prefix +GTSAM_EXPORT void PrintKeySet(const KeySet& keys, const std::string& s = "", + const KeyFormatter& keyFormatter = DefaultKeyFormatter); + +// Define Key to be Testable by specializing gtsam::traits +template struct traits; +template<> struct traits { + static void Print(const Key& key, const std::string& str = "") { + PrintKey(key, str); + } + static bool Equals(const Key& key1, const Key& key2, double tol = 1e-8) { + return key1 == key2; + } +}; + +} // namespace gtsam diff --git a/gtsam/inference/MetisIndex-inl.h b/gtsam/inference/MetisIndex-inl.h index 7299d7c8a..06e5ddeec 100644 --- a/gtsam/inference/MetisIndex-inl.h +++ b/gtsam/inference/MetisIndex-inl.h @@ -26,8 +26,8 @@ namespace gtsam { /* ************************************************************************* */ template void MetisIndex::augment(const FactorGraph& factors) { - std::map > iAdjMap; // Stores a set of keys that are adjacent to key x, with adjMap.first - std::map >::iterator iAdjMapIt; + std::map > iAdjMap; // Stores a set of keys that are adjacent to key x, with adjMap.first + std::map >::iterator iAdjMapIt; std::set keySet; /* ********** Convert to CSR format ********** */ diff --git a/gtsam/inference/Ordering.cpp b/gtsam/inference/Ordering.cpp index 5ae25d543..9f4a81d05 100644 --- a/gtsam/inference/Ordering.cpp +++ b/gtsam/inference/Ordering.cpp @@ -29,242 +29,236 @@ using namespace std; namespace gtsam { - /* ************************************************************************* */ - FastMap Ordering::invert() const - { - FastMap inverted; - for(size_t pos = 0; pos < this->size(); ++pos) - inverted.insert(make_pair((*this)[pos], pos)); - return inverted; +/* ************************************************************************* */ +FastMap Ordering::invert() const { + FastMap inverted; + for (size_t pos = 0; pos < this->size(); ++pos) + inverted.insert(make_pair((*this)[pos], pos)); + return inverted; +} + +/* ************************************************************************* */ +Ordering Ordering::Colamd(const VariableIndex& variableIndex) { + // Call constrained version with all groups set to zero + vector dummy_groups(variableIndex.size(), 0); + return Ordering::ColamdConstrained(variableIndex, dummy_groups); +} + +/* ************************************************************************* */ +Ordering Ordering::ColamdConstrained(const VariableIndex& variableIndex, + std::vector& cmember) { + gttic(Ordering_COLAMDConstrained); + + gttic(Prepare); + size_t nEntries = variableIndex.nEntries(), nFactors = + variableIndex.nFactors(), nVars = variableIndex.size(); + // Convert to compressed column major format colamd wants it in (== MATLAB format!) + size_t Alen = ccolamd_recommended((int) nEntries, (int) nFactors, + (int) nVars); /* colamd arg 3: size of the array A */ + vector A = vector(Alen); /* colamd arg 4: row indices of A, of size Alen */ + vector p = vector(nVars + 1); /* colamd arg 5: column pointers of A, of size n_col+1 */ + + // Fill in input data for COLAMD + p[0] = 0; + int count = 0; + vector keys(nVars); // Array to store the keys in the order we add them so we can retrieve them in permuted order + size_t index = 0; + BOOST_FOREACH(const VariableIndex::value_type key_factors, variableIndex) { + // Arrange factor indices into COLAMD format + const VariableIndex::Factors& column = key_factors.second; + size_t lastFactorId = numeric_limits::max(); + BOOST_FOREACH(size_t factorIndex, column) { + if (lastFactorId != numeric_limits::max()) + assert(factorIndex > lastFactorId); + A[count++] = (int) factorIndex; // copy sparse column + } + p[index + 1] = count; // column j (base 1) goes from A[j-1] to A[j]-1 + // Store key in array and increment index + keys[index] = key_factors.first; + ++index; } - /* ************************************************************************* */ - Ordering Ordering::colamd(const VariableIndex& variableIndex) - { - // Call constrained version with all groups set to zero - vector dummy_groups(variableIndex.size(), 0); - return Ordering::colamdConstrained(variableIndex, dummy_groups); + assert((size_t)count == variableIndex.nEntries()); + + //double* knobs = NULL; /* colamd arg 6: parameters (uses defaults if NULL) */ + double knobs[CCOLAMD_KNOBS]; + ccolamd_set_defaults(knobs); + knobs[CCOLAMD_DENSE_ROW] = -1; + knobs[CCOLAMD_DENSE_COL] = -1; + + int stats[CCOLAMD_STATS]; /* colamd arg 7: colamd output statistics and error codes */ + + gttoc(Prepare); + + // call colamd, result will be in p + /* returns (1) if successful, (0) otherwise*/ + if (nVars > 0) { + gttic(ccolamd); + int rv = ccolamd((int) nFactors, (int) nVars, (int) Alen, &A[0], &p[0], + knobs, stats, &cmember[0]); + if (rv != 1) + throw runtime_error( + (boost::format("ccolamd failed with return value %1%") % rv).str()); } - /* ************************************************************************* */ - Ordering Ordering::colamdConstrained( - const VariableIndex& variableIndex, std::vector& cmember) - { - gttic(Ordering_COLAMDConstrained); + // ccolamd_report(stats); - gttic(Prepare); - size_t nEntries = variableIndex.nEntries(), nFactors = variableIndex.nFactors(), nVars = variableIndex.size(); - // Convert to compressed column major format colamd wants it in (== MATLAB format!) - size_t Alen = ccolamd_recommended((int)nEntries, (int)nFactors, (int)nVars); /* colamd arg 3: size of the array A */ - vector A = vector(Alen); /* colamd arg 4: row indices of A, of size Alen */ - vector p = vector(nVars + 1); /* colamd arg 5: column pointers of A, of size n_col+1 */ + gttic(Fill_Ordering); + // Convert elimination ordering in p to an ordering + Ordering result; + result.resize(nVars); + for (size_t j = 0; j < nVars; ++j) + result[j] = keys[p[j]]; + gttoc(Fill_Ordering); - // Fill in input data for COLAMD - p[0] = 0; - int count = 0; - vector keys(nVars); // Array to store the keys in the order we add them so we can retrieve them in permuted order - size_t index = 0; - BOOST_FOREACH(const VariableIndex::value_type key_factors, variableIndex) { - // Arrange factor indices into COLAMD format - const VariableIndex::Factors& column = key_factors.second; - size_t lastFactorId = numeric_limits::max(); - BOOST_FOREACH(size_t factorIndex, column) { - if(lastFactorId != numeric_limits::max()) - assert(factorIndex > lastFactorId); - A[count++] = (int)factorIndex; // copy sparse column - } - p[index+1] = count; // column j (base 1) goes from A[j-1] to A[j]-1 - // Store key in array and increment index - keys[index] = key_factors.first; - ++ index; - } + return result; +} - assert((size_t)count == variableIndex.nEntries()); +/* ************************************************************************* */ +Ordering Ordering::ColamdConstrainedLast(const VariableIndex& variableIndex, + const std::vector& constrainLast, bool forceOrder) { + gttic(Ordering_COLAMDConstrainedLast); - //double* knobs = NULL; /* colamd arg 6: parameters (uses defaults if NULL) */ - double knobs[CCOLAMD_KNOBS]; - ccolamd_set_defaults(knobs); - knobs[CCOLAMD_DENSE_ROW]=-1; - knobs[CCOLAMD_DENSE_COL]=-1; + size_t n = variableIndex.size(); + std::vector cmember(n, 0); - int stats[CCOLAMD_STATS]; /* colamd arg 7: colamd output statistics and error codes */ + // Build a mapping to look up sorted Key indices by Key + FastMap keyIndices; + size_t j = 0; + BOOST_FOREACH(const VariableIndex::value_type key_factors, variableIndex) + keyIndices.insert(keyIndices.end(), make_pair(key_factors.first, j++)); - gttoc(Prepare); + // If at least some variables are not constrained to be last, constrain the + // ones that should be constrained. + int group = (constrainLast.size() != n ? 1 : 0); + BOOST_FOREACH(Key key, constrainLast) { + cmember[keyIndices.at(key)] = group; + if (forceOrder) + ++group; + } - // call colamd, result will be in p - /* returns (1) if successful, (0) otherwise*/ - if(nVars > 0) { - gttic(ccolamd); - int rv = ccolamd((int)nFactors, (int)nVars, (int)Alen, &A[0], &p[0], knobs, stats, &cmember[0]); - if(rv != 1) - throw runtime_error((boost::format("ccolamd failed with return value %1%")%rv).str()); - } + return Ordering::ColamdConstrained(variableIndex, cmember); +} - // ccolamd_report(stats); +/* ************************************************************************* */ +Ordering Ordering::ColamdConstrainedFirst(const VariableIndex& variableIndex, + const std::vector& constrainFirst, bool forceOrder) { + gttic(Ordering_COLAMDConstrainedFirst); - gttic(Fill_Ordering); - // Convert elimination ordering in p to an ordering - Ordering result; - result.resize(nVars); - for(size_t j = 0; j < nVars; ++j) - result[j] = keys[p[j]]; - gttoc(Fill_Ordering); + const int none = -1; + size_t n = variableIndex.size(); + std::vector cmember(n, none); + // Build a mapping to look up sorted Key indices by Key + FastMap keyIndices; + size_t j = 0; + BOOST_FOREACH(const VariableIndex::value_type key_factors, variableIndex) + keyIndices.insert(keyIndices.end(), make_pair(key_factors.first, j++)); + + // If at least some variables are not constrained to be last, constrain the + // ones that should be constrained. + int group = 0; + BOOST_FOREACH(Key key, constrainFirst) { + cmember[keyIndices.at(key)] = group; + if (forceOrder) + ++group; + } + + if (!forceOrder && !constrainFirst.empty()) + ++group; + BOOST_FOREACH(int& c, cmember) + if (c == none) + c = group; + + return Ordering::ColamdConstrained(variableIndex, cmember); +} + +/* ************************************************************************* */ +Ordering Ordering::ColamdConstrained(const VariableIndex& variableIndex, + const FastMap& groups) { + gttic(Ordering_COLAMDConstrained); + size_t n = variableIndex.size(); + std::vector cmember(n, 0); + + // Build a mapping to look up sorted Key indices by Key + FastMap keyIndices; + size_t j = 0; + BOOST_FOREACH(const VariableIndex::value_type key_factors, variableIndex) + keyIndices.insert(keyIndices.end(), make_pair(key_factors.first, j++)); + + // Assign groups + typedef FastMap::value_type key_group; + BOOST_FOREACH(const key_group& p, groups) { + // FIXME: check that no groups are skipped + cmember[keyIndices.at(p.first)] = p.second; + } + + return Ordering::ColamdConstrained(variableIndex, cmember); +} + +/* ************************************************************************* */ +Ordering Ordering::Metis(const MetisIndex& met) { + gttic(Ordering_METIS); + + vector xadj = met.xadj(); + vector adj = met.adj(); + vector perm, iperm; + + idx_t size = met.nValues(); + for (idx_t i = 0; i < size; i++) { + perm.push_back(0); + iperm.push_back(0); + } + + int outputError; + + outputError = METIS_NodeND(&size, &xadj[0], &adj[0], NULL, NULL, &perm[0], + &iperm[0]); + Ordering result; + + if (outputError != METIS_OK) { + std::cout << "METIS failed during Nested Dissection ordering!\n"; return result; } - /* ************************************************************************* */ - Ordering Ordering::colamdConstrainedLast( - const VariableIndex& variableIndex, const std::vector& constrainLast, bool forceOrder) - { - gttic(Ordering_COLAMDConstrainedLast); - - size_t n = variableIndex.size(); - std::vector cmember(n, 0); - - // Build a mapping to look up sorted Key indices by Key - FastMap keyIndices; - size_t j = 0; - BOOST_FOREACH(const VariableIndex::value_type key_factors, variableIndex) - keyIndices.insert(keyIndices.end(), make_pair(key_factors.first, j++)); - - // If at least some variables are not constrained to be last, constrain the - // ones that should be constrained. - int group = (constrainLast.size() != n ? 1 : 0); - BOOST_FOREACH(Key key, constrainLast) { - cmember[keyIndices.at(key)] = group; - if(forceOrder) - ++ group; - } - - return Ordering::colamdConstrained(variableIndex, cmember); + result.resize(size); + for (size_t j = 0; j < (size_t) size; ++j) { + // We have to add the minKey value back to obtain the original key in the Values + result[j] = met.intToKey(perm[j]); } + return result; +} - /* ************************************************************************* */ - Ordering Ordering::colamdConstrainedFirst( - const VariableIndex& variableIndex, const std::vector& constrainFirst, bool forceOrder) - { - gttic(Ordering_COLAMDConstrainedFirst); - - const int none = -1; - size_t n = variableIndex.size(); - std::vector cmember(n, none); - - // Build a mapping to look up sorted Key indices by Key - FastMap keyIndices; - size_t j = 0; - BOOST_FOREACH(const VariableIndex::value_type key_factors, variableIndex) - keyIndices.insert(keyIndices.end(), make_pair(key_factors.first, j++)); - - // If at least some variables are not constrained to be last, constrain the - // ones that should be constrained. - int group = 0; - BOOST_FOREACH(Key key, constrainFirst) { - cmember[keyIndices.at(key)] = group; - if(forceOrder) - ++ group; - } - - if(!forceOrder && !constrainFirst.empty()) - ++ group; - BOOST_FOREACH(int& c, cmember) - if(c == none) - c = group; - - return Ordering::colamdConstrained(variableIndex, cmember); - } - - /* ************************************************************************* */ - Ordering Ordering::colamdConstrained(const VariableIndex& variableIndex, - const FastMap& groups) - { - gttic(Ordering_COLAMDConstrained); - size_t n = variableIndex.size(); - std::vector cmember(n, 0); - - // Build a mapping to look up sorted Key indices by Key - FastMap keyIndices; - size_t j = 0; - BOOST_FOREACH(const VariableIndex::value_type key_factors, variableIndex) - keyIndices.insert(keyIndices.end(), make_pair(key_factors.first, j++)); - - // Assign groups - typedef FastMap::value_type key_group; - BOOST_FOREACH(const key_group& p, groups) { - // FIXME: check that no groups are skipped - cmember[keyIndices.at(p.first)] = p.second; - } - - return Ordering::colamdConstrained(variableIndex, cmember); - } - - - /* ************************************************************************* */ - Ordering Ordering::metis(const MetisIndex& met) - { - gttic(Ordering_METIS); - - vector xadj = met.xadj(); - vector adj = met.adj(); - vector perm, iperm; - - idx_t size = met.nValues(); - for (idx_t i = 0; i < size; i++) - { - perm.push_back(0); - iperm.push_back(0); - } - - int outputError; - - outputError = METIS_NodeND(&size, &xadj[0], &adj[0], NULL, NULL, &perm[0], &iperm[0]); - Ordering result; - - if (outputError != METIS_OK) - { - std::cout << "METIS failed during Nested Dissection ordering!\n"; - return result; - } - - result.resize(size); - for (size_t j = 0; j < (size_t)size; ++j){ - // We have to add the minKey value back to obtain the original key in the Values - result[j] = met.intToKey(perm[j]); - } - return result; - } - - /* ************************************************************************* */ - void Ordering::print(const std::string& str, const KeyFormatter& keyFormatter) const - { - cout << str; - // Print ordering in index order - // Print the ordering with varsPerLine ordering entries printed on each line, - // for compactness. - static const size_t varsPerLine = 10; - bool endedOnNewline = false; - for(size_t i = 0; i < size(); ++i) { - if(i % varsPerLine == 0) - cout << "Position " << i << ": "; - if(i % varsPerLine != 0) - cout << ", "; - cout << keyFormatter(at(i)); - if(i % varsPerLine == varsPerLine - 1) { - cout << "\n"; - endedOnNewline = true; - } else { - endedOnNewline = false; - } - } - if(!endedOnNewline) +/* ************************************************************************* */ +void Ordering::print(const std::string& str, + const KeyFormatter& keyFormatter) const { + cout << str; + // Print ordering in index order + // Print the ordering with varsPerLine ordering entries printed on each line, + // for compactness. + static const size_t varsPerLine = 10; + bool endedOnNewline = false; + for (size_t i = 0; i < size(); ++i) { + if (i % varsPerLine == 0) + cout << "Position " << i << ": "; + if (i % varsPerLine != 0) + cout << ", "; + cout << keyFormatter(at(i)); + if (i % varsPerLine == varsPerLine - 1) { cout << "\n"; - cout.flush(); + endedOnNewline = true; + } else { + endedOnNewline = false; + } } + if (!endedOnNewline) + cout << "\n"; + cout.flush(); +} - /* ************************************************************************* */ - bool Ordering::equals(const Ordering& other, double tol) const - { - return (*this) == other; - } +/* ************************************************************************* */ +bool Ordering::equals(const Ordering& other, double tol) const { + return (*this) == other; +} } diff --git a/gtsam/inference/Ordering.h b/gtsam/inference/Ordering.h index 274d5681c..8af2649c5 100644 --- a/gtsam/inference/Ordering.h +++ b/gtsam/inference/Ordering.h @@ -18,182 +18,224 @@ #pragma once -#include -#include -#include - -#include #include #include #include #include +#include + +#include +#include +#include namespace gtsam { - class Ordering : public std::vector { - protected: - typedef std::vector Base; +class Ordering: public std::vector { +protected: + typedef std::vector Base; - public: +public: - /// Type of ordering to use - enum OrderingType { - COLAMD, METIS, CUSTOM - }; - - typedef Ordering This; ///< Typedef to this class - typedef boost::shared_ptr shared_ptr; ///< shared_ptr to this class - - /// Create an empty ordering - GTSAM_EXPORT Ordering() {} - - /// Create from a container - template - explicit Ordering(const KEYS& keys) : Base(keys.begin(), keys.end()) {} - - /// Create an ordering using iterators over keys - template - Ordering(ITERATOR firstKey, ITERATOR lastKey) : Base(firstKey, lastKey) {} - - /// Add new variables to the ordering as ordering += key1, key2, ... Equivalent to calling - /// push_back. - boost::assign::list_inserter > - operator+=(Key key) { - return boost::assign::make_list_inserter(boost::assign_detail::call_push_back(*this))(key); - } - - /// Invert (not reverse) the ordering - returns a map from key to order position - FastMap invert() const; - - /// @name Fill-reducing Orderings @{ - - /// Compute a fill-reducing ordering using COLAMD from a factor graph (see details for note on - /// performance). This internally builds a VariableIndex so if you already have a VariableIndex, - /// it is faster to use COLAMD(const VariableIndex&) - template - static Ordering colamd(const FactorGraph& graph) { - return colamd(VariableIndex(graph)); } - - /// Compute a fill-reducing ordering using COLAMD from a VariableIndex. - static GTSAM_EXPORT Ordering colamd(const VariableIndex& variableIndex); - - /// Compute a fill-reducing ordering using constrained COLAMD from a factor graph (see details - /// for note on performance). This internally builds a VariableIndex so if you already have a - /// VariableIndex, it is faster to use COLAMD(const VariableIndex&). This function constrains - /// the variables in \c constrainLast to the end of the ordering, and orders all other variables - /// before in a fill-reducing ordering. If \c forceOrder is true, the variables in \c - /// constrainLast will be ordered in the same order specified in the vector \c - /// constrainLast. If \c forceOrder is false, the variables in \c constrainLast will be - /// ordered after all the others, but will be rearranged by CCOLAMD to reduce fill-in as well. - template - static Ordering colamdConstrainedLast(const FactorGraph& graph, - const std::vector& constrainLast, bool forceOrder = false) { - return colamdConstrainedLast(VariableIndex(graph), constrainLast, forceOrder); } - - /// Compute a fill-reducing ordering using constrained COLAMD from a VariableIndex. This - /// function constrains the variables in \c constrainLast to the end of the ordering, and orders - /// all other variables before in a fill-reducing ordering. If \c forceOrder is true, the - /// variables in \c constrainLast will be ordered in the same order specified in the vector - /// \c constrainLast. If \c forceOrder is false, the variables in \c constrainLast will be - /// ordered after all the others, but will be rearranged by CCOLAMD to reduce fill-in as well. - static GTSAM_EXPORT Ordering colamdConstrainedLast(const VariableIndex& variableIndex, - const std::vector& constrainLast, bool forceOrder = false); - - /// Compute a fill-reducing ordering using constrained COLAMD from a factor graph (see details - /// for note on performance). This internally builds a VariableIndex so if you already have a - /// VariableIndex, it is faster to use COLAMD(const VariableIndex&). This function constrains - /// the variables in \c constrainLast to the end of the ordering, and orders all other variables - /// before in a fill-reducing ordering. If \c forceOrder is true, the variables in \c - /// constrainLast will be ordered in the same order specified in the vector \c - /// constrainLast. If \c forceOrder is false, the variables in \c constrainFirst will be - /// ordered after all the others, but will be rearranged by CCOLAMD to reduce fill-in as well. - template - static Ordering colamdConstrainedFirst(const FactorGraph& graph, - const std::vector& constrainFirst, bool forceOrder = false) { - return colamdConstrainedFirst(VariableIndex(graph), constrainFirst, forceOrder); } - - /// Compute a fill-reducing ordering using constrained COLAMD from a VariableIndex. This - /// function constrains the variables in \c constrainFirst to the front of the ordering, and - /// orders all other variables after in a fill-reducing ordering. If \c forceOrder is true, the - /// variables in \c constrainFirst will be ordered in the same order specified in the - /// vector \c constrainFirst. If \c forceOrder is false, the variables in \c - /// constrainFirst will be ordered after all the others, but will be rearranged by CCOLAMD to - /// reduce fill-in as well. - static GTSAM_EXPORT Ordering colamdConstrainedFirst(const VariableIndex& variableIndex, - const std::vector& constrainFirst, bool forceOrder = false); - - /// Compute a fill-reducing ordering using constrained COLAMD from a factor graph (see details - /// for note on performance). This internally builds a VariableIndex so if you already have a - /// VariableIndex, it is faster to use COLAMD(const VariableIndex&). In this function, a group - /// for each variable should be specified in \c groups, and each group of variables will appear - /// in the ordering in group index order. \c groups should be a map from Key to group index. - /// The group indices used should be consecutive starting at 0, but may appear in \c groups in - /// arbitrary order. Any variables not present in \c groups will be assigned to group 0. This - /// function simply fills the \c cmember argument to CCOLAMD with the supplied indices, see the - /// CCOLAMD documentation for more information. - template - static Ordering colamdConstrained(const FactorGraph& graph, - const FastMap& groups) { - return colamdConstrained(VariableIndex(graph), groups); } - - /// Compute a fill-reducing ordering using constrained COLAMD from a VariableIndex. In this - /// function, a group for each variable should be specified in \c groups, and each group of - /// variables will appear in the ordering in group index order. \c groups should be a map from - /// Key to group index. The group indices used should be consecutive starting at 0, but may - /// appear in \c groups in arbitrary order. Any variables not present in \c groups will be - /// assigned to group 0. This function simply fills the \c cmember argument to CCOLAMD with the - /// supplied indices, see the CCOLAMD documentation for more information. - static GTSAM_EXPORT Ordering colamdConstrained(const VariableIndex& variableIndex, - const FastMap& groups); - - /// Return a natural Ordering. Typically used by iterative solvers - template - static Ordering Natural(const FactorGraph &fg) { - FastSet src = fg.keys(); - std::vector keys(src.begin(), src.end()); - std::stable_sort(keys.begin(), keys.end()); - return Ordering(keys); - } - - /// METIS Formatting function - template - static GTSAM_EXPORT void CSRFormat(std::vector& xadj, std::vector& adj, const FactorGraph& graph); - - /// Compute an ordering determined by METIS from a VariableIndex - static GTSAM_EXPORT Ordering metis(const MetisIndex& met); - - template - static Ordering metis(const FactorGraph& graph) - { - return metis(MetisIndex(graph)); - } - - /// @} - - /// @name Testable @{ - - GTSAM_EXPORT void print(const std::string& str = "", const KeyFormatter& keyFormatter = DefaultKeyFormatter) const; - - GTSAM_EXPORT bool equals(const Ordering& other, double tol = 1e-9) const; - - /// @} - - private: - /// Internal COLAMD function - static GTSAM_EXPORT Ordering colamdConstrained( - const VariableIndex& variableIndex, std::vector& cmember); - - - /** Serialization function */ - friend class boost::serialization::access; - template - void serialize(ARCHIVE & ar, const unsigned int /*version*/) { - ar & BOOST_SERIALIZATION_BASE_OBJECT_NVP(Base); - } + /// Type of ordering to use + enum OrderingType { + COLAMD, METIS, NATURAL, CUSTOM }; - /// traits - template<> struct traits : public Testable {}; + typedef Ordering This; ///< Typedef to this class + typedef boost::shared_ptr shared_ptr; ///< shared_ptr to this class + + /// Create an empty ordering + GTSAM_EXPORT + Ordering() { + } + + /// Create from a container + template + explicit Ordering(const KEYS& keys) : + Base(keys.begin(), keys.end()) { + } + + /// Create an ordering using iterators over keys + template + Ordering(ITERATOR firstKey, ITERATOR lastKey) : + Base(firstKey, lastKey) { + } + + /// Add new variables to the ordering as ordering += key1, key2, ... Equivalent to calling + /// push_back. + boost::assign::list_inserter > operator+=( + Key key) { + return boost::assign::make_list_inserter( + boost::assign_detail::call_push_back(*this))(key); + } + + /// Invert (not reverse) the ordering - returns a map from key to order position + FastMap invert() const; + + /// @name Fill-reducing Orderings @{ + + /// Compute a fill-reducing ordering using COLAMD from a factor graph (see details for note on + /// performance). This internally builds a VariableIndex so if you already have a VariableIndex, + /// it is faster to use COLAMD(const VariableIndex&) + template + static Ordering Colamd(const FactorGraph& graph) { + return Colamd(VariableIndex(graph)); + } + + /// Compute a fill-reducing ordering using COLAMD from a VariableIndex. + static GTSAM_EXPORT Ordering Colamd(const VariableIndex& variableIndex); + + /// Compute a fill-reducing ordering using constrained COLAMD from a factor graph (see details + /// for note on performance). This internally builds a VariableIndex so if you already have a + /// VariableIndex, it is faster to use COLAMD(const VariableIndex&). This function constrains + /// the variables in \c constrainLast to the end of the ordering, and orders all other variables + /// before in a fill-reducing ordering. If \c forceOrder is true, the variables in \c + /// constrainLast will be ordered in the same order specified in the vector \c + /// constrainLast. If \c forceOrder is false, the variables in \c constrainLast will be + /// ordered after all the others, but will be rearranged by CCOLAMD to reduce fill-in as well. + template + static Ordering ColamdConstrainedLast(const FactorGraph& graph, + const std::vector& constrainLast, bool forceOrder = false) { + return ColamdConstrainedLast(VariableIndex(graph), constrainLast, + forceOrder); + } + + /// Compute a fill-reducing ordering using constrained COLAMD from a VariableIndex. This + /// function constrains the variables in \c constrainLast to the end of the ordering, and orders + /// all other variables before in a fill-reducing ordering. If \c forceOrder is true, the + /// variables in \c constrainLast will be ordered in the same order specified in the vector + /// \c constrainLast. If \c forceOrder is false, the variables in \c constrainLast will be + /// ordered after all the others, but will be rearranged by CCOLAMD to reduce fill-in as well. + static GTSAM_EXPORT Ordering ColamdConstrainedLast( + const VariableIndex& variableIndex, const std::vector& constrainLast, + bool forceOrder = false); + + /// Compute a fill-reducing ordering using constrained COLAMD from a factor graph (see details + /// for note on performance). This internally builds a VariableIndex so if you already have a + /// VariableIndex, it is faster to use COLAMD(const VariableIndex&). This function constrains + /// the variables in \c constrainLast to the end of the ordering, and orders all other variables + /// before in a fill-reducing ordering. If \c forceOrder is true, the variables in \c + /// constrainFirst will be ordered in the same order specified in the vector \c + /// constrainFirst. If \c forceOrder is false, the variables in \c constrainFirst will be + /// ordered before all the others, but will be rearranged by CCOLAMD to reduce fill-in as well. + template + static Ordering ColamdConstrainedFirst(const FactorGraph& graph, + const std::vector& constrainFirst, bool forceOrder = false) { + return ColamdConstrainedFirst(VariableIndex(graph), constrainFirst, + forceOrder); + } + + /// Compute a fill-reducing ordering using constrained COLAMD from a VariableIndex. This + /// function constrains the variables in \c constrainFirst to the front of the ordering, and + /// orders all other variables after in a fill-reducing ordering. If \c forceOrder is true, the + /// variables in \c constrainFirst will be ordered in the same order specified in the + /// vector \c constrainFirst. If \c forceOrder is false, the variables in \c + /// constrainFirst will be ordered before all the others, but will be rearranged by CCOLAMD to + /// reduce fill-in as well. + static GTSAM_EXPORT Ordering ColamdConstrainedFirst( + const VariableIndex& variableIndex, + const std::vector& constrainFirst, bool forceOrder = false); + + /// Compute a fill-reducing ordering using constrained COLAMD from a factor graph (see details + /// for note on performance). This internally builds a VariableIndex so if you already have a + /// VariableIndex, it is faster to use COLAMD(const VariableIndex&). In this function, a group + /// for each variable should be specified in \c groups, and each group of variables will appear + /// in the ordering in group index order. \c groups should be a map from Key to group index. + /// The group indices used should be consecutive starting at 0, but may appear in \c groups in + /// arbitrary order. Any variables not present in \c groups will be assigned to group 0. This + /// function simply fills the \c cmember argument to CCOLAMD with the supplied indices, see the + /// CCOLAMD documentation for more information. + template + static Ordering ColamdConstrained(const FactorGraph& graph, + const FastMap& groups) { + return ColamdConstrained(VariableIndex(graph), groups); + } + + /// Compute a fill-reducing ordering using constrained COLAMD from a VariableIndex. In this + /// function, a group for each variable should be specified in \c groups, and each group of + /// variables will appear in the ordering in group index order. \c groups should be a map from + /// Key to group index. The group indices used should be consecutive starting at 0, but may + /// appear in \c groups in arbitrary order. Any variables not present in \c groups will be + /// assigned to group 0. This function simply fills the \c cmember argument to CCOLAMD with the + /// supplied indices, see the CCOLAMD documentation for more information. + static GTSAM_EXPORT Ordering ColamdConstrained( + const VariableIndex& variableIndex, const FastMap& groups); + + /// Return a natural Ordering. Typically used by iterative solvers + template + static Ordering Natural(const FactorGraph &fg) { + KeySet src = fg.keys(); + std::vector keys(src.begin(), src.end()); + std::stable_sort(keys.begin(), keys.end()); + return Ordering(keys); + } + + /// METIS Formatting function + template + static GTSAM_EXPORT void CSRFormat(std::vector& xadj, + std::vector& adj, const FactorGraph& graph); + + /// Compute an ordering determined by METIS from a VariableIndex + static GTSAM_EXPORT Ordering Metis(const MetisIndex& met); + + template + static Ordering Metis(const FactorGraph& graph) { + return Metis(MetisIndex(graph)); + } + + /// @} + + /// @name Named Constructors @{ + + template + static Ordering Create(OrderingType orderingType, + const FactorGraph& graph) { + + switch (orderingType) { + case COLAMD: + return Colamd(graph); + case METIS: + return Metis(graph); + case NATURAL: + return Natural(graph); + case CUSTOM: + throw std::runtime_error( + "Ordering::Create error: called with CUSTOM ordering type."); + default: + throw std::runtime_error( + "Ordering::Create error: called with unknown ordering type."); + } + } + + /// @} + + /// @name Testable @{ + + GTSAM_EXPORT + void print(const std::string& str = "", const KeyFormatter& keyFormatter = + DefaultKeyFormatter) const; + + GTSAM_EXPORT + bool equals(const Ordering& other, double tol = 1e-9) const; + + /// @} + +private: + /// Internal COLAMD function + static GTSAM_EXPORT Ordering ColamdConstrained( + const VariableIndex& variableIndex, std::vector& cmember); + + /** Serialization function */ + friend class boost::serialization::access; + template + void serialize(ARCHIVE & ar, const unsigned int version) { + ar & BOOST_SERIALIZATION_BASE_OBJECT_NVP(Base); + } +}; + +/// traits +template<> struct traits : public Testable { +}; } diff --git a/gtsam/inference/VariableIndex-inl.h b/gtsam/inference/VariableIndex-inl.h index 82eb85c76..c00a3633e 100644 --- a/gtsam/inference/VariableIndex-inl.h +++ b/gtsam/inference/VariableIndex-inl.h @@ -18,6 +18,8 @@ #pragma once #include +#include +#include namespace gtsam { diff --git a/gtsam/inference/VariableIndex.h b/gtsam/inference/VariableIndex.h index bcaec6ee4..3b80f0d01 100644 --- a/gtsam/inference/VariableIndex.h +++ b/gtsam/inference/VariableIndex.h @@ -18,16 +18,14 @@ #pragma once #include -#include #include -#include -#include -#include +#include +#include -#include +#include +#include -#include -#include +#include #include namespace gtsam { @@ -45,7 +43,7 @@ class GTSAM_EXPORT VariableIndex { public: typedef boost::shared_ptr shared_ptr; - typedef FastList Factors; + typedef FastVector Factors; typedef Factors::iterator Factor_iterator; typedef Factors::const_iterator Factor_const_iterator; diff --git a/gtsam/inference/tests/testKey.cpp b/gtsam/inference/tests/testKey.cpp index 1033c0cc9..b0708e660 100644 --- a/gtsam/inference/tests/testKey.cpp +++ b/gtsam/inference/tests/testKey.cpp @@ -14,6 +14,7 @@ * @author Alex Cunningham */ +#include #include #include #include diff --git a/gtsam/inference/tests/testOrdering.cpp b/gtsam/inference/tests/testOrdering.cpp index 013f569e0..d789da9b0 100644 --- a/gtsam/inference/tests/testOrdering.cpp +++ b/gtsam/inference/tests/testOrdering.cpp @@ -28,45 +28,47 @@ using namespace std; using namespace gtsam; using namespace boost::assign; +namespace example { +SymbolicFactorGraph symbolicChain() { + SymbolicFactorGraph sfg; + sfg.push_factor(0, 1); + sfg.push_factor(1, 2); + sfg.push_factor(2, 3); + sfg.push_factor(3, 4); + sfg.push_factor(4, 5); + return sfg; +} +} /* ************************************************************************* */ TEST(Ordering, constrained_ordering) { - SymbolicFactorGraph sfg; // create graph with wanted variable set = 2, 4 - sfg.push_factor(0,1); - sfg.push_factor(1,2); - sfg.push_factor(2,3); - sfg.push_factor(3,4); - sfg.push_factor(4,5); + SymbolicFactorGraph sfg = example::symbolicChain(); // unconstrained version - Ordering actUnconstrained = Ordering::colamd(sfg); + Ordering actUnconstrained = Ordering::Colamd(sfg); Ordering expUnconstrained = Ordering(list_of(0)(1)(2)(3)(4)(5)); EXPECT(assert_equal(expUnconstrained, actUnconstrained)); // constrained version - push one set to the end - Ordering actConstrained = Ordering::colamdConstrainedLast(sfg, list_of(2)(4)); + Ordering actConstrained = Ordering::ColamdConstrainedLast(sfg, list_of(2)(4)); Ordering expConstrained = Ordering(list_of(0)(1)(5)(3)(4)(2)); EXPECT(assert_equal(expConstrained, actConstrained)); // constrained version - push one set to the start - Ordering actConstrained2 = Ordering::colamdConstrainedFirst(sfg, list_of(2)(4)); + Ordering actConstrained2 = Ordering::ColamdConstrainedFirst(sfg, + list_of(2)(4)); Ordering expConstrained2 = Ordering(list_of(2)(4)(0)(1)(3)(5)); EXPECT(assert_equal(expConstrained2, actConstrained2)); } /* ************************************************************************* */ TEST(Ordering, grouped_constrained_ordering) { - SymbolicFactorGraph sfg; // create graph with constrained groups: // 1: 2, 4 // 2: 5 - sfg.push_factor(0,1); - sfg.push_factor(1,2); - sfg.push_factor(2,3); - sfg.push_factor(3,4); - sfg.push_factor(4,5); + SymbolicFactorGraph sfg = example::symbolicChain(); // constrained version - push one set to the end FastMap constraints; @@ -74,50 +76,48 @@ TEST(Ordering, grouped_constrained_ordering) { constraints[4] = 1; constraints[5] = 2; - Ordering actConstrained = Ordering::colamdConstrained(sfg, constraints); + Ordering actConstrained = Ordering::ColamdConstrained(sfg, constraints); Ordering expConstrained = list_of(0)(1)(3)(2)(4)(5); EXPECT(assert_equal(expConstrained, actConstrained)); } /* ************************************************************************* */ TEST(Ordering, csr_format) { - // Example in METIS manual - SymbolicFactorGraph sfg; - sfg.push_factor(0, 1); - sfg.push_factor(1, 2); - sfg.push_factor(2, 3); - sfg.push_factor(3, 4); - sfg.push_factor(5, 6); - sfg.push_factor(6, 7); - sfg.push_factor(7, 8); - sfg.push_factor(8, 9); - sfg.push_factor(10, 11); - sfg.push_factor(11, 12); - sfg.push_factor(12, 13); - sfg.push_factor(13, 14); + // Example in METIS manual + SymbolicFactorGraph sfg; + sfg.push_factor(0, 1); + sfg.push_factor(1, 2); + sfg.push_factor(2, 3); + sfg.push_factor(3, 4); + sfg.push_factor(5, 6); + sfg.push_factor(6, 7); + sfg.push_factor(7, 8); + sfg.push_factor(8, 9); + sfg.push_factor(10, 11); + sfg.push_factor(11, 12); + sfg.push_factor(12, 13); + sfg.push_factor(13, 14); - sfg.push_factor(0, 5); - sfg.push_factor(5, 10); - sfg.push_factor(1, 6); - sfg.push_factor(6, 11); - sfg.push_factor(2, 7); - sfg.push_factor(7, 12); - sfg.push_factor(3, 8); - sfg.push_factor(8, 13); - sfg.push_factor(4, 9); - sfg.push_factor(9, 14); + sfg.push_factor(0, 5); + sfg.push_factor(5, 10); + sfg.push_factor(1, 6); + sfg.push_factor(6, 11); + sfg.push_factor(2, 7); + sfg.push_factor(7, 12); + sfg.push_factor(3, 8); + sfg.push_factor(8, 13); + sfg.push_factor(4, 9); + sfg.push_factor(9, 14); - MetisIndex mi(sfg); + MetisIndex mi(sfg); - vector xadjExpected, adjExpected; - xadjExpected += 0, 2, 5, 8, 11, 13, 16, 20, 24, 28, 31, 33, 36, 39, 42, 44; - adjExpected += 1, 5, 0, 2, 6, 1, 3, 7, 2, 4, 8, 3, 9, 0, 6, 10, 1, 5, 7, 11, - 2, 6, 8, 12, 3, 7, 9, 13, 4, 8, 14, 5, 11, 6, 10, 12, 7, 11, - 13, 8, 12, 14, 9, 13 ; + vector xadjExpected, adjExpected; + xadjExpected += 0, 2, 5, 8, 11, 13, 16, 20, 24, 28, 31, 33, 36, 39, 42, 44; + adjExpected += 1, 5, 0, 2, 6, 1, 3, 7, 2, 4, 8, 3, 9, 0, 6, 10, 1, 5, 7, 11, 2, 6, 8, 12, 3, 7, 9, 13, 4, 8, 14, 5, 11, 6, 10, 12, 7, 11, 13, 8, 12, 14, 9, 13; - EXPECT(xadjExpected == mi.xadj()); - EXPECT(adjExpected.size() == mi.adj().size()); - EXPECT(adjExpected == mi.adj()); + EXPECT(xadjExpected == mi.xadj()); + EXPECT(adjExpected.size() == mi.adj().size()); + EXPECT(adjExpected == mi.adj()); } /* ************************************************************************* */ @@ -135,12 +135,11 @@ TEST(Ordering, csr_format_2) { vector xadjExpected, adjExpected; xadjExpected += 0, 1, 4, 6, 8, 10; - adjExpected += 1, 0, 2, 4, 1, 3, 2, 4, 1, 3; + adjExpected += 1, 0, 2, 4, 1, 3, 2, 4, 1, 3; EXPECT(xadjExpected == mi.xadj()); EXPECT(adjExpected.size() == mi.adj().size()); EXPECT(adjExpected == mi.adj()); - } /* ************************************************************************* */ @@ -170,7 +169,6 @@ TEST(Ordering, csr_format_3) { EXPECT(xadjExpected == mi.xadj()); EXPECT(adjExpected.size() == mi.adj().size()); EXPECT(adjExpected == adjAcutal); - } /* ************************************************************************* */ @@ -197,7 +195,7 @@ TEST(Ordering, csr_format_4) { EXPECT(adjExpected.size() == mi.adj().size()); EXPECT(adjExpected == adjAcutal); - Ordering metOrder = Ordering::metis(sfg); + Ordering metOrder = Ordering::Metis(sfg); // Test different symbol types sfg.push_factor(Symbol('l', 1)); @@ -206,8 +204,7 @@ TEST(Ordering, csr_format_4) { sfg.push_factor(Symbol('x', 3), Symbol('l', 1)); sfg.push_factor(Symbol('x', 4), Symbol('l', 1)); - Ordering metOrder2 = Ordering::metis(sfg); - + Ordering metOrder2 = Ordering::Metis(sfg); } /* ************************************************************************* */ @@ -229,8 +226,77 @@ TEST(Ordering, metis) { EXPECT(adjExpected.size() == mi.adj().size()); EXPECT(adjExpected == mi.adj()); - Ordering metis = Ordering::metis(sfg); + Ordering metis = Ordering::Metis(sfg); +} + +/* ************************************************************************* */ +TEST(Ordering, MetisLoop) { + + // create linear graph + SymbolicFactorGraph sfg = example::symbolicChain(); + + // add loop closure + sfg.push_factor(0, 5); + + // METIS +#if !defined(__APPLE__) + { + Ordering actual = Ordering::Create(Ordering::METIS, sfg); + // - P( 0 4 1) + // | - P( 2 | 4 1) + // | | - P( 3 | 4 2) + // | - P( 5 | 0 1) + Ordering expected = Ordering(list_of(3)(2)(5)(0)(4)(1)); + EXPECT(assert_equal(expected, actual)); + } +#else + { + Ordering actual = Ordering::Create(Ordering::METIS, sfg); + // - P( 1 0 3) + // | - P( 4 | 0 3) + // | | - P( 5 | 0 4) + // | - P( 2 | 1 3) + Ordering expected = Ordering(list_of(5)(4)(2)(1)(0)(3)); + EXPECT(assert_equal(expected, actual)); + } +#endif +} + +/* ************************************************************************* */ +TEST(Ordering, Create) { + + // create chain graph + SymbolicFactorGraph sfg = example::symbolicChain(); + + // COLAMD + { + //- P( 4 5) + //| - P( 3 | 4) + //| | - P( 2 | 3) + //| | | - P( 1 | 2) + //| | | | - P( 0 | 1) + Ordering actual = Ordering::Create(Ordering::COLAMD, sfg); + Ordering expected = Ordering(list_of(0)(1)(2)(3)(4)(5)); + EXPECT(assert_equal(expected, actual)); + } + + // METIS + { + Ordering actual = Ordering::Create(Ordering::METIS, sfg); + //- P( 1 0 2) + //| - P( 3 4 | 2) + //| | - P( 5 | 4) + Ordering expected = Ordering(list_of(5)(3)(4)(1)(0)(2)); + EXPECT(assert_equal(expected, actual)); + } + + // CUSTOM + CHECK_EXCEPTION(Ordering::Create(Ordering::CUSTOM, sfg), runtime_error); +} + +/* ************************************************************************* */ +int main() { + TestResult tr; + return TestRegistry::runAllTests(tr); } /* ************************************************************************* */ -int main() { TestResult tr; return TestRegistry::runAllTests(tr); } -/* ************************************************************************* */ diff --git a/gtsam/linear/BinaryJacobianFactor.h b/gtsam/linear/BinaryJacobianFactor.h new file mode 100644 index 000000000..23d11964c --- /dev/null +++ b/gtsam/linear/BinaryJacobianFactor.h @@ -0,0 +1,91 @@ +/* ---------------------------------------------------------------------------- + + * 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 BinaryJacobianFactor.h + * + * @brief A binary JacobianFactor specialization that uses fixed matrix math for speed + * + * @date June 2015 + * @author Frank Dellaert + */ + +#pragma once + +#include +#include +#include + +namespace gtsam { + +/** + * A binary JacobianFactor specialization that uses fixed matrix math for speed + */ +template +struct BinaryJacobianFactor: JacobianFactor { + + /// Constructor + BinaryJacobianFactor(Key key1, const Eigen::Matrix& A1, + Key key2, const Eigen::Matrix& A2, + const Eigen::Matrix& b, // + const SharedDiagonal& model = SharedDiagonal()) : + JacobianFactor(key1, A1, key2, A2, b, model) { + } + + inline Key key1() const { + return keys_[0]; + } + inline Key key2() const { + return keys_[1]; + } + + // Fixed-size matrix update + void updateHessian(const FastVector& infoKeys, + SymmetricBlockMatrix* info) const { + gttic(updateHessian_BinaryJacobianFactor); + // Whiten the factor if it has a noise model + const SharedDiagonal& model = get_model(); + if (model && !model->isUnit()) { + if (model->isConstrained()) + throw std::invalid_argument( + "BinaryJacobianFactor::updateHessian: cannot update information with " + "constrained noise model"); + BinaryJacobianFactor whitenedFactor(key1(), model->Whiten(getA(begin())), + key2(), model->Whiten(getA(end())), model->whiten(getb())); + whitenedFactor.updateHessian(infoKeys, info); + } else { + // First build an array of slots + DenseIndex slot1 = Slot(infoKeys, key1()); + DenseIndex slot2 = Slot(infoKeys, key2()); + DenseIndex slotB = info->nBlocks() - 1; + + const Matrix& Ab = Ab_.matrix(); + Eigen::Block A1(Ab, 0, 0); + Eigen::Block A2(Ab, 0, N1); + Eigen::Block b(Ab, 0, N1 + N2); + + // We perform I += A'*A to the upper triangle + (*info)(slot1, slot1).selfadjointView().rankUpdate(A1.transpose()); + (*info)(slot1, slot2).knownOffDiagonal() += A1.transpose() * A2; + (*info)(slot1, slotB).knownOffDiagonal() += A1.transpose() * b; + (*info)(slot2, slot2).selfadjointView().rankUpdate(A2.transpose()); + (*info)(slot2, slotB).knownOffDiagonal() += A2.transpose() * b; + (*info)(slotB, slotB)(0, 0) += b.transpose() * b; + } + } +}; + +template +struct traits > : Testable< + BinaryJacobianFactor > { +}; + +} //namespace gtsam diff --git a/gtsam/linear/GaussianBayesNet.cpp b/gtsam/linear/GaussianBayesNet.cpp index b3b8b9a41..6db13adb6 100644 --- a/gtsam/linear/GaussianBayesNet.cpp +++ b/gtsam/linear/GaussianBayesNet.cpp @@ -141,7 +141,20 @@ namespace gtsam { /* ************************************************************************* */ pair GaussianBayesNet::matrix() const { - return GaussianFactorGraph(*this).jacobian(); + GaussianFactorGraph factorGraph(*this); + KeySet keys = factorGraph.keys(); + // add frontal keys in order + Ordering ordering; + BOOST_FOREACH (const sharedConditional& cg, *this) + BOOST_FOREACH (Key key, cg->frontals()) { + ordering.push_back(key); + keys.erase(key); + } + // add remaining keys in case Bayes net is incomplete + BOOST_FOREACH (Key key, keys) + ordering.push_back(key); + // return matrix and RHS + return factorGraph.jacobian(ordering); } ///* ************************************************************************* */ diff --git a/gtsam/linear/GaussianFactor.h b/gtsam/linear/GaussianFactor.h index 6a7d91bc9..7f9c5ea3c 100644 --- a/gtsam/linear/GaussianFactor.h +++ b/gtsam/linear/GaussianFactor.h @@ -28,6 +28,8 @@ namespace gtsam { // Forward declarations class VectorValues; + class Scatter; + class SymmetricBlockMatrix; /** * An abstract virtual base class for JacobianFactor and HessianFactor. A GaussianFactor has a @@ -119,6 +121,14 @@ namespace gtsam { */ virtual GaussianFactor::shared_ptr negate() const = 0; + /** Update an information matrix by adding the information corresponding to this factor + * (used internally during elimination). + * @param scatter A mapping from variable index to slot index in this HessianFactor + * @param info The information matrix to be updated + */ + virtual void updateHessian(const FastVector& keys, + SymmetricBlockMatrix* info) const = 0; + /// y += alpha * A'*A*x virtual void multiplyHessianAdd(double alpha, const VectorValues& x, VectorValues& y) const = 0; @@ -131,6 +141,12 @@ namespace gtsam { /// Gradient wrt a key at any values virtual Vector gradient(Key key, const VectorValues& x) const = 0; + // Determine position of a given key + template + static DenseIndex Slot(const CONTAINER& keys, Key key) { + return std::find(keys.begin(), keys.end(), key) - keys.begin(); + } + private: /** Serialization function */ friend class boost::serialization::access; @@ -140,7 +156,7 @@ namespace gtsam { } }; // GaussianFactor - + /// traits template<> struct traits : public Testable { diff --git a/gtsam/linear/GaussianFactorGraph.cpp b/gtsam/linear/GaussianFactorGraph.cpp index 6953d2969..a39b1d91e 100644 --- a/gtsam/linear/GaussianFactorGraph.cpp +++ b/gtsam/linear/GaussianFactorGraph.cpp @@ -47,7 +47,7 @@ namespace gtsam { /* ************************************************************************* */ GaussianFactorGraph::Keys GaussianFactorGraph::keys() const { - FastSet keys; + KeySet keys; BOOST_FOREACH(const sharedFactor& factor, *this) if (factor) keys.insert(factor->begin(), factor->end()); @@ -123,26 +123,32 @@ namespace gtsam { /* ************************************************************************* */ vector > GaussianFactorGraph::sparseJacobian() const { // First find dimensions of each variable - vector dims; + typedef std::map KeySizeMap; + KeySizeMap dims; BOOST_FOREACH(const sharedFactor& factor, *this) { - for (GaussianFactor::const_iterator pos = factor->begin(); - pos != factor->end(); ++pos) { - if (dims.size() <= *pos) - dims.resize(*pos + 1, 0); - dims[*pos] = factor->getDim(pos); + if (!static_cast(factor)) continue; + + for (GaussianFactor::const_iterator key = factor->begin(); + key != factor->end(); ++key) { + dims[*key] = factor->getDim(key); } } // Compute first scalar column of each variable - vector columnIndices(dims.size() + 1, 0); - for (size_t j = 1; j < dims.size() + 1; ++j) - columnIndices[j] = columnIndices[j - 1] + dims[j - 1]; + size_t currentColIndex = 0; + KeySizeMap columnIndices = dims; + BOOST_FOREACH(const KeySizeMap::value_type& col, dims) { + columnIndices[col.first] = currentColIndex; + currentColIndex += dims[col.first]; + } // Iterate over all factors, adding sparse scalar entries typedef boost::tuple triplet; vector entries; size_t row = 0; BOOST_FOREACH(const sharedFactor& factor, *this) { + if (!static_cast(factor)) continue; + // Convert to JacobianFactor if necessary JacobianFactor::shared_ptr jacobianFactor( boost::dynamic_pointer_cast(factor)); @@ -159,11 +165,11 @@ namespace gtsam { // Whiten the factor and add entries for it // iterate over all variables in the factor const JacobianFactor whitened(jacobianFactor->whiten()); - for (JacobianFactor::const_iterator pos = whitened.begin(); - pos < whitened.end(); ++pos) { - JacobianFactor::constABlock whitenedA = whitened.getA(pos); + for (JacobianFactor::const_iterator key = whitened.begin(); + key < whitened.end(); ++key) { + JacobianFactor::constABlock whitenedA = whitened.getA(key); // find first column index for this key - size_t column_start = columnIndices[*pos]; + size_t column_start = columnIndices[*key]; for (size_t i = 0; i < (size_t) whitenedA.rows(); i++) for (size_t j = 0; j < (size_t) whitenedA.cols(); j++) { double s = whitenedA(i, j); @@ -173,7 +179,7 @@ namespace gtsam { } JacobianFactor::constBVector whitenedb(whitened.getb()); - size_t bcolumn = columnIndices.back(); + size_t bcolumn = currentColIndex; for (size_t i = 0; i < (size_t) whitenedb.size(); i++) entries.push_back(boost::make_tuple(row + i, bcolumn, whitenedb(i))); diff --git a/gtsam/linear/GaussianFactorGraph.h b/gtsam/linear/GaussianFactorGraph.h index 832114ff6..02bc95511 100644 --- a/gtsam/linear/GaussianFactorGraph.h +++ b/gtsam/linear/GaussianFactorGraph.h @@ -135,7 +135,7 @@ namespace gtsam { * Return the set of variables involved in the factors (computes a set * union). */ - typedef FastSet Keys; + typedef KeySet Keys; Keys keys() const; /* return a map of (Key, dimension) */ diff --git a/gtsam/linear/HessianFactor.cpp b/gtsam/linear/HessianFactor.cpp index f2bebcab9..2b275b60f 100644 --- a/gtsam/linear/HessianFactor.cpp +++ b/gtsam/linear/HessianFactor.cpp @@ -15,17 +15,19 @@ * @date Dec 8, 2010 */ -#include -#include -#include -#include -#include -#include +#include + #include #include -#include -#include #include +#include +#include +#include +#include +#include +#include +#include +#include #include #include @@ -49,232 +51,185 @@ using namespace std; using namespace boost::assign; -namespace br { using namespace boost::range; using namespace boost::adaptors; } +namespace br { +using namespace boost::range; +using namespace boost::adaptors; +} namespace gtsam { -/* ************************************************************************* */ -string SlotEntry::toString() const { - ostringstream oss; - oss << "SlotEntry: slot=" << slot << ", dim=" << dimension; - return oss.str(); -} - -/* ************************************************************************* */ -Scatter::Scatter(const GaussianFactorGraph& gfg, - boost::optional ordering) { - gttic(Scatter_Constructor); - static const size_t none = std::numeric_limits::max(); - - // First do the set union. - BOOST_FOREACH(const GaussianFactor::shared_ptr& factor, gfg) { - if (factor) { - for (GaussianFactor::const_iterator variable = factor->begin(); - variable != factor->end(); ++variable) { - // TODO: Fix this hack to cope with zero-row Jacobians that come from BayesTreeOrphanWrappers - const JacobianFactor* asJacobian = - dynamic_cast(factor.get()); - if (!asJacobian || asJacobian->cols() > 1) - this->insert( - make_pair(*variable, SlotEntry(none, factor->getDim(variable)))); - } - } - } - - // If we have an ordering, pre-fill the ordered variables first - size_t slot = 0; - if (ordering) { - BOOST_FOREACH(Key key, *ordering) { - const_iterator entry = find(key); - if (entry == end()) - throw std::invalid_argument( - "The ordering provided to the HessianFactor Scatter constructor\n" - "contained extra variables that did not appear in the factors to combine."); - at(key).slot = (slot++); - } - } - - // Next fill in the slot indices (we can only get these after doing the set - // union. - BOOST_FOREACH(value_type& var_slot, *this) { - if (var_slot.second.slot == none) - var_slot.second.slot = (slot++); - } -} - /* ************************************************************************* */ HessianFactor::HessianFactor() : - info_(cref_list_of<1>(1)) -{ + info_(cref_list_of<1>(1)) { linearTerm().setZero(); constantTerm() = 0.0; } /* ************************************************************************* */ HessianFactor::HessianFactor(Key j, const Matrix& G, const Vector& g, double f) : - GaussianFactor(cref_list_of<1>(j)), info_(cref_list_of<2>(G.cols())(1)) -{ - if(G.rows() != G.cols() || G.rows() != g.size()) throw invalid_argument( - "Attempting to construct HessianFactor with inconsistent matrix and/or vector dimensions"); - info_(0,0) = G; - info_(0,1) = g; - info_(1,1)(0,0) = f; + GaussianFactor(cref_list_of<1>(j)), info_(cref_list_of<2>(G.cols())(1)) { + if (G.rows() != G.cols() || G.rows() != g.size()) + throw invalid_argument( + "Attempting to construct HessianFactor with inconsistent matrix and/or vector dimensions"); + info_(0, 0) = G; + info_(0, 1) = g; + info_(1, 1)(0, 0) = f; } /* ************************************************************************* */ // error is 0.5*(x-mu)'*inv(Sigma)*(x-mu) = 0.5*(x'*G*x - 2*x'*G*mu + mu'*G*mu) // where G = inv(Sigma), g = G*mu, f = mu'*G*mu = mu'*g HessianFactor::HessianFactor(Key j, const Vector& mu, const Matrix& Sigma) : - GaussianFactor(cref_list_of<1>(j)), - info_(cref_list_of<2> (Sigma.cols()) (1) ) -{ - if (Sigma.rows() != Sigma.cols() || Sigma.rows() != mu.size()) throw invalid_argument( - "Attempting to construct HessianFactor with inconsistent matrix and/or vector dimensions"); - info_(0,0) = Sigma.inverse(); // G - info_(0,1) = info_(0,0).selfadjointView() * mu; // g - info_(1,1)(0,0) = mu.dot(info_(0,1).knownOffDiagonal().col(0)); // f + GaussianFactor(cref_list_of<1>(j)), info_(cref_list_of<2>(Sigma.cols())(1)) { + if (Sigma.rows() != Sigma.cols() || Sigma.rows() != mu.size()) + throw invalid_argument( + "Attempting to construct HessianFactor with inconsistent matrix and/or vector dimensions"); + info_(0, 0) = Sigma.inverse(); // G + info_(0, 1) = info_(0, 0).selfadjointView() * mu; // g + info_(1, 1)(0, 0) = mu.dot(info_(0, 1).knownOffDiagonal().col(0)); // f } /* ************************************************************************* */ -HessianFactor::HessianFactor(Key j1, Key j2, - const Matrix& G11, const Matrix& G12, const Vector& g1, - const Matrix& G22, const Vector& g2, double f) : - GaussianFactor(cref_list_of<2>(j1)(j2)), - info_(cref_list_of<3> (G11.cols()) (G22.cols()) (1) ) -{ - info_(0,0) = G11; - info_(0,1) = G12; - info_(0,2) = g1; - info_(1,1) = G22; - info_(1,2) = g2; - info_(2,2)(0,0) = f; +HessianFactor::HessianFactor(Key j1, Key j2, const Matrix& G11, + const Matrix& G12, const Vector& g1, const Matrix& G22, const Vector& g2, + double f) : + GaussianFactor(cref_list_of<2>(j1)(j2)), info_( + cref_list_of<3>(G11.cols())(G22.cols())(1)) { + info_(0, 0) = G11; + info_(0, 1) = G12; + info_(0, 2) = g1; + info_(1, 1) = G22; + info_(1, 2) = g2; + info_(2, 2)(0, 0) = f; } /* ************************************************************************* */ -HessianFactor::HessianFactor(Key j1, Key j2, Key j3, - const Matrix& G11, const Matrix& G12, const Matrix& G13, const Vector& g1, - const Matrix& G22, const Matrix& G23, const Vector& g2, - const Matrix& G33, const Vector& g3, double f) : - GaussianFactor(cref_list_of<3>(j1)(j2)(j3)), - info_(cref_list_of<4> (G11.cols()) (G22.cols()) (G33.cols()) (1) ) -{ - if(G11.rows() != G11.cols() || G11.rows() != G12.rows() || G11.rows() != G13.rows() || G11.rows() != g1.size() || - G22.cols() != G12.cols() || G33.cols() != G13.cols() || G22.cols() != g2.size() || G33.cols() != g3.size()) - throw invalid_argument("Inconsistent matrix and/or vector dimensions in HessianFactor constructor"); - info_(0,0) = G11; - info_(0,1) = G12; - info_(0,2) = G13; - info_(0,3) = g1; - info_(1,1) = G22; - info_(1,2) = G23; - info_(1,3) = g2; - info_(2,2) = G33; - info_(2,3) = g3; - info_(3,3)(0,0) = f; +HessianFactor::HessianFactor(Key j1, Key j2, Key j3, const Matrix& G11, + const Matrix& G12, const Matrix& G13, const Vector& g1, const Matrix& G22, + const Matrix& G23, const Vector& g2, const Matrix& G33, const Vector& g3, + double f) : + GaussianFactor(cref_list_of<3>(j1)(j2)(j3)), info_( + cref_list_of<4>(G11.cols())(G22.cols())(G33.cols())(1)) { + if (G11.rows() != G11.cols() || G11.rows() != G12.rows() + || G11.rows() != G13.rows() || G11.rows() != g1.size() + || G22.cols() != G12.cols() || G33.cols() != G13.cols() + || G22.cols() != g2.size() || G33.cols() != g3.size()) + throw invalid_argument( + "Inconsistent matrix and/or vector dimensions in HessianFactor constructor"); + info_(0, 0) = G11; + info_(0, 1) = G12; + info_(0, 2) = G13; + info_(0, 3) = g1; + info_(1, 1) = G22; + info_(1, 2) = G23; + info_(1, 3) = g2; + info_(2, 2) = G33; + info_(2, 3) = g3; + info_(3, 3)(0, 0) = f; } /* ************************************************************************* */ namespace { -DenseIndex _getSizeHF(const Vector& m) { return m.size(); } +DenseIndex _getSizeHF(const Vector& m) { + return m.size(); +} } /* ************************************************************************* */ -HessianFactor::HessianFactor(const std::vector& js, const std::vector& Gs, - const std::vector& gs, double f) : - GaussianFactor(js), info_(gs | br::transformed(&_getSizeHF), true) -{ +HessianFactor::HessianFactor(const std::vector& js, + const std::vector& Gs, const std::vector& gs, double f) : + GaussianFactor(js), info_(gs | br::transformed(&_getSizeHF), true) { // Get the number of variables size_t variable_count = js.size(); // Verify the provided number of entries in the vectors are consistent - if(gs.size() != variable_count || Gs.size() != (variable_count*(variable_count+1))/2) - throw invalid_argument("Inconsistent number of entries between js, Gs, and gs in HessianFactor constructor.\nThe number of keys provided \ + if (gs.size() != variable_count + || Gs.size() != (variable_count * (variable_count + 1)) / 2) + throw invalid_argument( + "Inconsistent number of entries between js, Gs, and gs in HessianFactor constructor.\nThe number of keys provided \ in js must match the number of linear vector pieces in gs. The number of upper-diagonal blocks in Gs must be n*(n+1)/2"); // Verify the dimensions of each provided matrix are consistent // Note: equations for calculating the indices derived from the "sum of an arithmetic sequence" formula - for(size_t i = 0; i < variable_count; ++i){ + for (size_t i = 0; i < variable_count; ++i) { DenseIndex block_size = gs[i].size(); // Check rows - for(size_t j = 0; j < variable_count-i; ++j){ - size_t index = i*(2*variable_count - i + 1)/2 + j; - if(Gs[index].rows() != block_size){ - throw invalid_argument("Inconsistent matrix and/or vector dimensions in HessianFactor constructor"); + for (size_t j = 0; j < variable_count - i; ++j) { + size_t index = i * (2 * variable_count - i + 1) / 2 + j; + if (Gs[index].rows() != block_size) { + throw invalid_argument( + "Inconsistent matrix and/or vector dimensions in HessianFactor constructor"); } } // Check cols - for(size_t j = 0; j <= i; ++j){ - size_t index = j*(2*variable_count - j + 1)/2 + (i-j); - if(Gs[index].cols() != block_size){ - throw invalid_argument("Inconsistent matrix and/or vector dimensions in HessianFactor constructor"); + for (size_t j = 0; j <= i; ++j) { + size_t index = j * (2 * variable_count - j + 1) / 2 + (i - j); + if (Gs[index].cols() != block_size) { + throw invalid_argument( + "Inconsistent matrix and/or vector dimensions in HessianFactor constructor"); } } } // Fill in the blocks size_t index = 0; - for(size_t i = 0; i < variable_count; ++i){ - for(size_t j = i; j < variable_count; ++j){ + for (size_t i = 0; i < variable_count; ++i) { + for (size_t j = i; j < variable_count; ++j) { info_(i, j) = Gs[index++]; } info_(i, variable_count) = gs[i]; } - info_(variable_count, variable_count)(0,0) = f; + info_(variable_count, variable_count)(0, 0) = f; } /* ************************************************************************* */ namespace { -void _FromJacobianHelper(const JacobianFactor& jf, SymmetricBlockMatrix& info) -{ +void _FromJacobianHelper(const JacobianFactor& jf, SymmetricBlockMatrix& info) { gttic(HessianFactor_fromJacobian); const SharedDiagonal& jfModel = jf.get_model(); - if(jfModel) - { - if(jf.get_model()->isConstrained()) - throw invalid_argument("Cannot construct HessianFactor from JacobianFactor with constrained noise model"); - info.full().triangularView() = jf.matrixObject().full().transpose() * - (jfModel->invsigmas().array() * jfModel->invsigmas().array()).matrix().asDiagonal() * - jf.matrixObject().full(); + if (jfModel) { + if (jf.get_model()->isConstrained()) + throw invalid_argument( + "Cannot construct HessianFactor from JacobianFactor with constrained noise model"); + info.full().triangularView() = + jf.matrixObject().full().transpose() + * (jfModel->invsigmas().array() * jfModel->invsigmas().array()).matrix().asDiagonal() + * jf.matrixObject().full(); } else { - info.full().triangularView() = jf.matrixObject().full().transpose() * jf.matrixObject().full(); + info.full().triangularView() = jf.matrixObject().full().transpose() + * jf.matrixObject().full(); } } } /* ************************************************************************* */ HessianFactor::HessianFactor(const JacobianFactor& jf) : - GaussianFactor(jf), info_(SymmetricBlockMatrix::LikeActiveViewOf(jf.matrixObject())) -{ + GaussianFactor(jf), info_( + SymmetricBlockMatrix::LikeActiveViewOf(jf.matrixObject())) { _FromJacobianHelper(jf, info_); } /* ************************************************************************* */ HessianFactor::HessianFactor(const GaussianFactor& gf) : - GaussianFactor(gf) -{ + GaussianFactor(gf) { // Copy the matrix data depending on what type of factor we're copying from - if(const JacobianFactor* jf = dynamic_cast(&gf)) - { + if (const JacobianFactor* jf = dynamic_cast(&gf)) { info_ = SymmetricBlockMatrix::LikeActiveViewOf(jf->matrixObject()); _FromJacobianHelper(*jf, info_); - } - else if(const HessianFactor* hf = dynamic_cast(&gf)) - { + } else if (const HessianFactor* hf = dynamic_cast(&gf)) { info_ = hf->info_; - } - else - { - throw std::invalid_argument("In HessianFactor(const GaussianFactor& gf), gf is neither a JacobianFactor nor a HessianFactor"); + } else { + throw std::invalid_argument( + "In HessianFactor(const GaussianFactor& gf), gf is neither a JacobianFactor nor a HessianFactor"); } } /* ************************************************************************* */ HessianFactor::HessianFactor(const GaussianFactorGraph& factors, - boost::optional scatter) -{ + boost::optional scatter) { gttic(HessianFactor_MergeConstructor); boost::optional computedScatter; - if(!scatter) { + if (!scatter) { computedScatter = Scatter(factors); scatter = computedScatter; } @@ -282,11 +237,14 @@ HessianFactor::HessianFactor(const GaussianFactorGraph& factors, // Allocate and copy keys gttic(allocate); // Allocate with dimensions for each variable plus 1 at the end for the information vector - keys_.resize(scatter->size()); - FastVector dims(scatter->size() + 1); - BOOST_FOREACH(const Scatter::value_type& key_slotentry, *scatter) { - keys_[key_slotentry.second.slot] = key_slotentry.first; - dims[key_slotentry.second.slot] = key_slotentry.second.dimension; + const size_t n = scatter->size(); + keys_.resize(n); + FastVector dims(n + 1); + DenseIndex slot = 0; + BOOST_FOREACH(const SlotEntry& slotentry, *scatter) { + keys_[slot] = slotentry.key; + dims[slot] = slotentry.dimension; + ++slot; } dims.back() = 1; info_ = SymmetricBlockMatrix(dims); @@ -296,64 +254,50 @@ HessianFactor::HessianFactor(const GaussianFactorGraph& factors, // Form A' * A gttic(update); BOOST_FOREACH(const GaussianFactor::shared_ptr& factor, factors) - { - if(factor) { - if(const HessianFactor* hessian = dynamic_cast(factor.get())) - updateATA(*hessian, *scatter); - else if(const JacobianFactor* jacobian = dynamic_cast(factor.get())) - updateATA(*jacobian, *scatter); - else - throw invalid_argument("GaussianFactor is neither Hessian nor Jacobian"); - } - } + if (factor) + factor->updateHessian(keys_, &info_); gttoc(update); } /* ************************************************************************* */ -void HessianFactor::print(const std::string& s, const KeyFormatter& formatter) const { +void HessianFactor::print(const std::string& s, + const KeyFormatter& formatter) const { cout << s << "\n"; cout << " keys: "; - for(const_iterator key=this->begin(); key!=this->end(); ++key) - cout << formatter(*key) << "(" << this->getDim(key) << ") "; + for (const_iterator key = begin(); key != end(); ++key) + cout << formatter(*key) << "(" << getDim(key) << ") "; cout << "\n"; - gtsam::print(Matrix(info_.full().selfadjointView()), "Augmented information matrix: "); + gtsam::print(Matrix(info_.full().selfadjointView()), + "Augmented information matrix: "); } /* ************************************************************************* */ bool HessianFactor::equals(const GaussianFactor& lf, double tol) const { - if(!dynamic_cast(&lf)) + const HessianFactor* rhs = dynamic_cast(&lf); + if (!rhs || !Factor::equals(lf, tol)) return false; - else { - if(!Factor::equals(lf, tol)) - return false; - Matrix thisMatrix = this->info_.full().selfadjointView(); - thisMatrix(thisMatrix.rows()-1, thisMatrix.cols()-1) = 0.0; - Matrix rhsMatrix = static_cast(lf).info_.full().selfadjointView(); - rhsMatrix(rhsMatrix.rows()-1, rhsMatrix.cols()-1) = 0.0; - return equal_with_abs_tol(thisMatrix, rhsMatrix, tol); - } + return equal_with_abs_tol(augmentedInformation(), rhs->augmentedInformation(), + tol); } /* ************************************************************************* */ -Matrix HessianFactor::augmentedInformation() const -{ +Matrix HessianFactor::augmentedInformation() const { return info_.full().selfadjointView(); } /* ************************************************************************* */ -Matrix HessianFactor::information() const -{ - return info_.range(0, this->size(), 0, this->size()).selfadjointView(); +Matrix HessianFactor::information() const { + return info_.range(0, size(), 0, size()).selfadjointView(); } /* ************************************************************************* */ VectorValues HessianFactor::hessianDiagonal() const { VectorValues d; // Loop over all variables - for (DenseIndex j = 0; j < (DenseIndex)size(); ++j) { + for (DenseIndex j = 0; j < (DenseIndex) size(); ++j) { // Get the diagonal block, and insert its diagonal Matrix B = info_(j, j).selfadjointView(); - d.insert(keys_[j],B.diagonal()); + d.insert(keys_[j], B.diagonal()); } return d; } @@ -366,26 +310,24 @@ void HessianFactor::hessianDiagonal(double* d) const { } /* ************************************************************************* */ -map HessianFactor::hessianBlockDiagonal() const { - map blocks; +map HessianFactor::hessianBlockDiagonal() const { + map blocks; // Loop over all variables - for (DenseIndex j = 0; j < (DenseIndex)size(); ++j) { + for (DenseIndex j = 0; j < (DenseIndex) size(); ++j) { // Get the diagonal block, and insert it Matrix B = info_(j, j).selfadjointView(); - blocks.insert(make_pair(keys_[j],B)); + blocks.insert(make_pair(keys_[j], B)); } return blocks; } /* ************************************************************************* */ -Matrix HessianFactor::augmentedJacobian() const -{ +Matrix HessianFactor::augmentedJacobian() const { return JacobianFactor(*this).augmentedJacobian(); } /* ************************************************************************* */ -std::pair HessianFactor::jacobian() const -{ +std::pair HessianFactor::jacobian() const { return JacobianFactor(*this).jacobian(); } @@ -396,103 +338,34 @@ double HessianFactor::error(const VectorValues& c) const { double xtg = 0, xGx = 0; // extract the relevant subset of the VectorValues // NOTE may not be as efficient - const Vector x = c.vector(this->keys()); + const Vector x = c.vector(keys()); xtg = x.dot(linearTerm()); - xGx = x.transpose() * info_.range(0, this->size(), 0, this->size()).selfadjointView() * x; - return 0.5 * (f - 2.0 * xtg + xGx); + xGx = x.transpose() * info_.range(0, size(), 0, size()).selfadjointView() * x; + return 0.5 * (f - 2.0 * xtg + xGx); } /* ************************************************************************* */ -void HessianFactor::updateATA(const HessianFactor& update, const Scatter& scatter) -{ - gttic(updateATA); - // This function updates 'combined' with the information in 'update'. 'scatter' maps variables in - // the update factor to slots in the combined factor. - - // First build an array of slots - gttic(slots); - FastVector slots(update.size()); - DenseIndex slot = 0; - BOOST_FOREACH(Key j, update) { - slots[slot] = scatter.at(j).slot; - ++ slot; - } - gttoc(slots); - +void HessianFactor::updateHessian(const FastVector& infoKeys, + SymmetricBlockMatrix* info) const { + gttic(updateHessian_HessianFactor); // Apply updates to the upper triangle - gttic(update); - size_t nrInfoBlocks = this->info_.nBlocks(); - for(DenseIndex j2=0; j2nBlocks() - 1; + vector slots(n + 1); + for (DenseIndex j = 0; j <= n; ++j) { + const DenseIndex J = (j == n) ? N : Slot(infoKeys, keys_[j]); + slots[j] = J; + for (DenseIndex i = 0; i <= j; ++i) { + const DenseIndex I = slots[i]; // because i<=j, slots[i] is valid. + (*info)(I, J) += info_(i, j); } } - gttoc(update); -} - -/* ************************************************************************* */ -void HessianFactor::updateATA(const JacobianFactor& update, - const Scatter& scatter) { - - // This function updates 'combined' with the information in 'update'. - // 'scatter' maps variables in the update factor to slots in the combined - // factor. - - gttic(updateATA); - - if (update.rows() > 0) { - gttic(whiten); - // Whiten the factor if it has a noise model - boost::optional _whitenedFactor; - const JacobianFactor* whitenedFactor = &update; - if (update.get_model()) { - if (update.get_model()->isConstrained()) - throw invalid_argument( - "Cannot update HessianFactor from JacobianFactor with constrained noise model"); - _whitenedFactor = update.whiten(); - whitenedFactor = &(*_whitenedFactor); - } - gttoc(whiten); - - // A is the whitened Jacobian matrix A, and we are going to perform I += A'*A below - const VerticalBlockMatrix& A = whitenedFactor->matrixObject(); - - // N is number of variables in HessianFactor, n in JacobianFactor - DenseIndex N = this->info_.nBlocks() - 1, n = A.nBlocks() - 1; - - // First build an array of slots - gttic(slots); - FastVector slots(n + 1); - DenseIndex slot = 0; - BOOST_FOREACH(Key j, update) - slots[slot++] = scatter.at(j).slot; - slots[n] = N; - gttoc(slots); - - // Apply updates to the upper triangle - gttic(update); - // Loop over blocks of A, including RHS with j==n - for (DenseIndex j = 0; j <= n; ++j) { - DenseIndex J = slots[j]; // get block in Hessian - // Fill off-diagonal blocks with Ai'*Aj - for (DenseIndex i = 0; i < j; ++i) { - DenseIndex I = slots[i]; // get block in Hessian - info_(I, J).knownOffDiagonal() += A(i).transpose() * A(j); - } - // Fill diagonal block with Aj'*Aj - info_(J, J).selfadjointView().rankUpdate(A(j).transpose()); - } - gttoc(update); - } } /* ************************************************************************* */ -GaussianFactor::shared_ptr HessianFactor::negate() const -{ +GaussianFactor::shared_ptr HessianFactor::negate() const { shared_ptr result = boost::make_shared(*this); - result->info_.full().triangularView() = -result->info_.full().triangularView().nestedExpression(); // Negate the information matrix of the result + result->info_.full().triangularView() = + -result->info_.full().triangularView().nestedExpression(); // Negate the information matrix of the result return result; } @@ -509,7 +382,7 @@ void HessianFactor::multiplyHessianAdd(double alpha, const VectorValues& x, // Accessing the VectorValues one by one is expensive // So we will loop over columns to access x only once per column // And fill the above temporary y values, to be added into yvalues after - for (DenseIndex j = 0; j < (DenseIndex)size(); ++j) { + for (DenseIndex j = 0; j < (DenseIndex) size(); ++j) { // xj is the input vector Vector xj = x.at(keys_[j]); DenseIndex i = 0; @@ -518,13 +391,13 @@ void HessianFactor::multiplyHessianAdd(double alpha, const VectorValues& x, // blocks on the diagonal are only half y[i] += info_(j, j).selfadjointView() * xj; // for below diagonal, we take transpose block from upper triangular part - for (i = j + 1; i < (DenseIndex)size(); ++i) + for (i = j + 1; i < (DenseIndex) size(); ++i) y[i] += info_(i, j).knownOffDiagonal() * xj; } // copy to yvalues - for(DenseIndex i = 0; i < (DenseIndex)size(); ++i) { - bool didNotExist; + for (DenseIndex i = 0; i < (DenseIndex) size(); ++i) { + bool didNotExist; VectorValues::iterator it; boost::tie(it, didNotExist) = yvalues.tryInsert(keys_[i], Vector()); if (didNotExist) @@ -539,7 +412,7 @@ VectorValues HessianFactor::gradientAtZero() const { VectorValues g; size_t n = size(); for (size_t j = 0; j < n; ++j) - g.insert(keys_[j], -info_(j,n).knownOffDiagonal()); + g.insert(keys_[j], -info_(j, n).knownOffDiagonal()); return g; } @@ -562,8 +435,7 @@ Vector HessianFactor::gradient(Key key, const VectorValues& x) const { if (i > j) { Matrix Gji = info(j, i); Gij = Gji.transpose(); - } - else { + } else { Gij = info(i, j); } // Accumulate Gij*xj to gradf @@ -575,30 +447,34 @@ Vector HessianFactor::gradient(Key key, const VectorValues& x) const { } /* ************************************************************************* */ -std::pair, boost::shared_ptr > -EliminateCholesky(const GaussianFactorGraph& factors, const Ordering& keys) -{ +std::pair, + boost::shared_ptr > EliminateCholesky( + const GaussianFactorGraph& factors, const Ordering& keys) { gttic(EliminateCholesky); // Build joint factor HessianFactor::shared_ptr jointFactor; try { - jointFactor = boost::make_shared(factors, Scatter(factors, keys)); - } catch(std::invalid_argument&) { + jointFactor = boost::make_shared(factors, + Scatter(factors, keys)); + } catch (std::invalid_argument&) { throw InvalidDenseElimination( "EliminateCholesky was called with a request to eliminate variables that are not\n" - "involved in the provided factors."); + "involved in the provided factors."); } // Do dense elimination GaussianConditional::shared_ptr conditional; try { size_t numberOfKeysToEliminate = keys.size(); - VerticalBlockMatrix Ab = jointFactor->info_.choleskyPartial(numberOfKeysToEliminate); - conditional = boost::make_shared(jointFactor->keys(), numberOfKeysToEliminate, Ab); + VerticalBlockMatrix Ab = jointFactor->info_.choleskyPartial( + numberOfKeysToEliminate); + conditional = boost::make_shared(jointFactor->keys(), + numberOfKeysToEliminate, Ab); // Erase the eliminated keys in the remaining factor - jointFactor->keys_.erase(jointFactor->begin(), jointFactor->begin() + numberOfKeysToEliminate); - } catch(CholeskyFailed&) { + jointFactor->keys_.erase(jointFactor->begin(), + jointFactor->begin() + numberOfKeysToEliminate); + } catch (const CholeskyFailed& e) { throw IndeterminantLinearSystemException(keys.front()); } @@ -607,9 +483,9 @@ EliminateCholesky(const GaussianFactorGraph& factors, const Ordering& keys) } /* ************************************************************************* */ -std::pair, boost::shared_ptr > -EliminatePreferCholesky(const GaussianFactorGraph& factors, const Ordering& keys) -{ +std::pair, + boost::shared_ptr > EliminatePreferCholesky( + const GaussianFactorGraph& factors, const Ordering& keys) { gttic(EliminatePreferCholesky); // If any JacobianFactors have constrained noise models, we have to convert diff --git a/gtsam/linear/HessianFactor.h b/gtsam/linear/HessianFactor.h index dbec5bb59..b74d557ea 100644 --- a/gtsam/linear/HessianFactor.h +++ b/gtsam/linear/HessianFactor.h @@ -18,10 +18,10 @@ #pragma once +#include +#include #include #include -#include -#include #include @@ -41,30 +41,6 @@ namespace gtsam { GTSAM_EXPORT std::pair, boost::shared_ptr > EliminateCholesky(const GaussianFactorGraph& factors, const Ordering& keys); - /** - * One SlotEntry stores the slot index for a variable, as well its dimension. - */ - struct GTSAM_EXPORT SlotEntry { - size_t slot, dimension; - SlotEntry(size_t _slot, size_t _dimension) - : slot(_slot), dimension(_dimension) {} - std::string toString() const; - }; - - /** - * Scatter is an intermediate data structure used when building a HessianFactor - * incrementally, to get the keys in the right order. The "scatter" is a map from - * global variable indices to slot indices in the union of involved variables. - * We also include the dimensionality of the variable. - */ - class Scatter: public FastMap { - public: - Scatter() { - } - Scatter(const GaussianFactorGraph& gfg, - boost::optional ordering = boost::none); - }; - /** * @brief A Gaussian factor using the canonical parameters (information form) * @@ -363,19 +339,12 @@ namespace gtsam { /** Return the full augmented Hessian matrix of this factor as a SymmetricBlockMatrix object. */ const SymmetricBlockMatrix& matrixObject() const { return info_; } - /** Update the factor by adding the information from the JacobianFactor + /** Update an information matrix by adding the information corresponding to this factor * (used internally during elimination). - * @param update The JacobianFactor containing the new information to add * @param scatter A mapping from variable index to slot index in this HessianFactor + * @param info The information matrix to be updated */ - void updateATA(const JacobianFactor& update, const Scatter& scatter); - - /** Update the factor by adding the information from the HessianFactor - * (used internally during elimination). - * @param update The HessianFactor containing the new information to add - * @param scatter A mapping from variable index to slot index in this HessianFactor - */ - void updateATA(const HessianFactor& update, const Scatter& scatter); + void updateHessian(const FastVector& keys, SymmetricBlockMatrix* info) const; /** y += alpha * A'*A*x */ void multiplyHessianAdd(double alpha, const VectorValues& x, VectorValues& y) const; diff --git a/gtsam/linear/JacobianFactor.cpp b/gtsam/linear/JacobianFactor.cpp index 597925eea..d4df57298 100644 --- a/gtsam/linear/JacobianFactor.cpp +++ b/gtsam/linear/JacobianFactor.cpp @@ -20,7 +20,7 @@ #include #include #include -#include +#include #include #include #include @@ -66,10 +66,10 @@ JacobianFactor::JacobianFactor() : /* ************************************************************************* */ JacobianFactor::JacobianFactor(const GaussianFactor& gf) { // Copy the matrix data depending on what type of factor we're copying from - if (const JacobianFactor* rhs = dynamic_cast(&gf)) - *this = JacobianFactor(*rhs); - else if (const HessianFactor* rhs = dynamic_cast(&gf)) - *this = JacobianFactor(*rhs); + if (const JacobianFactor* asJacobian = dynamic_cast(&gf)) + *this = JacobianFactor(*asJacobian); + else if (const HessianFactor* asHessian = dynamic_cast(&gf)) + *this = JacobianFactor(*asHessian); else throw std::invalid_argument( "In JacobianFactor(const GaussianFactor& rhs), rhs is neither a JacobianFactor nor a HessianFactor"); @@ -347,13 +347,21 @@ JacobianFactor::JacobianFactor(const GaussianFactorGraph& graph, /* ************************************************************************* */ void JacobianFactor::print(const string& s, const KeyFormatter& formatter) const { + static const Eigen::IOFormat matlab( + Eigen::StreamPrecision, // precision + 0, // flags + " ", // coeffSeparator + ";\n", // rowSeparator + "\t", // rowPrefix + "", // rowSuffix + "[\n", // matPrefix + "\n ]" // matSuffix + ); if (!s.empty()) cout << s << "\n"; for (const_iterator key = begin(); key != end(); ++key) { - cout - << formatMatrixIndented( - (boost::format(" A[%1%] = ") % formatter(*key)).str(), getA(key)) - << endl; + cout << boost::format(" A[%1%] = ") % formatter(*key); + cout << getA(key).format(matlab) << endl; } cout << formatMatrixIndented(" b = ", getb(), true) << "\n"; if (model_) @@ -432,8 +440,6 @@ Vector JacobianFactor::error_vector(const VectorValues& c) const { /* ************************************************************************* */ double JacobianFactor::error(const VectorValues& c) const { - if (empty()) - return 0; Vector weighted = error_vector(c); return 0.5 * weighted.dot(weighted); } @@ -497,6 +503,43 @@ map JacobianFactor::hessianBlockDiagonal() const { return blocks; } +/* ************************************************************************* */ +void JacobianFactor::updateHessian(const FastVector& infoKeys, + SymmetricBlockMatrix* info) const { + gttic(updateHessian_JacobianFactor); + + if (rows() == 0) return; + + // Whiten the factor if it has a noise model + const SharedDiagonal& model = get_model(); + if (model && !model->isUnit()) { + if (model->isConstrained()) + throw invalid_argument( + "JacobianFactor::updateHessian: cannot update information with " + "constrained noise model"); + JacobianFactor whitenedFactor = whiten(); + whitenedFactor.updateHessian(infoKeys, info); + } else { + // Ab_ is the augmented Jacobian matrix A, and we perform I += A'*A below + DenseIndex n = Ab_.nBlocks() - 1, N = info->nBlocks() - 1; + + // Apply updates to the upper triangle + // Loop over blocks of A, including RHS with j==n + vector slots(n+1); + for (DenseIndex j = 0; j <= n; ++j) { + const DenseIndex J = (j == n) ? N : Slot(infoKeys, keys_[j]); + slots[j] = J; + // Fill off-diagonal blocks with Ai'*Aj + for (DenseIndex i = 0; i < j; ++i) { + const DenseIndex I = slots[i]; // because i, jointFactor->Ab_.matrix().triangularView().setZero(); // Split elimination result into conditional and remaining factor - GaussianConditional::shared_ptr conditional = jointFactor->splitConditional( - keys.size()); + GaussianConditional::shared_ptr conditional = // + jointFactor->splitConditional(keys.size()); return make_pair(conditional, jointFactor); } @@ -722,11 +765,11 @@ GaussianConditional::shared_ptr JacobianFactor::splitConditional( } GaussianConditional::shared_ptr conditional = boost::make_shared< GaussianConditional>(Base::keys_, nrFrontals, Ab_, conditionalNoiseModel); - const DenseIndex maxRemainingRows = std::min(Ab_.cols() - 1, originalRowEnd) + const DenseIndex maxRemainingRows = std::min(Ab_.cols(), originalRowEnd) - Ab_.rowStart() - frontalDim; const DenseIndex remainingRows = - model_ ? - std::min(model_->sigmas().size() - frontalDim, maxRemainingRows) : + model_ ? std::min(model_->sigmas().size() - frontalDim, + maxRemainingRows) : maxRemainingRows; Ab_.rowStart() += frontalDim; Ab_.rowEnd() = Ab_.rowStart() + remainingRows; diff --git a/gtsam/linear/JacobianFactor.h b/gtsam/linear/JacobianFactor.h index 319d9faba..ea9958474 100644 --- a/gtsam/linear/JacobianFactor.h +++ b/gtsam/linear/JacobianFactor.h @@ -273,6 +273,13 @@ namespace gtsam { /** Get a view of the A matrix */ ABlock getA() { return Ab_.range(0, size()); } + /** Update an information matrix by adding the information corresponding to this factor + * (used internally during elimination). + * @param scatter A mapping from variable index to slot index in this HessianFactor + * @param info The information matrix to be updated + */ + void updateHessian(const FastVector& keys, SymmetricBlockMatrix* info) const; + /** Return A*x */ Vector operator*(const VectorValues& x) const; diff --git a/gtsam/linear/NoiseModel.cpp b/gtsam/linear/NoiseModel.cpp index a8b177b43..cb77902d0 100644 --- a/gtsam/linear/NoiseModel.cpp +++ b/gtsam/linear/NoiseModel.cpp @@ -20,6 +20,7 @@ #include #include +#include #include #include #include @@ -376,8 +377,11 @@ double Constrained::distance(const Vector& v) const { /* ************************************************************************* */ Matrix Constrained::Whiten(const Matrix& H) const { - // selective scaling - return vector_scale(invsigmas(), H, true); + Matrix A = H; + for (DenseIndex i=0; i<(DenseIndex)dim_; ++i) + if (!constrained(i)) // if constrained, leave row of A as is + A.row(i) *= invsigmas_(i); + return A; } /* ************************************************************************* */ @@ -503,7 +507,7 @@ Isotropic::shared_ptr Isotropic::Variance(size_t dim, double variance, bool smar /* ************************************************************************* */ void Isotropic::print(const string& name) const { - cout << name << "isotropic sigma " << " " << sigma_ << endl; + cout << boost::format("isotropic dim=%1% sigma=%2%") % dim() % sigma_ << endl; } /* ************************************************************************* */ @@ -531,6 +535,11 @@ void Isotropic::WhitenInPlace(Matrix& H) const { H *= invsigma_; } +/* ************************************************************************* */ +void Isotropic::whitenInPlace(Vector& v) const { + v *= invsigma_; +} + /* ************************************************************************* */ void Isotropic::WhitenInPlace(Eigen::Block H) const { H *= invsigma_; @@ -687,7 +696,7 @@ Huber::Huber(double k, const ReweightScheme reweight) } double Huber::weight(double error) const { - return (error < k_) ? (1.0) : (k_ / fabs(error)); + return (fabs(error) > k_) ? k_ / fabs(error) : 1.0; } void Huber::print(const std::string &s="") const { @@ -790,6 +799,66 @@ Welsh::shared_ptr Welsh::Create(double c, const ReweightScheme reweight) { return shared_ptr(new Welsh(c, reweight)); } +/* ************************************************************************* */ +// GemanMcClure +/* ************************************************************************* */ +GemanMcClure::GemanMcClure(double c, const ReweightScheme reweight) + : Base(reweight), c_(c) { +} + +double GemanMcClure::weight(double error) const { + const double c2 = c_*c_; + const double c4 = c2*c2; + const double c2error = c2 + error*error; + return c4/(c2error*c2error); +} + +void GemanMcClure::print(const std::string &s="") const { + std::cout << s << ": Geman-McClure (" << c_ << ")" << std::endl; +} + +bool GemanMcClure::equals(const Base &expected, double tol) const { + const GemanMcClure* p = dynamic_cast(&expected); + if (p == NULL) return false; + return fabs(c_ - p->c_) < tol; +} + +GemanMcClure::shared_ptr GemanMcClure::Create(double c, const ReweightScheme reweight) { + return shared_ptr(new GemanMcClure(c, reweight)); +} + +/* ************************************************************************* */ +// DCS +/* ************************************************************************* */ +DCS::DCS(double c, const ReweightScheme reweight) + : Base(reweight), c_(c) { +} + +double DCS::weight(double error) const { + const double e2 = error*error; + if (e2 > c_) + { + const double w = 2.0*c_/(c_ + e2); + return w*w; + } + + return 1.0; +} + +void DCS::print(const std::string &s="") const { + std::cout << s << ": DCS (" << c_ << ")" << std::endl; +} + +bool DCS::equals(const Base &expected, double tol) const { + const DCS* p = dynamic_cast(&expected); + if (p == NULL) return false; + return fabs(c_ - p->c_) < tol; +} + +DCS::shared_ptr DCS::Create(double c, const ReweightScheme reweight) { + return shared_ptr(new DCS(c, reweight)); +} + } // namespace mEstimator /* ************************************************************************* */ diff --git a/gtsam/linear/NoiseModel.h b/gtsam/linear/NoiseModel.h index 923e7c7e9..db01152f6 100644 --- a/gtsam/linear/NoiseModel.h +++ b/gtsam/linear/NoiseModel.h @@ -20,6 +20,7 @@ #include #include +#include #include #include @@ -62,10 +63,11 @@ namespace gtsam { Base(size_t dim = 1):dim_(dim) {} virtual ~Base() {} - /// true if a constrained noise mode, saves slow/clumsy dynamic casting - virtual bool isConstrained() const { - return false; // default false - } + /// true if a constrained noise model, saves slow/clumsy dynamic casting + virtual bool isConstrained() const { return false; } // default false + + /// true if a unit noise model, saves slow/clumsy dynamic casting + virtual bool isUnit() const { return false; } // default false /// Dimensionality inline size_t dim() const { return dim_;} @@ -80,6 +82,9 @@ namespace gtsam { /// Whiten an error vector. virtual Vector whiten(const Vector& v) const = 0; + /// Whiten a matrix. + virtual Matrix Whiten(const Matrix& H) const = 0; + /// Unwhiten an error vector. virtual Vector unwhiten(const Vector& v) const = 0; @@ -237,7 +242,7 @@ namespace gtsam { virtual Matrix R() const { return thisR();} /// Compute information matrix - virtual Matrix information() const { return thisR().transpose() * thisR(); } + virtual Matrix information() const { return R().transpose() * R(); } /// Compute covariance matrix virtual Matrix covariance() const { return information().inverse(); } @@ -390,9 +395,7 @@ namespace gtsam { virtual ~Constrained() {} /// true if a constrained noise mode, saves slow/clumsy dynamic casting - virtual bool isConstrained() const { - return true; - } + virtual bool isConstrained() const { return true; } /// Return true if a particular dimension is free or constrained bool constrained(size_t i) const; @@ -548,6 +551,7 @@ namespace gtsam { virtual Vector unwhiten(const Vector& v) const; virtual Matrix Whiten(const Matrix& H) const; virtual void WhitenInPlace(Matrix& H) const; + virtual void whitenInPlace(Vector& v) const; virtual void WhitenInPlace(Eigen::Block H) const; /** @@ -590,6 +594,9 @@ namespace gtsam { return shared_ptr(new Unit(dim)); } + /// true if a unit noise model, saves slow/clumsy dynamic casting + virtual bool isUnit() const { return true; } + virtual void print(const std::string& name) const; virtual double Mahalanobis(const Vector& v) const {return v.dot(v); } virtual Vector whiten(const Vector& v) const { return v; } @@ -816,6 +823,65 @@ namespace gtsam { } }; + /// GemanMcClure implements the "Geman-McClure" robust error model + /// (Zhang97ivc). + /// + /// Note that Geman-McClure weight function uses the parameter c == 1.0, + /// but here it's allowed to use different values, so we actually have + /// the generalized Geman-McClure from (Agarwal15phd). + class GTSAM_EXPORT GemanMcClure : public Base { + public: + typedef boost::shared_ptr shared_ptr; + + GemanMcClure(double c = 1.0, const ReweightScheme reweight = Block); + virtual ~GemanMcClure() {} + virtual double weight(double error) const; + virtual void print(const std::string &s) const; + virtual bool equals(const Base& expected, double tol=1e-8) const; + static shared_ptr Create(double k, const ReweightScheme reweight = Block) ; + + protected: + double c_; + + private: + /** Serialization function */ + friend class boost::serialization::access; + template + void serialize(ARCHIVE & ar, const unsigned int /*version*/) { + ar & BOOST_SERIALIZATION_BASE_OBJECT_NVP(Base); + ar & BOOST_SERIALIZATION_NVP(c_); + } + }; + + /// DCS implements the Dynamic Covariance Scaling robust error model + /// from the paper Robust Map Optimization (Agarwal13icra). + /// + /// Under the special condition of the parameter c == 1.0 and not + /// forcing the output weight s <= 1.0, DCS is similar to Geman-McClure. + class GTSAM_EXPORT DCS : public Base { + public: + typedef boost::shared_ptr shared_ptr; + + DCS(double c = 1.0, const ReweightScheme reweight = Block); + virtual ~DCS() {} + virtual double weight(double error) const; + virtual void print(const std::string &s) const; + virtual bool equals(const Base& expected, double tol=1e-8) const; + static shared_ptr Create(double k, const ReweightScheme reweight = Block) ; + + protected: + double c_; + + private: + /** Serialization function */ + friend class boost::serialization::access; + template + void serialize(ARCHIVE & ar, const unsigned int /*version*/) { + ar & BOOST_SERIALIZATION_BASE_OBJECT_NVP(Base); + ar & BOOST_SERIALIZATION_NVP(c_); + } + }; + } ///\namespace mEstimator /// Base class for robust error models @@ -854,6 +920,8 @@ namespace gtsam { // TODO: functions below are dummy but necessary for the noiseModel::Base inline virtual Vector whiten(const Vector& v) const { Vector r = v; this->WhitenSystem(r); return r; } + inline virtual Matrix Whiten(const Matrix& A) const + { Vector b; Matrix B=A; this->WhitenSystem(B,b); return B; } inline virtual Vector unwhiten(const Vector& /*v*/) const { throw std::invalid_argument("unwhiten is not currently supported for robust noise models."); } inline virtual double distance(const Vector& v) const diff --git a/gtsam/slam/RegularHessianFactor.h b/gtsam/linear/RegularHessianFactor.h similarity index 64% rename from gtsam/slam/RegularHessianFactor.h rename to gtsam/linear/RegularHessianFactor.h index 5765f67fd..e5e545c36 100644 --- a/gtsam/slam/RegularHessianFactor.h +++ b/gtsam/linear/RegularHessianFactor.h @@ -19,6 +19,7 @@ #pragma once #include +#include #include #include @@ -27,15 +28,11 @@ namespace gtsam { template class RegularHessianFactor: public HessianFactor { -private: - - // Use Eigen magic to access raw memory - typedef Eigen::Matrix DVector; - typedef Eigen::Map DMap; - typedef Eigen::Map ConstDMap; - public: + typedef Eigen::Matrix VectorD; + typedef Eigen::Matrix MatrixD; + /** Construct an n-way factor. Gs contains the upper-triangle blocks of the * quadratic term (the Hessian matrix) provided in row-order, gs the pieces * of the linear vector term, and f the constant term. @@ -43,27 +40,68 @@ public: RegularHessianFactor(const std::vector& js, const std::vector& Gs, const std::vector& gs, double f) : HessianFactor(js, Gs, gs, f) { + checkInvariants(); } /** Construct a binary factor. Gxx are the upper-triangle blocks of the * quadratic term (the Hessian matrix), gx the pieces of the linear vector * term, and f the constant term. */ - RegularHessianFactor(Key j1, Key j2, const Matrix& G11, const Matrix& G12, - const Vector& g1, const Matrix& G22, const Vector& g2, double f) : + RegularHessianFactor(Key j1, Key j2, const MatrixD& G11, const MatrixD& G12, + const VectorD& g1, const MatrixD& G22, const VectorD& g2, double f) : HessianFactor(j1, j2, G11, G12, g1, G22, g2, f) { } + /** Construct a ternary factor. Gxx are the upper-triangle blocks of the + * quadratic term (the Hessian matrix), gx the pieces of the linear vector + * term, and f the constant term. + */ + RegularHessianFactor(Key j1, Key j2, Key j3, + const MatrixD& G11, const MatrixD& G12, const MatrixD& G13, const VectorD& g1, + const MatrixD& G22, const MatrixD& G23, const VectorD& g2, + const MatrixD& G33, const VectorD& g3, double f) : + HessianFactor(j1, j2, j3, G11, G12, G13, g1, G22, G23, g2, G33, g3, f) { + } + /** Constructor with an arbitrary number of keys and with the augmented information matrix * specified as a block matrix. */ template RegularHessianFactor(const KEYS& keys, const SymmetricBlockMatrix& augmentedInformation) : HessianFactor(keys, augmentedInformation) { + checkInvariants(); } + /// Construct from RegularJacobianFactor + RegularHessianFactor(const RegularJacobianFactor& jf) + : HessianFactor(jf) {} + + /// Construct from a GaussianFactorGraph + RegularHessianFactor(const GaussianFactorGraph& factors, + boost::optional scatter = boost::none) + : HessianFactor(factors, scatter) { + checkInvariants(); + } + +private: + + /// Check invariants after construction + void checkInvariants() { + if (info_.cols() != 1 + (info_.nBlocks()-1) * (DenseIndex)D) + throw std::invalid_argument( + "RegularHessianFactor constructor was given non-regular factors"); + } + + // Use Eigen magic to access raw memory + typedef Eigen::Map DMap; + typedef Eigen::Map ConstDMap; + // Scratch space for multiplyHessianAdd - mutable std::vector y; + // According to link below this is thread-safe. + // http://stackoverflow.com/questions/11160964/multiple-copies-of-the-same-object-c-thread-safe + mutable std::vector y_; + +public: /** y += alpha * A'*A*x */ virtual void multiplyHessianAdd(double alpha, const VectorValues& x, @@ -74,32 +112,32 @@ public: /** y += alpha * A'*A*x */ void multiplyHessianAdd(double alpha, const double* x, double* yvalues) const { - // Create a vector of temporary y values, corresponding to rows i - y.resize(size()); - BOOST_FOREACH(DVector & yi, y) + // Create a vector of temporary y_ values, corresponding to rows i + y_.resize(size()); + BOOST_FOREACH(VectorD & yi, y_) yi.setZero(); // Accessing the VectorValues one by one is expensive // So we will loop over columns to access x only once per column - // And fill the above temporary y values, to be added into yvalues after - DVector xj(D); + // And fill the above temporary y_ values, to be added into yvalues after + VectorD xj(D); for (DenseIndex j = 0; j < (DenseIndex) size(); ++j) { Key key = keys_[j]; const double* xj = x + key * D; DenseIndex i = 0; for (; i < j; ++i) - y[i] += info_(i, j).knownOffDiagonal() * ConstDMap(xj); + y_[i] += info_(i, j).knownOffDiagonal() * ConstDMap(xj); // blocks on the diagonal are only half - y[i] += info_(j, j).selfadjointView() * ConstDMap(xj); + y_[i] += info_(j, j).selfadjointView() * ConstDMap(xj); // for below diagonal, we take transpose block from upper triangular part for (i = j + 1; i < (DenseIndex) size(); ++i) - y[i] += info_(i, j).knownOffDiagonal() * ConstDMap(xj); + y_[i] += info_(i, j).knownOffDiagonal() * ConstDMap(xj); } // copy to yvalues for (DenseIndex i = 0; i < (DenseIndex) size(); ++i) { Key key = keys_[i]; - DMap(yvalues + key * D) += alpha * y[i]; + DMap(yvalues + key * D) += alpha * y_[i]; } } @@ -107,28 +145,27 @@ public: void multiplyHessianAdd(double alpha, const double* x, double* yvalues, std::vector offsets) const { - // Create a vector of temporary y values, corresponding to rows i - std::vector y; - y.reserve(size()); - for (const_iterator it = begin(); it != end(); it++) - y.push_back(zero(getDim(it))); + // Create a vector of temporary y_ values, corresponding to rows i + y_.resize(size()); + BOOST_FOREACH(VectorD & yi, y_) + yi.setZero(); // Accessing the VectorValues one by one is expensive // So we will loop over columns to access x only once per column - // And fill the above temporary y values, to be added into yvalues after + // And fill the above temporary y_ values, to be added into yvalues after for (DenseIndex j = 0; j < (DenseIndex) size(); ++j) { DenseIndex i = 0; for (; i < j; ++i) - y[i] += info_(i, j).knownOffDiagonal() + y_[i] += info_(i, j).knownOffDiagonal() * ConstDMap(x + offsets[keys_[j]], offsets[keys_[j] + 1] - offsets[keys_[j]]); // blocks on the diagonal are only half - y[i] += info_(j, j).selfadjointView() + y_[i] += info_(j, j).selfadjointView() * ConstDMap(x + offsets[keys_[j]], offsets[keys_[j] + 1] - offsets[keys_[j]]); // for below diagonal, we take transpose block from upper triangular part for (i = j + 1; i < (DenseIndex) size(); ++i) - y[i] += info_(i, j).knownOffDiagonal() + y_[i] += info_(i, j).knownOffDiagonal() * ConstDMap(x + offsets[keys_[j]], offsets[keys_[j] + 1] - offsets[keys_[j]]); } @@ -136,7 +173,7 @@ public: // copy to yvalues for (DenseIndex i = 0; i < (DenseIndex) size(); ++i) DMap(yvalues + offsets[keys_[i]], - offsets[keys_[i] + 1] - offsets[keys_[i]]) += alpha * y[i]; + offsets[keys_[i] + 1] - offsets[keys_[i]]) += alpha * y_[i]; } /** Return the diagonal of the Hessian for this factor (raw memory version) */ @@ -158,7 +195,7 @@ public: for (DenseIndex pos = 0; pos < (DenseIndex) size(); ++pos) { Key j = keys_[pos]; // Get the diagonal block, and insert its diagonal - DVector dj = -info_(pos, size()).knownOffDiagonal(); + VectorD dj = -info_(pos, size()).knownOffDiagonal(); DMap(d + D * j) += dj; } } diff --git a/gtsam/slam/RegularJacobianFactor.h b/gtsam/linear/RegularJacobianFactor.h similarity index 100% rename from gtsam/slam/RegularJacobianFactor.h rename to gtsam/linear/RegularJacobianFactor.h diff --git a/gtsam/linear/Sampler.cpp b/gtsam/linear/Sampler.cpp index 48972a953..bfbc222ba 100644 --- a/gtsam/linear/Sampler.cpp +++ b/gtsam/linear/Sampler.cpp @@ -14,9 +14,6 @@ * @author Alex Cunningham */ -#include -#include - #include namespace gtsam { @@ -51,7 +48,7 @@ Vector Sampler::sampleDiagonal(const Vector& sigmas) { } else { typedef boost::normal_distribution Normal; Normal dist(0.0, sigma); - boost::variate_generator norm(generator_, dist); + boost::variate_generator norm(generator_, dist); result(i) = norm(); } } diff --git a/gtsam/linear/Sampler.h b/gtsam/linear/Sampler.h index f2632308b..6c84bfda2 100644 --- a/gtsam/linear/Sampler.h +++ b/gtsam/linear/Sampler.h @@ -20,7 +20,7 @@ #include -#include +#include namespace gtsam { @@ -37,7 +37,7 @@ protected: noiseModel::Diagonal::shared_ptr model_; /** generator */ - boost::minstd_rand generator_; + boost::mt19937_64 generator_; public: typedef boost::shared_ptr shared_ptr; diff --git a/gtsam/linear/Scatter.cpp b/gtsam/linear/Scatter.cpp new file mode 100644 index 000000000..ed2af529f --- /dev/null +++ b/gtsam/linear/Scatter.cpp @@ -0,0 +1,91 @@ +/* ---------------------------------------------------------------------------- + + * 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 Scatter.cpp + * @author Richard Roberts + * @author Frank Dellaert + * @date June 2015 + */ + +#include +#include +#include + +#include +#include + +using namespace std; + +namespace gtsam { + +/* ************************************************************************* */ +string SlotEntry::toString() const { + ostringstream oss; + oss << "SlotEntry: key=" << key << ", dim=" << dimension; + return oss.str(); +} + +/* ************************************************************************* */ +Scatter::Scatter(const GaussianFactorGraph& gfg, + boost::optional ordering) { + gttic(Scatter_Constructor); + + // If we have an ordering, pre-fill the ordered variables first + if (ordering) { + BOOST_FOREACH (Key key, *ordering) { + push_back(SlotEntry(key, 0)); + } + } + + // Now, find dimensions of variables and/or extend + BOOST_FOREACH (const GaussianFactor::shared_ptr& factor, gfg) { + if (!factor) continue; + + // TODO: Fix this hack to cope with zero-row Jacobians that come from BayesTreeOrphanWrappers + const JacobianFactor* asJacobian = dynamic_cast(factor.get()); + if (asJacobian && asJacobian->cols() <= 1) continue; + + // loop over variables + for (GaussianFactor::const_iterator variable = factor->begin(); + variable != factor->end(); ++variable) { + const Key key = *variable; + iterator it = find(key); // theoretically expensive, yet cache friendly + if (it!=end()) + it->dimension = factor->getDim(variable); + else + push_back(SlotEntry(key, factor->getDim(variable))); + } + } + + // To keep the same behavior as before, sort the keys after the ordering + iterator first = begin(); + if (ordering) first += ordering->size(); + if (first != end()) std::sort(first, end()); + + // Filter out keys with zero dimensions (if ordering had more keys) + erase(std::remove_if(begin(), end(), SlotEntry::Zero), end()); +} + +/* ************************************************************************* */ +FastVector::iterator Scatter::find(Key key) { + iterator it = begin(); + while(it != end()) { + if (it->key == key) + return it; + ++it; + } + return it; // end() +} + +/* ************************************************************************* */ + +} // gtsam diff --git a/gtsam/linear/Scatter.h b/gtsam/linear/Scatter.h new file mode 100644 index 000000000..39bfa6b8d --- /dev/null +++ b/gtsam/linear/Scatter.h @@ -0,0 +1,63 @@ +/* ---------------------------------------------------------------------------- + + * 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 Scatter.h + * @brief Maps global variable indices to slot indices + * @author Richard Roberts + * @author Frank Dellaert + * @date June 2015 + */ + +#pragma once + +#include +#include +#include + +#include + +namespace gtsam { + +class GaussianFactorGraph; +class Ordering; + +/// One SlotEntry stores the slot index for a variable, as well its dim. +struct GTSAM_EXPORT SlotEntry { + Key key; + size_t dimension; + SlotEntry(Key _key, size_t _dimension) : key(_key), dimension(_dimension) {} + std::string toString() const; + friend bool operator<(const SlotEntry& p, const SlotEntry& q) { + return p.key < q.key; + } + static bool Zero(const SlotEntry& p) { return p.dimension==0;} +}; + +/** + * Scatter is an intermediate data structure used when building a HessianFactor + * incrementally, to get the keys in the right order. In spirit, it is a map + * from global variable indices to slot indices in the union of involved + * variables. We also include the dimensionality of the variable. + */ +class Scatter : public FastVector { + public: + /// Constructor + Scatter(const GaussianFactorGraph& gfg, + boost::optional ordering = boost::none); + + private: + + /// Find the SlotEntry with the right key (linear time worst case) + iterator find(Key key); +}; + +} // \ namespace gtsam diff --git a/gtsam/linear/SubgraphPreconditioner.cpp b/gtsam/linear/SubgraphPreconditioner.cpp index f5ee4ddfc..ee2447d2f 100644 --- a/gtsam/linear/SubgraphPreconditioner.cpp +++ b/gtsam/linear/SubgraphPreconditioner.cpp @@ -15,20 +15,40 @@ * @author: Frank Dellaert */ -#include #include -#include -#include -#include -#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + #include -#include #include +#include +#include +#include +#include + +#include +#include +#include #include +#include #include -#include +#include +#include +#include +#include // accumulate #include #include +#include +#include #include #include diff --git a/gtsam/linear/SubgraphPreconditioner.h b/gtsam/linear/SubgraphPreconditioner.h index 350963bcf..e74b92df1 100644 --- a/gtsam/linear/SubgraphPreconditioner.h +++ b/gtsam/linear/SubgraphPreconditioner.h @@ -17,13 +17,31 @@ #pragma once -#include #include +#include +#include #include #include #include +#include +#include +#include +#include +#include + +#include #include +#include +#include +#include + +namespace boost { +namespace serialization { +class access; +} /* namespace serialization */ +} /* namespace boost */ + namespace gtsam { // Forward declarations diff --git a/gtsam/linear/VectorValues.cpp b/gtsam/linear/VectorValues.cpp index 664fcf3b7..33c62cfb6 100644 --- a/gtsam/linear/VectorValues.cpp +++ b/gtsam/linear/VectorValues.cpp @@ -66,6 +66,18 @@ namespace gtsam { return result; } + /* ************************************************************************* */ + VectorValues::iterator VectorValues::insert(const std::pair& key_value) { + // Note that here we accept a pair with a reference to the Vector, but the Vector is copied as + // it is inserted into the values_ map. + std::pair result = values_.insert(key_value); + if(!result.second) + throw std::invalid_argument( + "Requested to insert variable '" + DefaultKeyFormatter(key_value.first) + + "' already in this VectorValues."); + return result.first; + } + /* ************************************************************************* */ void VectorValues::update(const VectorValues& values) { diff --git a/gtsam/linear/VectorValues.h b/gtsam/linear/VectorValues.h index 968fc1adb..d04d9faac 100644 --- a/gtsam/linear/VectorValues.h +++ b/gtsam/linear/VectorValues.h @@ -181,23 +181,14 @@ namespace gtsam { * @param value The vector to be inserted. * @param j The index with which the value will be associated. */ iterator insert(Key j, const Vector& value) { - return insert(std::make_pair(j, value)); // Note only passing a reference to the Vector + return insert(std::make_pair(j, value)); } /** Insert a vector \c value with key \c j. Throws an invalid_argument exception if the key \c * j is already used. * @param value The vector to be inserted. * @param j The index with which the value will be associated. */ - iterator insert(const std::pair& key_value) { - // Note that here we accept a pair with a reference to the Vector, but the Vector is copied as - // it is inserted into the values_ map. - std::pair result = values_.insert(key_value); - if(!result.second) - throw std::invalid_argument( - "Requested to insert variable '" + DefaultKeyFormatter(key_value.first) - + "' already in this VectorValues."); - return result.first; - } + iterator insert(const std::pair& key_value); /** Insert all values from \c values. Throws an invalid_argument exception if any keys to be * inserted are already used. */ diff --git a/gtsam/linear/linearExceptions.cpp b/gtsam/linear/linearExceptions.cpp index 88758ae7a..a4168af2d 100644 --- a/gtsam/linear/linearExceptions.cpp +++ b/gtsam/linear/linearExceptions.cpp @@ -19,6 +19,7 @@ #include #include #include +#include namespace gtsam { diff --git a/gtsam/linear/linearExceptions.h b/gtsam/linear/linearExceptions.h index 63bc61e80..32db27fc9 100644 --- a/gtsam/linear/linearExceptions.h +++ b/gtsam/linear/linearExceptions.h @@ -17,9 +17,8 @@ */ #pragma once -#include -#include -#include +#include +#include namespace gtsam { diff --git a/gtsam/linear/tests/testGaussianBayesTree.cpp b/gtsam/linear/tests/testGaussianBayesTree.cpp index 05f8c3d2a..4f7c5c335 100644 --- a/gtsam/linear/tests/testGaussianBayesTree.cpp +++ b/gtsam/linear/tests/testGaussianBayesTree.cpp @@ -83,13 +83,30 @@ TEST( GaussianBayesTree, eliminate ) { GaussianBayesTree bt = *chain.eliminateMultifrontal(chainOrdering); + Scatter scatter(chain); + EXPECT_LONGS_EQUAL(4, scatter.size()); + EXPECT_LONGS_EQUAL(1, scatter.at(0).key); + EXPECT_LONGS_EQUAL(2, scatter.at(1).key); + EXPECT_LONGS_EQUAL(3, scatter.at(2).key); + EXPECT_LONGS_EQUAL(4, scatter.at(3).key); + Matrix two = (Matrix(1, 1) << 2.).finished(); Matrix one = (Matrix(1, 1) << 1.).finished(); GaussianBayesTree bayesTree_expected; bayesTree_expected.insertRoot( - MakeClique(GaussianConditional(pair_list_of(x3, (Matrix(2, 1) << 2., 0.).finished()) (x4, (Matrix(2, 1) << 2., 2.).finished()), 2, Vector2(2., 2.)), list_of - (MakeClique(GaussianConditional(pair_list_of(x2, (Matrix(2, 1) << -2.*sqrt(2.), 0.).finished()) (x1, (Matrix(2, 1) << -sqrt(2.), -sqrt(2.)).finished()) (x3, (Matrix(2, 1) << -sqrt(2.), sqrt(2.)).finished()), 2, (Vector(2) << -2.*sqrt(2.), 0.).finished()))))); + MakeClique( + GaussianConditional( + pair_list_of(x3, (Matrix21() << 2., 0.).finished())( + x4, (Matrix21() << 2., 2.).finished()), 2, Vector2(2., 2.)), + list_of( + MakeClique( + GaussianConditional( + pair_list_of(x2, + (Matrix21() << -2. * sqrt(2.), 0.).finished())(x1, + (Matrix21() << -sqrt(2.), -sqrt(2.)).finished())(x3, + (Matrix21() << -sqrt(2.), sqrt(2.)).finished()), 2, + (Vector(2) << -2. * sqrt(2.), 0.).finished()))))); EXPECT(assert_equal(bayesTree_expected, bt)); } diff --git a/gtsam/linear/tests/testHessianFactor.cpp b/gtsam/linear/tests/testHessianFactor.cpp index 3a2cd0fd4..10fb34988 100644 --- a/gtsam/linear/tests/testHessianFactor.cpp +++ b/gtsam/linear/tests/testHessianFactor.cpp @@ -10,7 +10,7 @@ * -------------------------------------------------------------------------- */ /** - * @file testCholeskyFactor.cpp + * @file testHessianFactor.cpp * @author Richard Roberts * @date Dec 15, 2010 */ @@ -38,6 +38,16 @@ using namespace gtsam; const double tol = 1e-5; +/* ************************************************************************* */ +TEST(HessianFactor, Slot) +{ + FastVector keys = list_of(2)(4)(1); + EXPECT_LONGS_EQUAL(0, GaussianFactor::Slot(keys,2)); + EXPECT_LONGS_EQUAL(1, GaussianFactor::Slot(keys,4)); + EXPECT_LONGS_EQUAL(2, GaussianFactor::Slot(keys,1)); + EXPECT_LONGS_EQUAL(3, GaussianFactor::Slot(keys,5)); // does not exist +} + /* ************************************************************************* */ TEST(HessianFactor, emptyConstructor) { @@ -270,30 +280,69 @@ TEST(HessianFactor, ConstructorNWay) } /* ************************************************************************* */ -TEST(HessianFactor, CombineAndEliminate) -{ - Matrix A01 = (Matrix(3,3) << - 1.0, 0.0, 0.0, - 0.0, 1.0, 0.0, - 0.0, 0.0, 1.0).finished(); +TEST(HessianFactor, CombineAndEliminate1) { + Matrix3 A01 = 3.0 * I_3x3; + Vector3 b0(1, 0, 0); + + Matrix3 A21 = 4.0 * I_3x3; + Vector3 b2 = Vector3::Zero(); + + GaussianFactorGraph gfg; + gfg.add(1, A01, b0); + gfg.add(1, A21, b2); + + Matrix63 A1; + A1 << A01, A21; + Vector6 b; + b << b0, b2; + + // create a full, uneliminated version of the factor + JacobianFactor jacobian(1, A1, b); + + // Make sure combining works + HessianFactor hessian(gfg); + VectorValues v; + v.insert(1, Vector3(1, 0, 0)); + EXPECT_DOUBLES_EQUAL(jacobian.error(v), hessian.error(v), 1e-9); + EXPECT(assert_equal(HessianFactor(jacobian), hessian, 1e-6)); + EXPECT(assert_equal(25.0 * I_3x3, hessian.information(), 1e-9)); + EXPECT( + assert_equal(jacobian.augmentedInformation(), + hessian.augmentedInformation(), 1e-9)); + + // perform elimination on jacobian + Ordering ordering = list_of(1); + GaussianConditional::shared_ptr expectedConditional; + JacobianFactor::shared_ptr expectedFactor; + boost::tie(expectedConditional, expectedFactor) = // + jacobian.eliminate(ordering); + + // Eliminate + GaussianConditional::shared_ptr actualConditional; + HessianFactor::shared_ptr actualHessian; + boost::tie(actualConditional, actualHessian) = // + EliminateCholesky(gfg, ordering); + + EXPECT(assert_equal(*expectedConditional, *actualConditional, 1e-6)); + EXPECT_DOUBLES_EQUAL(expectedFactor->error(v), actualHessian->error(v), 1e-9); + EXPECT( + assert_equal(expectedFactor->augmentedInformation(), + actualHessian->augmentedInformation(), 1e-9)); + EXPECT(assert_equal(HessianFactor(*expectedFactor), *actualHessian, 1e-6)); +} + +/* ************************************************************************* */ +TEST(HessianFactor, CombineAndEliminate2) { + Matrix A01 = I_3x3; Vector3 b0(1.5, 1.5, 1.5); Vector3 s0(1.6, 1.6, 1.6); - Matrix A10 = (Matrix(3,3) << - 2.0, 0.0, 0.0, - 0.0, 2.0, 0.0, - 0.0, 0.0, 2.0).finished(); - Matrix A11 = (Matrix(3,3) << - -2.0, 0.0, 0.0, - 0.0, -2.0, 0.0, - 0.0, 0.0, -2.0).finished(); + Matrix A10 = 2.0 * I_3x3; + Matrix A11 = -2.0 * I_3x3; Vector3 b1(2.5, 2.5, 2.5); Vector3 s1(2.6, 2.6, 2.6); - Matrix A21 = (Matrix(3,3) << - 3.0, 0.0, 0.0, - 0.0, 3.0, 0.0, - 0.0, 0.0, 3.0).finished(); + Matrix A21 = 3.0 * I_3x3; Vector3 b2(3.5, 3.5, 3.5); Vector3 s2(3.6, 3.6, 3.6); @@ -302,27 +351,45 @@ TEST(HessianFactor, CombineAndEliminate) gfg.add(0, A10, 1, A11, b1, noiseModel::Diagonal::Sigmas(s1, true)); gfg.add(1, A21, b2, noiseModel::Diagonal::Sigmas(s2, true)); - Matrix zero3x3 = zeros(3,3); - Matrix A0 = gtsam::stack(3, &A10, &zero3x3, &zero3x3); - Matrix A1 = gtsam::stack(3, &A11, &A01, &A21); - Vector9 b; b << b1, b0, b2; - Vector9 sigmas; sigmas << s1, s0, s2; + Matrix93 A0, A1; + A0 << A10, Z_3x3, Z_3x3; + A1 << A11, A01, A21; + Vector9 b, sigmas; + b << b1, b0, b2; + sigmas << s1, s0, s2; // create a full, uneliminated version of the factor - JacobianFactor expectedFactor(0, A0, 1, A1, b, noiseModel::Diagonal::Sigmas(sigmas, true)); + JacobianFactor jacobian(0, A0, 1, A1, b, + noiseModel::Diagonal::Sigmas(sigmas, true)); + + // Make sure combining works + HessianFactor hessian(gfg); + EXPECT(assert_equal(HessianFactor(jacobian), hessian, 1e-6)); + EXPECT( + assert_equal(jacobian.augmentedInformation(), + hessian.augmentedInformation(), 1e-9)); // perform elimination on jacobian + Ordering ordering = list_of(0); GaussianConditional::shared_ptr expectedConditional; - JacobianFactor::shared_ptr expectedRemainingFactor; - boost::tie(expectedConditional, expectedRemainingFactor) = expectedFactor.eliminate(Ordering(list_of(0))); + JacobianFactor::shared_ptr expectedFactor; + boost::tie(expectedConditional, expectedFactor) = // + jacobian.eliminate(ordering); // Eliminate GaussianConditional::shared_ptr actualConditional; - HessianFactor::shared_ptr actualCholeskyFactor; - boost::tie(actualConditional, actualCholeskyFactor) = EliminateCholesky(gfg, Ordering(list_of(0))); + HessianFactor::shared_ptr actualHessian; + boost::tie(actualConditional, actualHessian) = // + EliminateCholesky(gfg, ordering); EXPECT(assert_equal(*expectedConditional, *actualConditional, 1e-6)); - EXPECT(assert_equal(HessianFactor(*expectedRemainingFactor), *actualCholeskyFactor, 1e-6)); + VectorValues v; + v.insert(1, Vector3(1, 2, 3)); + EXPECT_DOUBLES_EQUAL(expectedFactor->error(v), actualHessian->error(v), 1e-9); + EXPECT( + assert_equal(expectedFactor->augmentedInformation(), + actualHessian->augmentedInformation(), 1e-9)); + EXPECT(assert_equal(HessianFactor(*expectedFactor), *actualHessian, 1e-6)); } /* ************************************************************************* */ diff --git a/gtsam/linear/tests/testJacobianFactor.cpp b/gtsam/linear/tests/testJacobianFactor.cpp index 7b2d59171..17ceaf5f0 100644 --- a/gtsam/linear/tests/testJacobianFactor.cpp +++ b/gtsam/linear/tests/testJacobianFactor.cpp @@ -540,9 +540,9 @@ TEST(JacobianFactor, EliminateQR) EXPECT(assert_equal(size_t(2), actualJF.keys().size())); EXPECT(assert_equal(Key(9), actualJF.keys()[0])); EXPECT(assert_equal(Key(11), actualJF.keys()[1])); - EXPECT(assert_equal(Matrix(R.block(6, 6, 4, 2)), actualJF.getA(actualJF.begin()), 0.001)); - EXPECT(assert_equal(Matrix(R.block(6, 8, 4, 2)), actualJF.getA(actualJF.begin()+1), 0.001)); - EXPECT(assert_equal(Vector(R.col(10).segment(6, 4)), actualJF.getb(), 0.001)); + EXPECT(assert_equal(Matrix(R.block(6, 6, 5, 2)), actualJF.getA(actualJF.begin()), 0.001)); + EXPECT(assert_equal(Matrix(R.block(6, 8, 5, 2)), actualJF.getA(actualJF.begin()+1), 0.001)); + EXPECT(assert_equal(Vector(R.col(10).segment(6, 5)), actualJF.getb(), 0.001)); EXPECT(!actualJF.get_model()); } diff --git a/gtsam/linear/tests/testNoiseModel.cpp b/gtsam/linear/tests/testNoiseModel.cpp index b2afb1709..d6857c6ff 100644 --- a/gtsam/linear/tests/testNoiseModel.cpp +++ b/gtsam/linear/tests/testNoiseModel.cpp @@ -33,19 +33,12 @@ using namespace gtsam; using namespace noiseModel; using namespace boost::assign; -static const double kSigma = 2, s_1=1.0/kSigma, kVariance = kSigma*kSigma, prc = 1.0/kVariance; -static const Matrix R = (Matrix(3, 3) << - s_1, 0.0, 0.0, - 0.0, s_1, 0.0, - 0.0, 0.0, s_1).finished(); -static const Matrix kCovariance = (Matrix(3, 3) << - kVariance, 0.0, 0.0, - 0.0, kVariance, 0.0, - 0.0, 0.0, kVariance).finished(); +static const double kSigma = 2, kInverseSigma = 1.0 / kSigma, + kVariance = kSigma * kSigma, prc = 1.0 / kVariance; +static const Matrix R = Matrix3::Identity() * kInverseSigma; +static const Matrix kCovariance = Matrix3::Identity() * kVariance; static const Vector3 kSigmas(kSigma, kSigma, kSigma); -//static double inf = numeric_limits::infinity(); - /* ************************************************************************* */ TEST(NoiseModel, constructors) { @@ -58,8 +51,8 @@ TEST(NoiseModel, constructors) m.push_back(Gaussian::Covariance(kCovariance,false)); m.push_back(Gaussian::Information(kCovariance.inverse(),false)); m.push_back(Diagonal::Sigmas(kSigmas,false)); - m.push_back(Diagonal::Variances((Vector(3) << kVariance, kVariance, kVariance).finished(),false)); - m.push_back(Diagonal::Precisions((Vector(3) << prc, prc, prc).finished(),false)); + m.push_back(Diagonal::Variances((Vector3(kVariance, kVariance, kVariance)),false)); + m.push_back(Diagonal::Precisions(Vector3(prc, prc, prc),false)); m.push_back(Isotropic::Sigma(3, kSigma,false)); m.push_back(Isotropic::Variance(3, kVariance,false)); m.push_back(Isotropic::Precision(3, prc,false)); @@ -82,25 +75,23 @@ TEST(NoiseModel, constructors) DOUBLES_EQUAL(distance,mi->Mahalanobis(unwhitened),1e-9); // test R matrix - Matrix expectedR((Matrix(3, 3) << - s_1, 0.0, 0.0, - 0.0, s_1, 0.0, - 0.0, 0.0, s_1).finished()); - BOOST_FOREACH(Gaussian::shared_ptr mi, m) - EXPECT(assert_equal(expectedR,mi->R())); + EXPECT(assert_equal(R,mi->R())); + + // test covariance + BOOST_FOREACH(Gaussian::shared_ptr mi, m) + EXPECT(assert_equal(kCovariance,mi->covariance())); + + // test covariance + BOOST_FOREACH(Gaussian::shared_ptr mi, m) + EXPECT(assert_equal(kCovariance.inverse(),mi->information())); // test Whiten operator Matrix H((Matrix(3, 4) << 0.0, 0.0, 1.0, 1.0, 0.0, 1.0, 0.0, 1.0, 1.0, 0.0, 0.0, 1.0).finished()); - - Matrix expected((Matrix(3, 4) << - 0.0, 0.0, s_1, s_1, - 0.0, s_1, 0.0, s_1, - s_1, 0.0, 0.0, s_1).finished()); - + Matrix expected = kInverseSigma * H; BOOST_FOREACH(Gaussian::shared_ptr mi, m) EXPECT(assert_equal(expected,mi->Whiten(H))); @@ -122,7 +113,7 @@ TEST(NoiseModel, equals) { Gaussian::shared_ptr g1 = Gaussian::SqrtInformation(R), g2 = Gaussian::SqrtInformation(eye(3,3)); - Diagonal::shared_ptr d1 = Diagonal::Sigmas((Vector(3) << kSigma, kSigma, kSigma).finished()), + Diagonal::shared_ptr d1 = Diagonal::Sigmas(Vector3(kSigma, kSigma, kSigma)), d2 = Diagonal::Sigmas(Vector3(0.1, 0.2, 0.3)); Isotropic::shared_ptr i1 = Isotropic::Sigma(3, kSigma), i2 = Isotropic::Sigma(3, 0.7); @@ -141,7 +132,7 @@ TEST(NoiseModel, equals) ///* ************************************************************************* */ //TEST(NoiseModel, ConstrainedSmart ) //{ -// Gaussian::shared_ptr nonconstrained = Constrained::MixedSigmas((Vector(3) << sigma, 0.0, sigma), true); +// Gaussian::shared_ptr nonconstrained = Constrained::MixedSigmas((Vector3(sigma, 0.0, sigma), true); // Diagonal::shared_ptr n1 = boost::dynamic_pointer_cast(nonconstrained); // Constrained::shared_ptr n2 = boost::dynamic_pointer_cast(nonconstrained); // EXPECT(n1); @@ -160,8 +151,8 @@ TEST(NoiseModel, ConstrainedConstructors ) Constrained::shared_ptr actual; size_t d = 3; double m = 100.0; - Vector sigmas = (Vector(3) << kSigma, 0.0, 0.0).finished(); - Vector mu = Vector3(200.0, 300.0, 400.0); + Vector3 sigmas(kSigma, 0.0, 0.0); + Vector3 mu(200.0, 300.0, 400.0); actual = Constrained::All(d); // TODO: why should this be a thousand ??? Dummy variable? EXPECT(assert_equal(gtsam::repeat(d, 1000.0), actual->mu())); @@ -187,7 +178,7 @@ TEST(NoiseModel, ConstrainedMixed ) { Vector feasible = Vector3(1.0, 0.0, 1.0), infeasible = Vector3(1.0, 1.0, 1.0); - Diagonal::shared_ptr d = Constrained::MixedSigmas((Vector(3) << kSigma, 0.0, kSigma).finished()); + Diagonal::shared_ptr d = Constrained::MixedSigmas(Vector3(kSigma, 0.0, kSigma)); // NOTE: we catch constrained variables elsewhere, so whitening does nothing EXPECT(assert_equal(Vector3(0.5, 1.0, 0.5),d->whiten(infeasible))); EXPECT(assert_equal(Vector3(0.5, 0.0, 0.5),d->whiten(feasible))); @@ -331,7 +322,7 @@ TEST(NoiseModel, WhitenInPlace) } /* ************************************************************************* */ -TEST(NoiseModel, robustFunction) +TEST(NoiseModel, robustFunctionHuber) { const double k = 5.0, error1 = 1.0, error2 = 10.0; const mEstimator::Huber::shared_ptr huber = mEstimator::Huber::Create(k); @@ -341,17 +332,37 @@ TEST(NoiseModel, robustFunction) DOUBLES_EQUAL(0.5, weight2, 1e-8); } +TEST(NoiseModel, robustFunctionGemanMcClure) +{ + const double k = 1.0, error1 = 1.0, error2 = 10.0; + const mEstimator::GemanMcClure::shared_ptr gmc = mEstimator::GemanMcClure::Create(k); + const double weight1 = gmc->weight(error1), + weight2 = gmc->weight(error2); + DOUBLES_EQUAL(0.25 , weight1, 1e-8); + DOUBLES_EQUAL(9.80296e-5, weight2, 1e-8); +} + +TEST(NoiseModel, robustFunctionDCS) +{ + const double k = 1.0, error1 = 1.0, error2 = 10.0; + const mEstimator::DCS::shared_ptr dcs = mEstimator::DCS::Create(k); + const double weight1 = dcs->weight(error1), + weight2 = dcs->weight(error2); + DOUBLES_EQUAL(1.0 , weight1, 1e-8); + DOUBLES_EQUAL(0.00039211, weight2, 1e-8); +} + /* ************************************************************************* */ -TEST(NoiseModel, robustNoise) +TEST(NoiseModel, robustNoiseHuber) { const double k = 10.0, error1 = 1.0, error2 = 100.0; Matrix A = (Matrix(2, 2) << 1.0, 10.0, 100.0, 1000.0).finished(); - Vector b = (Vector(2) << error1, error2).finished(); + Vector b = Vector2(error1, error2); const Robust::shared_ptr robust = Robust::Create( mEstimator::Huber::Create(k, mEstimator::Huber::Scalar), Unit::Create(2)); - robust->WhitenSystem(A,b); + robust->WhitenSystem(A, b); DOUBLES_EQUAL(error1, b(0), 1e-8); DOUBLES_EQUAL(sqrt(k*error2), b(1), 1e-8); @@ -362,6 +373,57 @@ TEST(NoiseModel, robustNoise) DOUBLES_EQUAL(sqrt(k/100.0)*1000.0, A(1,1), 1e-8); } +TEST(NoiseModel, robustNoiseGemanMcClure) +{ + const double k = 1.0, error1 = 1.0, error2 = 100.0; + const double a00 = 1.0, a01 = 10.0, a10 = 100.0, a11 = 1000.0; + Matrix A = (Matrix(2, 2) << a00, a01, a10, a11).finished(); + Vector b = Vector2(error1, error2); + const Robust::shared_ptr robust = Robust::Create( + mEstimator::GemanMcClure::Create(k, mEstimator::GemanMcClure::Scalar), + Unit::Create(2)); + + robust->WhitenSystem(A, b); + + const double k2 = k*k; + const double k4 = k2*k2; + const double k2error = k2 + error2*error2; + + const double sqrt_weight_error1 = sqrt(0.25); + const double sqrt_weight_error2 = sqrt(k4/(k2error*k2error)); + + DOUBLES_EQUAL(sqrt_weight_error1*error1, b(0), 1e-8); + DOUBLES_EQUAL(sqrt_weight_error2*error2, b(1), 1e-8); + + DOUBLES_EQUAL(sqrt_weight_error1*a00, A(0,0), 1e-8); + DOUBLES_EQUAL(sqrt_weight_error1*a01, A(0,1), 1e-8); + DOUBLES_EQUAL(sqrt_weight_error2*a10, A(1,0), 1e-8); + DOUBLES_EQUAL(sqrt_weight_error2*a11, A(1,1), 1e-8); +} + +TEST(NoiseModel, robustNoiseDCS) +{ + const double k = 1.0, error1 = 1.0, error2 = 100.0; + const double a00 = 1.0, a01 = 10.0, a10 = 100.0, a11 = 1000.0; + Matrix A = (Matrix(2, 2) << a00, a01, a10, a11).finished(); + Vector b = Vector2(error1, error2); + const Robust::shared_ptr robust = Robust::Create( + mEstimator::DCS::Create(k, mEstimator::DCS::Scalar), + Unit::Create(2)); + + robust->WhitenSystem(A, b); + + const double sqrt_weight = 2.0*k/(k + error2*error2); + + DOUBLES_EQUAL(error1, b(0), 1e-8); + DOUBLES_EQUAL(sqrt_weight*error2, b(1), 1e-8); + + DOUBLES_EQUAL(a00, A(0,0), 1e-8); + DOUBLES_EQUAL(a01, A(0,1), 1e-8); + DOUBLES_EQUAL(sqrt_weight*a10, A(1,0), 1e-8); + DOUBLES_EQUAL(sqrt_weight*a11, A(1,1), 1e-8); +} + /* ************************************************************************* */ #define TEST_GAUSSIAN(gaussian)\ EQUALITY(info, gaussian->information());\ diff --git a/gtsam/slam/tests/testRegularHessianFactor.cpp b/gtsam/linear/tests/testRegularHessianFactor.cpp similarity index 50% rename from gtsam/slam/tests/testRegularHessianFactor.cpp rename to gtsam/linear/tests/testRegularHessianFactor.cpp index e2b8ac3cf..f53803dd1 100644 --- a/gtsam/slam/tests/testRegularHessianFactor.cpp +++ b/gtsam/linear/tests/testRegularHessianFactor.cpp @@ -15,7 +15,8 @@ * @date March 4, 2014 */ -#include +#include +#include #include #include @@ -29,30 +30,62 @@ using namespace gtsam; using namespace boost::assign; /* ************************************************************************* */ -TEST(RegularHessianFactor, ConstructorNWay) +TEST(RegularHessianFactor, Constructors) { - Matrix G11 = (Matrix(2,2) << 111, 112, 113, 114).finished(); - Matrix G12 = (Matrix(2,2) << 121, 122, 123, 124).finished(); - Matrix G13 = (Matrix(2,2) << 131, 132, 133, 134).finished(); + // First construct a regular JacobianFactor + // 0.5*|x0 + x1 + x3 - [1;2]|^2 = 0.5*|A*x-b|^2, with A=[I I I] + Matrix A1 = I_2x2, A2 = I_2x2, A3 = I_2x2; + Vector2 b(1,2); + vector > terms; + terms += make_pair(0, A1), make_pair(1, A2), make_pair(3, A3); + RegularJacobianFactor<2> jf(terms, b); - Matrix G22 = (Matrix(2,2) << 221, 222, 222, 224).finished(); - Matrix G23 = (Matrix(2,2) << 231, 232, 233, 234).finished(); + // Test conversion from JacobianFactor + RegularHessianFactor<2> factor(jf); - Matrix G33 = (Matrix(2,2) << 331, 332, 332, 334).finished(); + // 0.5*|A*x-b|^2 = 0.5*(Ax-b)'*(Ax-b) = 0.5*x'*A'A*x - x'*A'b + 0.5*b'*b + // Compare with comment in HessianFactor: E(x) = 0.5 x^T G x - x^T g + 0.5 f + // Hence G = I6, g A'*b = [b;b;b], and f = b'*b = 1+4 = 5 + Matrix G11 = I_2x2; + Matrix G12 = I_2x2; + Matrix G13 = I_2x2; - Vector g1 = (Vector(2) << -7, -9).finished(); - Vector g2 = (Vector(2) << -9, 1).finished(); - Vector g3 = (Vector(2) << 2, 3).finished(); + Matrix G22 = I_2x2; + Matrix G23 = I_2x2; - double f = 10; + Matrix G33 = I_2x2; - std::vector js; - js.push_back(0); js.push_back(1); js.push_back(3); - std::vector Gs; - Gs.push_back(G11); Gs.push_back(G12); Gs.push_back(G13); Gs.push_back(G22); Gs.push_back(G23); Gs.push_back(G33); - std::vector gs; - gs.push_back(g1); gs.push_back(g2); gs.push_back(g3); - RegularHessianFactor<2> factor(js, Gs, gs, f); + Vector2 g1 = b, g2 = b, g3 = b; + + double f = 5; + + // Test ternary constructor + RegularHessianFactor<2> factor2(0, 1, 3, G11, G12, G13, g1, G22, G23, g2, G33, g3, f); + EXPECT(assert_equal(factor,factor2)); + + // Test n-way constructor + vector keys; keys += 0, 1, 3; + vector Gs; Gs += G11, G12, G13, G22, G23, G33; + vector gs; gs += g1, g2, g3; + RegularHessianFactor<2> factor3(keys, Gs, gs, f); + EXPECT(assert_equal(factor, factor3)); + + // Test constructor from Gaussian Factor Graph + GaussianFactorGraph gfg; + gfg += jf; + RegularHessianFactor<2> factor4(gfg); + EXPECT(assert_equal(factor, factor4)); + GaussianFactorGraph gfg2; + gfg2 += factor; + RegularHessianFactor<2> factor5(gfg); + EXPECT(assert_equal(factor, factor5)); + + // Test constructor from Information matrix + Matrix info = factor.augmentedInformation(); + vector dims; dims += 2, 2, 2; + SymmetricBlockMatrix sym(dims, info, true); + RegularHessianFactor<2> factor6(keys, sym); + EXPECT(assert_equal(factor, factor6)); // multiplyHessianAdd: { @@ -61,13 +94,13 @@ TEST(RegularHessianFactor, ConstructorNWay) HessianFactor::const_iterator i1 = factor.begin(); HessianFactor::const_iterator i2 = i1 + 1; Vector X(6); X << 1,2,3,4,5,6; - Vector Y(6); Y << 2633, 2674, 4465, 4501, 5669, 5696; + Vector Y(6); Y << 9, 12, 9, 12, 9, 12; EXPECT(assert_equal(Y,AtA*X)); VectorValues x = map_list_of - (0, (Vector(2) << 1,2).finished()) - (1, (Vector(2) << 3,4).finished()) - (3, (Vector(2) << 5,6).finished()); + (0, Vector2(1,2)) + (1, Vector2(3,4)) + (3, Vector2(5,6)); VectorValues expected; expected.insert(0, Y.segment<2>(0)); @@ -77,15 +110,15 @@ TEST(RegularHessianFactor, ConstructorNWay) // VectorValues version double alpha = 1.0; VectorValues actualVV; - actualVV.insert(0, zero(2)); - actualVV.insert(1, zero(2)); - actualVV.insert(3, zero(2)); + actualVV.insert(0, Vector2::Zero()); + actualVV.insert(1, Vector2::Zero()); + actualVV.insert(3, Vector2::Zero()); factor.multiplyHessianAdd(alpha, x, actualVV); EXPECT(assert_equal(expected, actualVV)); // RAW ACCESS - Vector expected_y(8); expected_y << 2633, 2674, 4465, 4501, 0, 0, 5669, 5696; - Vector fast_y = gtsam::zero(8); + Vector expected_y(8); expected_y << 9, 12, 9, 12, 0, 0, 9, 12; + Vector fast_y = Vector8::Zero(); double xvalues[8] = {1,2,3,4,0,0,5,6}; factor.multiplyHessianAdd(alpha, xvalues, fast_y.data()); EXPECT(assert_equal(expected_y, fast_y)); diff --git a/gtsam/slam/tests/testRegularJacobianFactor.cpp b/gtsam/linear/tests/testRegularJacobianFactor.cpp similarity index 99% rename from gtsam/slam/tests/testRegularJacobianFactor.cpp rename to gtsam/linear/tests/testRegularJacobianFactor.cpp index 5803516a1..b8c4aa689 100644 --- a/gtsam/slam/tests/testRegularJacobianFactor.cpp +++ b/gtsam/linear/tests/testRegularJacobianFactor.cpp @@ -16,7 +16,7 @@ * @date Nov 12, 2014 */ -#include +#include #include #include #include diff --git a/gtsam/linear/tests/testScatter.cpp b/gtsam/linear/tests/testScatter.cpp new file mode 100644 index 000000000..575f29c26 --- /dev/null +++ b/gtsam/linear/tests/testScatter.cpp @@ -0,0 +1,65 @@ +/* ---------------------------------------------------------------------------- + + * 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 testScatter.cpp + * @author Frank Dellaert + * @date June, 2015 + */ + +#include +#include +#include +#include + +using namespace std; +using namespace gtsam; +using symbol_shorthand::X; + +/* ************************************************************************* */ +TEST(HessianFactor, CombineAndEliminate) { + static const size_t m = 3, n = 3; + Matrix A01 = + (Matrix(m, n) << 1.0, 0.0, 0.0, 0.0, 1.0, 0.0, 0.0, 0.0, 1.0).finished(); + Vector3 b0(1.5, 1.5, 1.5); + Vector3 s0(1.6, 1.6, 1.6); + + Matrix A10 = + (Matrix(m, n) << 2.0, 0.0, 0.0, 0.0, 2.0, 0.0, 0.0, 0.0, 2.0).finished(); + Matrix A11 = (Matrix(m, n) << -2.0, 0.0, 0.0, 0.0, -2.0, 0.0, 0.0, 0.0, -2.0) + .finished(); + Vector3 b1(2.5, 2.5, 2.5); + Vector3 s1(2.6, 2.6, 2.6); + + Matrix A21 = + (Matrix(m, n) << 3.0, 0.0, 0.0, 0.0, 3.0, 0.0, 0.0, 0.0, 3.0).finished(); + Vector3 b2(3.5, 3.5, 3.5); + Vector3 s2(3.6, 3.6, 3.6); + + GaussianFactorGraph gfg; + gfg.add(X(1), A01, b0, noiseModel::Diagonal::Sigmas(s0, true)); + gfg.add(X(0), A10, X(1), A11, b1, noiseModel::Diagonal::Sigmas(s1, true)); + gfg.add(X(1), A21, b2, noiseModel::Diagonal::Sigmas(s2, true)); + + Scatter scatter(gfg); + EXPECT_LONGS_EQUAL(2, scatter.size()); + EXPECT(assert_equal(X(0), scatter.at(0).key)); + EXPECT(assert_equal(X(1), scatter.at(1).key)); + EXPECT_LONGS_EQUAL(n, scatter.at(0).dimension); + EXPECT_LONGS_EQUAL(n, scatter.at(1).dimension); +} + +/* ************************************************************************* */ +int main() { + TestResult tr; + return TestRegistry::runAllTests(tr); +} +/* ************************************************************************* */ diff --git a/gtsam/linear/tests/testSerializationLinear.cpp b/gtsam/linear/tests/testSerializationLinear.cpp index f93788af9..71fdbe6a6 100644 --- a/gtsam/linear/tests/testSerializationLinear.cpp +++ b/gtsam/linear/tests/testSerializationLinear.cpp @@ -38,6 +38,7 @@ using namespace gtsam::serializationTestHelpers; /* ************************************************************************* */ // Export Noisemodels +// See http://www.boost.org/doc/libs/1_32_0/libs/serialization/doc/special.html BOOST_CLASS_EXPORT_GUID(gtsam::noiseModel::Constrained, "gtsam_noiseModel_Constrained"); BOOST_CLASS_EXPORT_GUID(gtsam::noiseModel::Diagonal, "gtsam_noiseModel_Diagonal"); BOOST_CLASS_EXPORT_GUID(gtsam::noiseModel::Gaussian, "gtsam_noiseModel_Gaussian"); diff --git a/gtsam/navigation/AHRSFactor.cpp b/gtsam/navigation/AHRSFactor.cpp index 2f03d72a4..0d7e05515 100644 --- a/gtsam/navigation/AHRSFactor.cpp +++ b/gtsam/navigation/AHRSFactor.cpp @@ -27,83 +27,50 @@ namespace gtsam { //------------------------------------------------------------------------------ // Inner class PreintegratedMeasurements //------------------------------------------------------------------------------ -AHRSFactor::PreintegratedMeasurements::PreintegratedMeasurements( - const Vector3& bias, const Matrix3& measuredOmegaCovariance) : - PreintegratedRotation(measuredOmegaCovariance), biasHat_(bias) -{ - preintMeasCov_.setZero(); -} - -//------------------------------------------------------------------------------ -AHRSFactor::PreintegratedMeasurements::PreintegratedMeasurements() : - PreintegratedRotation(I_3x3), biasHat_(Vector3()) -{ - preintMeasCov_.setZero(); -} - -//------------------------------------------------------------------------------ -void AHRSFactor::PreintegratedMeasurements::print(const string& s) const { +void PreintegratedAhrsMeasurements::print(const string& s) const { PreintegratedRotation::print(s); cout << "biasHat [" << biasHat_.transpose() << "]" << endl; cout << " PreintMeasCov [ " << preintMeasCov_ << " ]" << endl; } //------------------------------------------------------------------------------ -bool AHRSFactor::PreintegratedMeasurements::equals( - const PreintegratedMeasurements& other, double tol) const { - return PreintegratedRotation::equals(other, tol) - && equal_with_abs_tol(biasHat_, other.biasHat_, tol); +bool PreintegratedAhrsMeasurements::equals( + const PreintegratedAhrsMeasurements& other, double tol) const { + return PreintegratedRotation::equals(other, tol) && + equal_with_abs_tol(biasHat_, other.biasHat_, tol); } //------------------------------------------------------------------------------ -void AHRSFactor::PreintegratedMeasurements::resetIntegration() { +void PreintegratedAhrsMeasurements::resetIntegration() { PreintegratedRotation::resetIntegration(); preintMeasCov_.setZero(); } //------------------------------------------------------------------------------ -void AHRSFactor::PreintegratedMeasurements::integrateMeasurement( - const Vector3& measuredOmega, double deltaT, - boost::optional body_P_sensor) { +void PreintegratedAhrsMeasurements::integrateMeasurement( + const Vector3& measuredOmega, double deltaT) { - // First we compensate the measurements for the bias - Vector3 correctedOmega = measuredOmega - biasHat_; - - // Then compensate for sensor-body displacement: we express the quantities - // (originally in the IMU frame) into the body frame - if (body_P_sensor) { - Matrix3 body_R_sensor = body_P_sensor->rotation().matrix(); - // rotation rate vector in the body frame - correctedOmega = body_R_sensor * correctedOmega; - } - - // rotation vector describing rotation increment computed from the - // current rotation rate measurement - const Vector3 theta_incr = correctedOmega * deltaT; - Matrix3 D_Rincr_integratedOmega; - const Rot3 incrR = Rot3::Expmap(theta_incr, D_Rincr_integratedOmega); // expensive !! - - // Update Jacobian - update_delRdelBiasOmega(D_Rincr_integratedOmega, incrR, deltaT); - - // Update rotation and deltaTij. - Matrix3 Fr; // Jacobian of the update - updateIntegratedRotationAndDeltaT(incrR, deltaT, Fr); + Matrix3 D_incrR_integratedOmega, Fr; + PreintegratedRotation::integrateMeasurement(measuredOmega, + biasHat_, deltaT, &D_incrR_integratedOmega, &Fr); // first order uncertainty propagation // the deltaT allows to pass from continuous time noise to discrete time noise - preintMeasCov_ = Fr * preintMeasCov_ * Fr.transpose() - + gyroscopeCovariance() * deltaT; + preintMeasCov_ = Fr * preintMeasCov_ * Fr.transpose() + p().gyroscopeCovariance * deltaT; } //------------------------------------------------------------------------------ -Vector3 AHRSFactor::PreintegratedMeasurements::predict(const Vector3& bias, - boost::optional H) const { +Vector3 PreintegratedAhrsMeasurements::predict(const Vector3& bias, + OptionalJacobian<3,3> H) const { const Vector3 biasOmegaIncr = bias - biasHat_; - return biascorrectedThetaRij(biasOmegaIncr, H); + const Rot3 biascorrected = biascorrectedDeltaRij(biasOmegaIncr, H); + Matrix3 D_omega_biascorrected; + const Vector3 omega = Rot3::Logmap(biascorrected, H ? &D_omega_biascorrected : 0); + if (H) (*H) = D_omega_biascorrected * (*H); + return omega; } //------------------------------------------------------------------------------ -Vector AHRSFactor::PreintegratedMeasurements::DeltaAngles( +Vector PreintegratedAhrsMeasurements::DeltaAngles( const Vector& msr_gyro_t, const double msr_dt, const Vector3& delta_angles) { @@ -121,22 +88,16 @@ Vector AHRSFactor::PreintegratedMeasurements::DeltaAngles( //------------------------------------------------------------------------------ // AHRSFactor methods //------------------------------------------------------------------------------ -AHRSFactor::AHRSFactor() : - _PIM_(Vector3(), Z_3x3) { -} +AHRSFactor::AHRSFactor( + Key rot_i, Key rot_j, Key bias, + const PreintegratedAhrsMeasurements& preintegratedMeasurements) + : Base(noiseModel::Gaussian::Covariance( + preintegratedMeasurements.preintMeasCov_), + rot_i, rot_j, bias), + _PIM_(preintegratedMeasurements) {} -AHRSFactor::AHRSFactor(Key rot_i, Key rot_j, Key bias, - const PreintegratedMeasurements& preintegratedMeasurements, - const Vector3& omegaCoriolis, boost::optional body_P_sensor) : - Base( - noiseModel::Gaussian::Covariance( - preintegratedMeasurements.preintMeasCov_), rot_i, rot_j, bias), _PIM_( - preintegratedMeasurements), omegaCoriolis_(omegaCoriolis), body_P_sensor_( - body_P_sensor) { -} - -//------------------------------------------------------------------------------ gtsam::NonlinearFactor::shared_ptr AHRSFactor::clone() const { +//------------------------------------------------------------------------------ return boost::static_pointer_cast( gtsam::NonlinearFactor::shared_ptr(new This(*this))); } @@ -147,20 +108,13 @@ void AHRSFactor::print(const string& s, cout << s << "AHRSFactor(" << keyFormatter(this->key1()) << "," << keyFormatter(this->key2()) << "," << keyFormatter(this->key3()) << ","; _PIM_.print(" preintegrated measurements:"); - cout << " omegaCoriolis: [ " << omegaCoriolis_.transpose() << " ]" << endl; noiseModel_->print(" noise model: "); - if (body_P_sensor_) - body_P_sensor_->print(" sensor pose in body frame: "); } //------------------------------------------------------------------------------ bool AHRSFactor::equals(const NonlinearFactor& other, double tol) const { const This *e = dynamic_cast(&other); - return e != NULL && Base::equals(*e, tol) && _PIM_.equals(e->_PIM_, tol) - && equal_with_abs_tol(omegaCoriolis_, e->omegaCoriolis_, tol) - && ((!body_P_sensor_ && !e->body_P_sensor_) - || (body_P_sensor_ && e->body_P_sensor_ - && body_P_sensor_->equals(*e->body_P_sensor_))); + return e != NULL && Base::equals(*e, tol) && _PIM_.equals(e->_PIM_, tol); } //------------------------------------------------------------------------------ @@ -172,8 +126,7 @@ Vector AHRSFactor::evaluateError(const Rot3& Ri, const Rot3& Rj, const Vector3 biascorrectedOmega = _PIM_.predict(bias, H3); // Coriolis term - const Vector3 coriolis = _PIM_.integrateCoriolis(Ri, omegaCoriolis_); - const Matrix3 coriolisHat = skewSymmetric(coriolis); + const Vector3 coriolis = _PIM_.integrateCoriolis(Ri); const Vector3 correctedOmega = biascorrectedOmega - coriolis; // Prediction @@ -191,7 +144,7 @@ Vector AHRSFactor::evaluateError(const Rot3& Ri, const Rot3& Rj, if (H1) { // dfR/dRi H1->resize(3, 3); - Matrix3 D_coriolis = -D_cDeltaRij_cOmega * coriolisHat; + Matrix3 D_coriolis = -D_cDeltaRij_cOmega * skewSymmetric(coriolis); (*H1) << D_fR_fRrot * (-actualRij.transpose() - fRrot.transpose() * D_coriolis); } @@ -199,7 +152,7 @@ Vector AHRSFactor::evaluateError(const Rot3& Ri, const Rot3& Rj, if (H2) { // dfR/dPosej H2->resize(3, 3); - (*H2) << D_fR_fRrot * Matrix3::Identity(); + (*H2) << D_fR_fRrot; } if (H3) { @@ -215,15 +168,13 @@ Vector AHRSFactor::evaluateError(const Rot3& Ri, const Rot3& Rj, } //------------------------------------------------------------------------------ -Rot3 AHRSFactor::predict(const Rot3& rot_i, const Vector3& bias, - const PreintegratedMeasurements preintegratedMeasurements, - const Vector3& omegaCoriolis, boost::optional body_P_sensor) { - +Rot3 AHRSFactor::Predict( + const Rot3& rot_i, const Vector3& bias, + const PreintegratedAhrsMeasurements preintegratedMeasurements) { const Vector3 biascorrectedOmega = preintegratedMeasurements.predict(bias); // Coriolis term - const Vector3 coriolis = // - preintegratedMeasurements.integrateCoriolis(rot_i, omegaCoriolis); + const Vector3 coriolis = preintegratedMeasurements.integrateCoriolis(rot_i); const Vector3 correctedOmega = biascorrectedOmega - coriolis; const Rot3 correctedDeltaRij = Rot3::Expmap(correctedOmega); @@ -231,4 +182,31 @@ Rot3 AHRSFactor::predict(const Rot3& rot_i, const Vector3& bias, return rot_i.compose(correctedDeltaRij); } -} //namespace gtsam +//------------------------------------------------------------------------------ +AHRSFactor::AHRSFactor(Key rot_i, Key rot_j, Key bias, + const PreintegratedMeasurements& pim, + const Vector3& omegaCoriolis, + const boost::optional& body_P_sensor) + : Base(noiseModel::Gaussian::Covariance(pim.preintMeasCov_), rot_i, rot_j, bias), + _PIM_(pim) { + boost::shared_ptr p = + boost::make_shared(pim.p()); + p->body_P_sensor = body_P_sensor; + _PIM_.p_ = p; +} + +//------------------------------------------------------------------------------ +Rot3 AHRSFactor::predict(const Rot3& rot_i, const Vector3& bias, + const PreintegratedMeasurements pim, + const Vector3& omegaCoriolis, + const boost::optional& body_P_sensor) { + boost::shared_ptr p = + boost::make_shared(pim.p()); + p->omegaCoriolis = omegaCoriolis; + p->body_P_sensor = body_P_sensor; + PreintegratedMeasurements newPim = pim; + newPim.p_ = p; + return Predict(rot_i, bias, newPim); +} + +} // namespace gtsam diff --git a/gtsam/navigation/AHRSFactor.h b/gtsam/navigation/AHRSFactor.h index fbf7d51a1..c2a88bd44 100644 --- a/gtsam/navigation/AHRSFactor.h +++ b/gtsam/navigation/AHRSFactor.h @@ -26,91 +26,94 @@ namespace gtsam { -class GTSAM_EXPORT AHRSFactor: public NoiseModelFactor3 { -public: +/** + * PreintegratedAHRSMeasurements accumulates (integrates) the Gyroscope + * measurements (rotation rates) and the corresponding covariance matrix. + * Can be built incrementally so as to avoid costly integration at time of factor construction. + */ +class GTSAM_EXPORT PreintegratedAhrsMeasurements : public PreintegratedRotation { + + protected: + + Vector3 biasHat_; ///< Angular rate bias values used during preintegration. + Matrix3 preintMeasCov_; ///< Covariance matrix of the preintegrated measurements (first-order propagation from *measurementCovariance*) + + /// Default constructor, only for serialization + PreintegratedAhrsMeasurements() {} + + friend class AHRSFactor; + + public: /** - * CombinedPreintegratedMeasurements accumulates (integrates) the Gyroscope - * measurements (rotation rates) and the corresponding covariance matrix. - * The measurements are then used to build the Preintegrated AHRS factor. - * Can be built incrementally so as to avoid costly integration at time of - * factor construction. + * Default constructor, initialize with no measurements + * @param bias Current estimate of acceleration and rotation rate biases */ - class GTSAM_EXPORT PreintegratedMeasurements : public PreintegratedRotation { + PreintegratedAhrsMeasurements(const boost::shared_ptr& p, + const Vector3& biasHat) : + PreintegratedRotation(p), biasHat_(biasHat) { + resetIntegration(); + } - friend class AHRSFactor; + const Params& p() const { return *boost::static_pointer_cast(p_);} + const Vector3& biasHat() const { return biasHat_; } + const Matrix3& preintMeasCov() const { return preintMeasCov_; } - protected: - Vector3 biasHat_; ///< Acceleration and angular rate bias values used during preintegration. Note that we won't be using the accelerometer - Matrix3 preintMeasCov_; ///< Covariance matrix of the preintegrated measurements (first-order propagation from *measurementCovariance*) + /// print + void print(const std::string& s = "Preintegrated Measurements: ") const; - public: + /// equals + bool equals(const PreintegratedAhrsMeasurements&, double tol = 1e-9) const; - /// Default constructor - PreintegratedMeasurements(); + /// Reset inetgrated quantities to zero + void resetIntegration(); - /** - * Default constructor, initialize with no measurements - * @param bias Current estimate of acceleration and rotation rate biases - * @param measuredOmegaCovariance Covariance matrix of measured angular rate - */ - PreintegratedMeasurements(const Vector3& bias, - const Matrix3& measuredOmegaCovariance); + /** + * Add a single Gyroscope measurement to the preintegration. + * @param measureOmedga Measured angular velocity (in body frame) + * @param deltaT Time step + */ + void integrateMeasurement(const Vector3& measuredOmega, double deltaT); - Vector3 biasHat() const { - return biasHat_; - } - const Matrix3& preintMeasCov() const { - return preintMeasCov_; - } + /// Predict bias-corrected incremental rotation + /// TODO: The matrix Hbias is the derivative of predict? Unit-test? + Vector3 predict(const Vector3& bias, OptionalJacobian<3,3> H = boost::none) const; - /// print - void print(const std::string& s = "Preintegrated Measurements: ") const; + // This function is only used for test purposes + // (compare numerical derivatives wrt analytic ones) + static Vector DeltaAngles(const Vector& msr_gyro_t, const double msr_dt, + const Vector3& delta_angles); - /// equals - bool equals(const PreintegratedMeasurements&, double tol = 1e-9) const; - - /// TODO: Document - void resetIntegration(); - - /** - * Add a single Gyroscope measurement to the preintegration. - * @param measureOmedga Measured angular velocity (in body frame) - * @param deltaT Time step - * @param body_P_sensor Optional sensor frame - */ - void integrateMeasurement(const Vector3& measuredOmega, double deltaT, - boost::optional body_P_sensor = boost::none); - - /// Predict bias-corrected incremental rotation - /// TODO: The matrix Hbias is the derivative of predict? Unit-test? - Vector3 predict(const Vector3& bias, boost::optional H = - boost::none) const; - - // This function is only used for test purposes - // (compare numerical derivatives wrt analytic ones) - static Vector DeltaAngles(const Vector& msr_gyro_t, const double msr_dt, - const Vector3& delta_angles); - - private: - - /** Serialization function */ - friend class boost::serialization::access; - template - void serialize(ARCHIVE & ar, const unsigned int /*version*/) { - ar & BOOST_SERIALIZATION_BASE_OBJECT_NVP(PreintegratedRotation); - ar & BOOST_SERIALIZATION_NVP(biasHat_); - } - }; + /// @deprecated constructor + PreintegratedAhrsMeasurements(const Vector3& biasHat, + const Matrix3& measuredOmegaCovariance) + : PreintegratedRotation(boost::make_shared()), + biasHat_(biasHat) { + p_->gyroscopeCovariance = measuredOmegaCovariance; + resetIntegration(); + } private: + + /** Serialization function */ + friend class boost::serialization::access; + template + void serialize(ARCHIVE & ar, const unsigned int /*version*/) { + ar & BOOST_SERIALIZATION_BASE_OBJECT_NVP(PreintegratedRotation); + ar & BOOST_SERIALIZATION_NVP(p_); + ar & BOOST_SERIALIZATION_NVP(biasHat_); + } +}; + +class GTSAM_EXPORT AHRSFactor: public NoiseModelFactor3 { + typedef AHRSFactor This; typedef NoiseModelFactor3 Base; - PreintegratedMeasurements _PIM_; - Vector3 gravity_; - Vector3 omegaCoriolis_; ///< Controls whether higher order terms are included when calculating the Coriolis Effect - boost::optional body_P_sensor_; ///< The pose of the sensor in the body frame + PreintegratedAhrsMeasurements _PIM_; + + /** Default constructor - only use for serialization */ + AHRSFactor() {} public: @@ -121,22 +124,15 @@ public: typedef boost::shared_ptr shared_ptr; #endif - /** Default constructor - only use for serialization */ - AHRSFactor(); - /** * Constructor * @param rot_i previous rot key * @param rot_j current rot key * @param bias previous bias key * @param preintegratedMeasurements preintegrated measurements - * @param omegaCoriolis rotation rate of the inertial frame - * @param body_P_sensor Optional pose of the sensor frame in the body frame */ AHRSFactor(Key rot_i, Key rot_j, Key bias, - const PreintegratedMeasurements& preintegratedMeasurements, - const Vector3& omegaCoriolis, - boost::optional body_P_sensor = boost::none); + const PreintegratedAhrsMeasurements& preintegratedMeasurements); virtual ~AHRSFactor() { } @@ -152,14 +148,10 @@ public: virtual bool equals(const NonlinearFactor&, double tol = 1e-9) const; /// Access the preintegrated measurements. - const PreintegratedMeasurements& preintegratedMeasurements() const { + const PreintegratedAhrsMeasurements& preintegratedMeasurements() const { return _PIM_; } - const Vector3& omegaCoriolis() const { - return omegaCoriolis_; - } - /** implement functions needed to derive from Factor */ /// vector of errors @@ -169,10 +161,25 @@ public: boost::none) const; /// predicted states from IMU + /// TODO(frank): relationship with PIM predict ?? + static Rot3 Predict( + const Rot3& rot_i, const Vector3& bias, + const PreintegratedAhrsMeasurements preintegratedMeasurements); + + /// @deprecated name + typedef PreintegratedAhrsMeasurements PreintegratedMeasurements; + + /// @deprecated constructor + AHRSFactor(Key rot_i, Key rot_j, Key bias, + const PreintegratedMeasurements& preintegratedMeasurements, + const Vector3& omegaCoriolis, + const boost::optional& body_P_sensor = boost::none); + + /// @deprecated static function static Rot3 predict(const Rot3& rot_i, const Vector3& bias, const PreintegratedMeasurements preintegratedMeasurements, const Vector3& omegaCoriolis, - boost::optional body_P_sensor = boost::none); + const boost::optional& body_P_sensor = boost::none); private: @@ -184,13 +191,9 @@ private: & boost::serialization::make_nvp("NoiseModelFactor3", boost::serialization::base_object(*this)); ar & BOOST_SERIALIZATION_NVP(_PIM_); - ar & BOOST_SERIALIZATION_NVP(omegaCoriolis_); - ar & BOOST_SERIALIZATION_NVP(body_P_sensor_); } }; // AHRSFactor -typedef AHRSFactor::PreintegratedMeasurements AHRSFactorPreintegratedMeasurements; - } //namespace gtsam diff --git a/gtsam/navigation/CombinedImuFactor.cpp b/gtsam/navigation/CombinedImuFactor.cpp index 3547719ac..a961a79bd 100644 --- a/gtsam/navigation/CombinedImuFactor.cpp +++ b/gtsam/navigation/CombinedImuFactor.cpp @@ -1,6 +1,6 @@ /* ---------------------------------------------------------------------------- - * GTSAM Copyright 2010, Georgia Tech Research Corporation, + * 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) @@ -29,157 +29,131 @@ namespace gtsam { using namespace std; //------------------------------------------------------------------------------ -// Inner class CombinedPreintegratedMeasurements +// Inner class PreintegratedCombinedMeasurements //------------------------------------------------------------------------------ -CombinedImuFactor::CombinedPreintegratedMeasurements::CombinedPreintegratedMeasurements( - const imuBias::ConstantBias& bias, const Matrix3& measuredAccCovariance, - const Matrix3& measuredOmegaCovariance, - const Matrix3& integrationErrorCovariance, const Matrix3& biasAccCovariance, - const Matrix3& biasOmegaCovariance, const Matrix& biasAccOmegaInit, - const bool use2ndOrderIntegration) : - PreintegrationBase(bias, measuredAccCovariance, measuredOmegaCovariance, - integrationErrorCovariance, use2ndOrderIntegration), biasAccCovariance_( - biasAccCovariance), biasOmegaCovariance_(biasOmegaCovariance), biasAccOmegaInit_( - biasAccOmegaInit) { - preintMeasCov_.setZero(); -} - -//------------------------------------------------------------------------------ -void CombinedImuFactor::CombinedPreintegratedMeasurements::print( +void PreintegratedCombinedMeasurements::print( const string& s) const { PreintegrationBase::print(s); - cout << " biasAccCovariance [ " << biasAccCovariance_ << " ]" << endl; - cout << " biasOmegaCovariance [ " << biasOmegaCovariance_ << " ]" << endl; - cout << " biasAccOmegaInit [ " << biasAccOmegaInit_ << " ]" << endl; cout << " preintMeasCov [ " << preintMeasCov_ << " ]" << endl; } //------------------------------------------------------------------------------ -bool CombinedImuFactor::CombinedPreintegratedMeasurements::equals( - const CombinedPreintegratedMeasurements& expected, double tol) const { - return equal_with_abs_tol(biasAccCovariance_, expected.biasAccCovariance_, - tol) - && equal_with_abs_tol(biasOmegaCovariance_, expected.biasOmegaCovariance_, - tol) - && equal_with_abs_tol(biasAccOmegaInit_, expected.biasAccOmegaInit_, tol) - && equal_with_abs_tol(preintMeasCov_, expected.preintMeasCov_, tol) - && PreintegrationBase::equals(expected, tol); +bool PreintegratedCombinedMeasurements::equals( + const PreintegratedCombinedMeasurements& other, double tol) const { + return PreintegrationBase::equals(other, tol) && + equal_with_abs_tol(preintMeasCov_, other.preintMeasCov_, tol); } //------------------------------------------------------------------------------ -void CombinedImuFactor::CombinedPreintegratedMeasurements::resetIntegration() { +void PreintegratedCombinedMeasurements::resetIntegration() { PreintegrationBase::resetIntegration(); preintMeasCov_.setZero(); } //------------------------------------------------------------------------------ -void CombinedImuFactor::CombinedPreintegratedMeasurements::integrateMeasurement( - const Vector3& measuredAcc, const Vector3& measuredOmega, double deltaT, - boost::optional body_P_sensor, - boost::optional F_test, boost::optional G_test) { +// sugar for derivative blocks +#define D_R_R(H) (H)->block<3,3>(0,0) +#define D_R_t(H) (H)->block<3,3>(0,3) +#define D_R_v(H) (H)->block<3,3>(0,6) +#define D_t_R(H) (H)->block<3,3>(3,0) +#define D_t_t(H) (H)->block<3,3>(3,3) +#define D_t_v(H) (H)->block<3,3>(3,6) +#define D_v_R(H) (H)->block<3,3>(6,0) +#define D_v_t(H) (H)->block<3,3>(6,3) +#define D_v_v(H) (H)->block<3,3>(6,6) +#define D_a_a(H) (H)->block<3,3>(9,9) +#define D_g_g(H) (H)->block<3,3>(12,12) - // NOTE: order is important here because each update uses old values, e.g., velocity and position updates are based on previous rotation estimate. - // (i.e., we have to update jacobians and covariances before updating preintegrated measurements). +//------------------------------------------------------------------------------ +void PreintegratedCombinedMeasurements::integrateMeasurement( + const Vector3& measuredAcc, const Vector3& measuredOmega, double dt) { + // Update preintegrated measurements. + Matrix9 A; // overall Jacobian wrt preintegrated measurements (df/dx) + Matrix93 B, C; + PreintegrationBase::integrateMeasurement(measuredAcc, measuredOmega, dt, &A, &B, &C); - Vector3 correctedAcc, correctedOmega; - correctMeasurementsByBiasAndSensorPose(measuredAcc, measuredOmega, - correctedAcc, correctedOmega, body_P_sensor); - - const Vector3 integratedOmega = correctedOmega * deltaT; // rotation vector describing rotation increment computed from the current rotation rate measurement - Matrix3 D_Rincr_integratedOmega; // Right jacobian computed at theta_incr - const Rot3 Rincr = Rot3::Expmap(integratedOmega, D_Rincr_integratedOmega); // rotation increment computed from the current rotation rate measurement - - // Update Jacobians - /* ----------------------------------------------------------------------------------------------------------------------- */ - updatePreintegratedJacobians(correctedAcc, D_Rincr_integratedOmega, Rincr, - deltaT); - - // Update preintegrated measurements covariance: as in [2] we consider a first order propagation that - // can be seen as a prediction phase in an EKF framework. In this implementation, contrarily to [2] we - // consider the uncertainty of the bias selection and we keep correlation between biases and preintegrated measurements - /* ----------------------------------------------------------------------------------------------------------------------- */ - const Matrix3 R_i = deltaRij(); // store this - // Update preintegrated measurements. TODO Frank moved from end of this function !!! - Matrix9 F_9x9; - updatePreintegratedMeasurements(correctedAcc, Rincr, deltaT, F_9x9); + // Update preintegrated measurements covariance: as in [2] we consider a first + // order propagation that can be seen as a prediction phase in an EKF + // framework. In this implementation, in contrast to [2], we consider the + // uncertainty of the bias selection and we keep correlation between biases + // and preintegrated measurements // Single Jacobians to propagate covariance - Matrix3 H_vel_biasacc = -R_i * deltaT; - Matrix3 H_angles_biasomega = -D_Rincr_integratedOmega * deltaT; + // TODO(frank): should we not also accout for bias on position? + Matrix3 theta_H_biasOmega = - C.topRows<3>(); + Matrix3 vel_H_biasAcc = -B.bottomRows<3>(); // overall Jacobian wrt preintegrated measurements (df/dx) - Matrix F(15, 15); - // for documentation: - // F << I_3x3, I_3x3 * deltaT, Z_3x3, Z_3x3, Z_3x3, - // Z_3x3, I_3x3, H_vel_angles, H_vel_biasacc, Z_3x3, - // Z_3x3, Z_3x3, H_angles_angles, Z_3x3, H_angles_biasomega, - // Z_3x3, Z_3x3, Z_3x3, I_3x3, Z_3x3, - // Z_3x3, Z_3x3, Z_3x3, Z_3x3, I_3x3; + Eigen::Matrix F; F.setZero(); - F.block<9, 9>(0, 0) = F_9x9; + F.block<9, 9>(0, 0) = A; + F.block<3, 3>(0, 12) = theta_H_biasOmega; + F.block<3, 3>(6, 9) = vel_H_biasAcc; F.block<6, 6>(9, 9) = I_6x6; - F.block<3, 3>(3, 9) = H_vel_biasacc; - F.block<3, 3>(6, 12) = H_angles_biasomega; + + // propagate uncertainty + // TODO(frank): use noiseModel routine so we can have arbitrary noise models. + const Matrix3& aCov = p().accelerometerCovariance; + const Matrix3& wCov = p().gyroscopeCovariance; + const Matrix3& iCov = p().integrationCovariance; // first order uncertainty propagation - // Optimized matrix multiplication (1/deltaT) * G * measurementCovariance * G.transpose() - Matrix G_measCov_Gt = Matrix::Zero(15, 15); + // Optimized matrix multiplication (1/dt) * G * measurementCovariance * + // G.transpose() + Eigen::Matrix G_measCov_Gt; + G_measCov_Gt.setZero(15, 15); + + // BLOCK DIAGONAL TERMS + D_t_t(&G_measCov_Gt) = dt * iCov; + D_v_v(&G_measCov_Gt) = (1 / dt) * vel_H_biasAcc * + (aCov + p().biasAccOmegaInt.block<3, 3>(0, 0)) * + (vel_H_biasAcc.transpose()); + D_R_R(&G_measCov_Gt) = (1 / dt) * theta_H_biasOmega * + (wCov + p().biasAccOmegaInt.block<3, 3>(3, 3)) * + (theta_H_biasOmega.transpose()); + D_a_a(&G_measCov_Gt) = dt * p().biasAccCovariance; + D_g_g(&G_measCov_Gt) = dt * p().biasOmegaCovariance; -// BLOCK DIAGONAL TERMS - G_measCov_Gt.block<3, 3>(0, 0) = deltaT * integrationCovariance(); - G_measCov_Gt.block<3, 3>(3, 3) = (1 / deltaT) * (H_vel_biasacc) - * (accelerometerCovariance() + biasAccOmegaInit_.block<3, 3>(0, 0)) - * (H_vel_biasacc.transpose()); - G_measCov_Gt.block<3, 3>(6, 6) = (1 / deltaT) * (H_angles_biasomega) - * (gyroscopeCovariance() + biasAccOmegaInit_.block<3, 3>(3, 3)) - * (H_angles_biasomega.transpose()); - G_measCov_Gt.block<3, 3>(9, 9) = (1 / deltaT) * biasAccCovariance_; - G_measCov_Gt.block<3, 3>(12, 12) = (1 / deltaT) * biasOmegaCovariance_; // OFF BLOCK DIAGONAL TERMS - Matrix3 block23 = H_vel_biasacc * biasAccOmegaInit_.block<3, 3>(3, 0) - * H_angles_biasomega.transpose(); - G_measCov_Gt.block<3, 3>(3, 6) = block23; - G_measCov_Gt.block<3, 3>(6, 3) = block23.transpose(); + Matrix3 temp = vel_H_biasAcc * p().biasAccOmegaInt.block<3, 3>(3, 0) * + theta_H_biasOmega.transpose(); + D_v_R(&G_measCov_Gt) = temp; + D_R_v(&G_measCov_Gt) = temp.transpose(); preintMeasCov_ = F * preintMeasCov_ * F.transpose() + G_measCov_Gt; - - // F_test and G_test are used for testing purposes and are not needed by the factor - if (F_test) { - F_test->resize(15, 15); - (*F_test) << F; - } - if (G_test) { - G_test->resize(15, 21); - // This is for testing & documentation - ///< measurementCovariance_ : cov[integrationError measuredAcc measuredOmega biasAccRandomWalk biasOmegaRandomWalk biasAccInit biasOmegaInit] in R^(21 x 21) - (*G_test) << // - I_3x3 * deltaT, Z_3x3, Z_3x3, Z_3x3, Z_3x3, Z_3x3, Z_3x3, // - Z_3x3, -H_vel_biasacc, Z_3x3, Z_3x3, Z_3x3, H_vel_biasacc, Z_3x3, // - Z_3x3, Z_3x3, -H_angles_biasomega, Z_3x3, Z_3x3, Z_3x3, H_angles_biasomega, // - Z_3x3, Z_3x3, Z_3x3, I_3x3, Z_3x3, Z_3x3, Z_3x3, // - Z_3x3, Z_3x3, Z_3x3, Z_3x3, I_3x3, Z_3x3, Z_3x3; - } } +//------------------------------------------------------------------------------ +#ifdef GTSAM_ALLOW_DEPRECATED_SINCE_V4 +PreintegratedCombinedMeasurements::PreintegratedCombinedMeasurements( + const imuBias::ConstantBias& biasHat, const Matrix3& measuredAccCovariance, + const Matrix3& measuredOmegaCovariance, + const Matrix3& integrationErrorCovariance, const Matrix3& biasAccCovariance, + const Matrix3& biasOmegaCovariance, const Matrix6& biasAccOmegaInt, + const bool use2ndOrderIntegration) { + if (!use2ndOrderIntegration) + throw("PreintegratedImuMeasurements no longer supports first-order integration: it incorrectly compensated for gravity"); + biasHat_ = biasHat; + boost::shared_ptr p = Params::MakeSharedD(); + p->gyroscopeCovariance = measuredOmegaCovariance; + p->accelerometerCovariance = measuredAccCovariance; + p->integrationCovariance = integrationErrorCovariance; + p->biasAccCovariance = biasAccCovariance; + p->biasOmegaCovariance = biasOmegaCovariance; + p->biasAccOmegaInt = biasAccOmegaInt; + p_ = p; + resetIntegration(); + preintMeasCov_.setZero(); +} +#endif //------------------------------------------------------------------------------ // CombinedImuFactor methods //------------------------------------------------------------------------------ -CombinedImuFactor::CombinedImuFactor() : - ImuFactorBase(), _PIM_(imuBias::ConstantBias(), Z_3x3, Z_3x3, Z_3x3, Z_3x3, - Z_3x3, Z_6x6) { -} - -//------------------------------------------------------------------------------ -CombinedImuFactor::CombinedImuFactor(Key pose_i, Key vel_i, Key pose_j, - Key vel_j, Key bias_i, Key bias_j, - const CombinedPreintegratedMeasurements& preintegratedMeasurements, - const Vector3& gravity, const Vector3& omegaCoriolis, - boost::optional body_P_sensor, const bool use2ndOrderCoriolis) : - Base( - noiseModel::Gaussian::Covariance( - preintegratedMeasurements.preintMeasCov_), pose_i, vel_i, pose_j, - vel_j, bias_i, bias_j), ImuFactorBase(gravity, omegaCoriolis, - body_P_sensor, use2ndOrderCoriolis), _PIM_(preintegratedMeasurements) { -} +CombinedImuFactor::CombinedImuFactor( + Key pose_i, Key vel_i, Key pose_j, Key vel_j, Key bias_i, Key bias_j, + const PreintegratedCombinedMeasurements& pim) + : Base(noiseModel::Gaussian::Covariance(pim.preintMeasCov_), pose_i, vel_i, + pose_j, vel_j, bias_i, bias_j), + _PIM_(pim) {} //------------------------------------------------------------------------------ gtsam::NonlinearFactor::shared_ptr CombinedImuFactor::clone() const { @@ -194,17 +168,14 @@ void CombinedImuFactor::print(const string& s, << keyFormatter(this->key2()) << "," << keyFormatter(this->key3()) << "," << keyFormatter(this->key4()) << "," << keyFormatter(this->key5()) << "," << keyFormatter(this->key6()) << ")\n"; - ImuFactorBase::print(""); _PIM_.print(" preintegrated measurements:"); this->noiseModel_->print(" noise model: "); } //------------------------------------------------------------------------------ -bool CombinedImuFactor::equals(const NonlinearFactor& expected, - double tol) const { - const This *e = dynamic_cast(&expected); - return e != NULL && Base::equals(*e, tol) && _PIM_.equals(e->_PIM_, tol) - && ImuFactorBase::equals(*e, tol); +bool CombinedImuFactor::equals(const NonlinearFactor& other, double tol) const { + const This* e = dynamic_cast(&other); + return e != NULL && Base::equals(*e, tol) && _PIM_.equals(e->_PIM_, tol); } //------------------------------------------------------------------------------ @@ -224,8 +195,7 @@ Vector CombinedImuFactor::evaluateError(const Pose3& pose_i, Matrix93 D_r_vel_i, D_r_vel_j; // error wrt preintegrated measurements - Vector9 r_pvR = _PIM_.computeErrorAndJacobians(pose_i, vel_i, pose_j, vel_j, - bias_i, gravity_, omegaCoriolis_, use2ndOrderCoriolis_, + Vector9 r_Rpv = _PIM_.computeErrorAndJacobians(pose_i, vel_i, pose_j, vel_j, bias_i, H1 ? &D_r_pose_i : 0, H2 ? &D_r_vel_i : 0, H3 ? &D_r_pose_j : 0, H4 ? &D_r_vel_j : 0, H5 ? &D_r_bias_i : 0); @@ -234,25 +204,25 @@ Vector CombinedImuFactor::evaluateError(const Pose3& pose_i, H1->resize(15, 6); H1->block<9, 6>(0, 0) = D_r_pose_i; // adding: [dBiasAcc/dPi ; dBiasOmega/dPi] - H1->block<6, 6>(9, 0) = Z_6x6; + H1->block<6, 6>(9, 0).setZero(); } if (H2) { H2->resize(15, 3); H2->block<9, 3>(0, 0) = D_r_vel_i; // adding: [dBiasAcc/dVi ; dBiasOmega/dVi] - H2->block<6, 3>(9, 0) = Matrix::Zero(6, 3); + H2->block<6, 3>(9, 0).setZero(); } if (H3) { H3->resize(15, 6); H3->block<9, 6>(0, 0) = D_r_pose_j; // adding: [dBiasAcc/dPj ; dBiasOmega/dPj] - H3->block<6, 6>(9, 0) = Z_6x6; + H3->block<6, 6>(9, 0).setZero(); } if (H4) { H4->resize(15, 3); H4->block<9, 3>(0, 0) = D_r_vel_j; // adding: [dBiasAcc/dVi ; dBiasOmega/dVi] - H4->block<6, 3>(9, 0) = Matrix::Zero(6, 3); + H4->block<6, 3>(9, 0).setZero(); } if (H5) { H5->resize(15, 6); @@ -262,15 +232,50 @@ Vector CombinedImuFactor::evaluateError(const Pose3& pose_i, } if (H6) { H6->resize(15, 6); - H6->block<9, 6>(0, 0) = Matrix::Zero(9, 6); + H6->block<9, 6>(0, 0).setZero(); // adding: [dBiasAcc/dBias_j ; dBiasOmega/dBias_j] H6->block<6, 6>(9, 0) = Hbias_j; } // overall error Vector r(15); - r << r_pvR, fbias; // vector of size 15 + r << r_Rpv, fbias; // vector of size 15 return r; } +//------------------------------------------------------------------------------ +#ifdef GTSAM_ALLOW_DEPRECATED_SINCE_V4 +CombinedImuFactor::CombinedImuFactor( + Key pose_i, Key vel_i, Key pose_j, Key vel_j, Key bias_i, Key bias_j, + const CombinedPreintegratedMeasurements& pim, const Vector3& n_gravity, + const Vector3& omegaCoriolis, const boost::optional& body_P_sensor, + const bool use2ndOrderCoriolis) + : Base(noiseModel::Gaussian::Covariance(pim.preintMeasCov_), pose_i, vel_i, + pose_j, vel_j, bias_i, bias_j), + _PIM_(pim) { + boost::shared_ptr p = + boost::make_shared(pim.p()); + p->n_gravity = n_gravity; + p->omegaCoriolis = omegaCoriolis; + p->body_P_sensor = body_P_sensor; + p->use2ndOrderCoriolis = use2ndOrderCoriolis; + _PIM_.p_ = p; +} + +void CombinedImuFactor::Predict(const Pose3& pose_i, const Vector3& vel_i, + Pose3& pose_j, Vector3& vel_j, + const imuBias::ConstantBias& bias_i, + CombinedPreintegratedMeasurements& pim, + const Vector3& n_gravity, + const Vector3& omegaCoriolis, + const bool use2ndOrderCoriolis) { + // use deprecated predict + PoseVelocityBias pvb = pim.predict(pose_i, vel_i, bias_i, n_gravity, + omegaCoriolis, use2ndOrderCoriolis); + pose_j = pvb.pose; + vel_j = pvb.velocity; +} +#endif + } /// namespace gtsam + diff --git a/gtsam/navigation/CombinedImuFactor.h b/gtsam/navigation/CombinedImuFactor.h index a65a4d3f7..3141f8245 100644 --- a/gtsam/navigation/CombinedImuFactor.h +++ b/gtsam/navigation/CombinedImuFactor.h @@ -1,6 +1,6 @@ /* ---------------------------------------------------------------------------- - * GTSAM Copyright 2010, Georgia Tech Research Corporation, + * 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) @@ -24,21 +24,17 @@ /* GTSAM includes */ #include #include -#include -#include +#include namespace gtsam { -/** - * - * @addtogroup SLAM - * +/* * If you are using the factor, please cite: * L. Carlone, Z. Kira, C. Beall, V. Indelman, F. Dellaert, Eliminating * conditionally independent sets in factor graphs: a unifying perspective based * on smart factors, Int. Conf. on Robotics and Automation (ICRA), 2014. * - ** REFERENCES: + * REFERENCES: * [1] G.S. Chirikjian, "Stochastic Models, Information Theory, and Lie Groups", * Volume 2, 2008. * [2] T. Lupton and S.Sukkarieh, "Visual-Inertial-Aided Navigation for @@ -46,14 +42,158 @@ namespace gtsam { * TRO, 28(1):61-76, 2012. * [3] L. Carlone, S. Williams, R. Roberts, "Preintegrated IMU factor: * Computation of the Jacobian Matrices", Tech. Report, 2013. + * [4] C. Forster, L. Carlone, F. Dellaert, D. Scaramuzza, IMU Preintegration on + * Manifold for Efficient Visual-Inertial Maximum-a-Posteriori Estimation, + * Robotics: Science and Systems (RSS), 2015. */ +/** + * PreintegratedCombinedMeasurements integrates the IMU measurements + * (rotation rates and accelerations) and the corresponding covariance matrix. + * The measurements are then used to build the CombinedImuFactor. Integration + * is done incrementally (ideally, one integrates the measurement as soon as + * it is received from the IMU) so as to avoid costly integration at time of + * factor construction. + * + * @addtogroup SLAM + */ +class PreintegratedCombinedMeasurements : public PreintegrationBase { + +public: + + /// Parameters for pre-integration: + /// Usage: Create just a single Params and pass a shared pointer to the constructor + struct Params : PreintegrationParams { + Matrix3 biasAccCovariance; ///< continuous-time "Covariance" describing accelerometer bias random walk + Matrix3 biasOmegaCovariance; ///< continuous-time "Covariance" describing gyroscope bias random walk + Matrix6 biasAccOmegaInt; ///< covariance of bias used for pre-integration + + /// See two named constructors below for good values of n_gravity in body frame + Params(const Vector3& n_gravity) : + PreintegrationParams(n_gravity), biasAccCovariance(I_3x3), biasOmegaCovariance( + I_3x3), biasAccOmegaInt(I_6x6) { + } + + // Default Params for a Z-down navigation frame, such as NED: gravity points along positive Z-axis + static boost::shared_ptr MakeSharedD(double g = 9.81) { + return boost::make_shared(Vector3(0, 0, g)); + } + + // Default Params for a Z-up navigation frame, such as ENU: gravity points along negative Z-axis + static boost::shared_ptr MakeSharedU(double g = 9.81) { + return boost::make_shared(Vector3(0, 0, -g)); + } + + private: + /// Default constructor makes unitialized params struct + Params() {} + + /** Serialization function */ + friend class boost::serialization::access; + template + void serialize(ARCHIVE& ar, const unsigned int /*version*/) { + ar& BOOST_SERIALIZATION_BASE_OBJECT_NVP(PreintegratedRotation::Params); + ar& BOOST_SERIALIZATION_NVP(biasAccCovariance); + ar& BOOST_SERIALIZATION_NVP(biasOmegaCovariance); + ar& BOOST_SERIALIZATION_NVP(biasAccOmegaInt); + } + }; + + protected: + /* Covariance matrix of the preintegrated measurements + * COVARIANCE OF: [PreintPOSITION PreintVELOCITY PreintROTATION BiasAcc BiasOmega] + * (first-order propagation from *measurementCovariance*). + * PreintegratedCombinedMeasurements also include the biases and keep the correlation + * between the preintegrated measurements and the biases + */ + Eigen::Matrix preintMeasCov_; + + PreintegratedCombinedMeasurements() {} + + friend class CombinedImuFactor; + + public: + /// @name Constructors + /// @{ + + /** + * Default constructor, initializes the class with no measurements + * @param bias Current estimate of acceleration and rotation rate biases + */ + PreintegratedCombinedMeasurements( + const boost::shared_ptr& p, + const imuBias::ConstantBias& biasHat = imuBias::ConstantBias()) + : PreintegrationBase(p, biasHat) { + preintMeasCov_.setZero(); + } + + /// @} + + /// @name Basic utilities + /// @{ + + /// Re-initialize PreintegratedCombinedMeasurements + void resetIntegration(); + + /// const reference to params, shadows definition in base class + Params& p() const { return *boost::static_pointer_cast(p_);} + /// @} + + /// @name Access instance variables + /// @{ + Matrix preintMeasCov() const { return preintMeasCov_; } + /// @} + + /// @name Testable + /// @{ + void print(const std::string& s = "Preintegrated Measurements:") const; + bool equals(const PreintegratedCombinedMeasurements& expected, double tol = 1e-9) const; + /// @} + + /// @name Main functionality + /// @{ + + /** + * Add a single IMU measurement to the preintegration. + * @param measuredAcc Measured acceleration (in body frame, as given by the + * sensor) + * @param measuredOmega Measured angular velocity (as given by the sensor) + * @param deltaT Time interval between two consecutive IMU measurements + * @param body_P_sensor Optional sensor frame (pose of the IMU in the body + * frame) + */ + void integrateMeasurement(const Vector3& measuredAcc, + const Vector3& measuredOmega, double deltaT); + + /// @} + +#ifdef GTSAM_ALLOW_DEPRECATED_SINCE_V4 + /// deprecated constructor + /// NOTE(frank): assumes Z-Down convention, only second order integration supported + PreintegratedCombinedMeasurements(const imuBias::ConstantBias& biasHat, + const Matrix3& measuredAccCovariance, + const Matrix3& measuredOmegaCovariance, + const Matrix3& integrationErrorCovariance, + const Matrix3& biasAccCovariance, const Matrix3& biasOmegaCovariance, + const Matrix6& biasAccOmegaInt, const bool use2ndOrderIntegration = true); +#endif + + private: + /// Serialization function + friend class boost::serialization::access; + template + void serialize(ARCHIVE& ar, const unsigned int /*version*/) { + ar& BOOST_SERIALIZATION_BASE_OBJECT_NVP(PreintegrationBase); + ar& BOOST_SERIALIZATION_NVP(preintMeasCov_); + } +}; + /** * CombinedImuFactor is a 6-ways factor involving previous state (pose and * velocity of the vehicle, as well as bias at previous time step), and current * state (pose, velocity, bias at current time step). Following the pre- * integration scheme proposed in [2], the CombinedImuFactor includes many IMU - * measurements, which are "summarized" using the CombinedPreintegratedMeasurements + * measurements, which are "summarized" using the PreintegratedCombinedMeasurements * class. There are 3 main differences wrpt the ImuFactor class: * 1) The factor is 6-ways, meaning that it also involves both biases (previous * and current time step).Therefore, the factor internally imposes the biases @@ -61,105 +201,26 @@ namespace gtsam { * "biasOmegaCovariance" described the random walk that models bias evolution. * 2) The preintegration covariance takes into account the noise in the bias * estimate used for integration. - * 3) The covariance matrix of the CombinedPreintegratedMeasurements preserves + * 3) The covariance matrix of the PreintegratedCombinedMeasurements preserves * the correlation between the bias uncertainty and the preintegrated * measurements uncertainty. + * + * @addtogroup SLAM */ class CombinedImuFactor: public NoiseModelFactor6, public ImuFactorBase { + Vector3, imuBias::ConstantBias, imuBias::ConstantBias> { public: - /** - * CombinedPreintegratedMeasurements integrates the IMU measurements - * (rotation rates and accelerations) and the corresponding covariance matrix. - * The measurements are then used to build the CombinedImuFactor. Integration - * is done incrementally (ideally, one integrates the measurement as soon as - * it is received from the IMU) so as to avoid costly integration at time of - * factor construction. - */ - class CombinedPreintegratedMeasurements: public PreintegrationBase { - - friend class CombinedImuFactor; - - protected: - - Matrix3 biasAccCovariance_; ///< continuous-time "Covariance" describing accelerometer bias random walk - Matrix3 biasOmegaCovariance_; ///< continuous-time "Covariance" describing gyroscope bias random walk - Matrix6 biasAccOmegaInit_; ///< covariance of bias used for pre-integration - - Eigen::Matrix preintMeasCov_; ///< Covariance matrix of the preintegrated measurements - ///< COVARIANCE OF: [PreintPOSITION PreintVELOCITY PreintROTATION BiasAcc BiasOmega] - ///< (first-order propagation from *measurementCovariance*). CombinedPreintegratedMeasurements also include the biases and keep the correlation - ///< between the preintegrated measurements and the biases - - public: - - /** - * Default constructor, initializes the class with no measurements - * @param bias Current estimate of acceleration and rotation rate biases - * @param measuredAccCovariance Covariance matrix of measuredAcc - * @param measuredOmegaCovariance Covariance matrix of measured Angular Rate - * @param integrationErrorCovariance Covariance matrix of integration errors (velocity -> position) - * @param biasAccCovariance Covariance matrix of biasAcc (random walk describing BIAS evolution) - * @param biasOmegaCovariance Covariance matrix of biasOmega (random walk describing BIAS evolution) - * @param biasAccOmegaInit Covariance of biasAcc & biasOmega when preintegrating measurements - * @param use2ndOrderIntegration Controls the order of integration - * (if false: p(t+1) = p(t) + v(t) deltaT ; if true: p(t+1) = p(t) + v(t) deltaT + 0.5 * acc(t) deltaT^2) - */ - CombinedPreintegratedMeasurements(const imuBias::ConstantBias& bias, - const Matrix3& measuredAccCovariance, - const Matrix3& measuredOmegaCovariance, - const Matrix3& integrationErrorCovariance, - const Matrix3& biasAccCovariance, const Matrix3& biasOmegaCovariance, - const Matrix& biasAccOmegaInit, const bool use2ndOrderIntegration = - false); - - /// print - void print(const std::string& s = "Preintegrated Measurements:") const; - - /// equals - bool equals(const CombinedPreintegratedMeasurements& expected, double tol = - 1e-9) const; - - /// Re-initialize CombinedPreintegratedMeasurements - void resetIntegration(); - - /** - * Add a single IMU measurement to the preintegration. - * @param measuredAcc Measured acceleration (in body frame, as given by the sensor) - * @param measuredOmega Measured angular velocity (as given by the sensor) - * @param deltaT Time interval between two consecutive IMU measurements - * @param body_P_sensor Optional sensor frame (pose of the IMU in the body frame) - */ - void integrateMeasurement(const Vector3& measuredAcc, - const Vector3& measuredOmega, double deltaT, - boost::optional body_P_sensor = boost::none, - boost::optional F_test = boost::none, - boost::optional G_test = boost::none); - - /// methods to access class variables - Matrix preintMeasCov() const { - return preintMeasCov_; - } - - private: - - /// Serialization function - friend class boost::serialization::access; - template - void serialize(ARCHIVE & ar, const unsigned int /*version*/) { - ar & BOOST_SERIALIZATION_BASE_OBJECT_NVP(PreintegrationBase); - ar & BOOST_SERIALIZATION_NVP(preintMeasCov_); - } - }; - private: typedef CombinedImuFactor This; typedef NoiseModelFactor6 Base; - CombinedPreintegratedMeasurements _PIM_; + PreintegratedCombinedMeasurements _PIM_; + + /** Default constructor - only use for serialization */ + CombinedImuFactor() {} public: @@ -170,9 +231,6 @@ public: typedef boost::shared_ptr shared_ptr; #endif - /** Default constructor - only use for serialization */ - CombinedImuFactor(); - /** * Constructor * @param pose_i Previous pose key @@ -181,21 +239,13 @@ public: * @param vel_j Current velocity key * @param bias_i Previous bias key * @param bias_j Current bias key - * @param CombinedPreintegratedMeasurements CombinedPreintegratedMeasurements IMU measurements - * @param gravity Gravity vector expressed in the global frame - * @param omegaCoriolis Rotation rate of the global frame w.r.t. an inertial frame - * @param body_P_sensor Optional pose of the sensor frame in the body frame - * @param use2ndOrderCoriolis When true, the second-order term is used in the calculation of the Coriolis Effect + * @param PreintegratedCombinedMeasurements Combined IMU measurements */ - CombinedImuFactor(Key pose_i, Key vel_i, Key pose_j, Key vel_j, Key bias_i, - Key bias_j, - const CombinedPreintegratedMeasurements& preintegratedMeasurements, - const Vector3& gravity, const Vector3& omegaCoriolis, - boost::optional body_P_sensor = boost::none, - const bool use2ndOrderCoriolis = false); + CombinedImuFactor( + Key pose_i, Key vel_i, Key pose_j, Key vel_j, Key bias_i, Key bias_j, + const PreintegratedCombinedMeasurements& preintegratedMeasurements); - virtual ~CombinedImuFactor() { - } + virtual ~CombinedImuFactor() {} /// @return a deep copy of this factor virtual gtsam::NonlinearFactor::shared_ptr clone() const; @@ -211,7 +261,7 @@ public: /** Access the preintegrated measurements. */ - const CombinedPreintegratedMeasurements& preintegratedMeasurements() const { + const PreintegratedCombinedMeasurements& preintegratedMeasurements() const { return _PIM_; } @@ -226,20 +276,24 @@ public: boost::optional H4 = boost::none, boost::optional H5 = boost::none, boost::optional H6 = boost::none) const; - /** @deprecated The following function has been deprecated, use PreintegrationBase::predict with the same signature instead */ +#ifdef GTSAM_ALLOW_DEPRECATED_SINCE_V4 + /// @deprecated typename + typedef gtsam::PreintegratedCombinedMeasurements CombinedPreintegratedMeasurements; + + /// @deprecated constructor + CombinedImuFactor(Key pose_i, Key vel_i, Key pose_j, Key vel_j, Key bias_i, + Key bias_j, const CombinedPreintegratedMeasurements& pim, + const Vector3& n_gravity, const Vector3& omegaCoriolis, + const boost::optional& body_P_sensor = boost::none, + const bool use2ndOrderCoriolis = false); + + // @deprecated use PreintegrationBase::predict static void Predict(const Pose3& pose_i, const Vector3& vel_i, Pose3& pose_j, - Vector3& vel_j, const imuBias::ConstantBias& bias_i, - const CombinedPreintegratedMeasurements& PIM, const Vector3& gravity, - const Vector3& omegaCoriolis, const bool use2ndOrderCoriolis = false, - boost::optional deltaPij_biascorrected_out = boost::none, - boost::optional deltaVij_biascorrected_out = boost::none) { - PoseVelocityBias PVB( - PIM.predict(pose_i, vel_i, bias_i, gravity, omegaCoriolis, - use2ndOrderCoriolis, deltaPij_biascorrected_out, - deltaVij_biascorrected_out)); - pose_j = PVB.pose; - vel_j = PVB.velocity; - } + Vector3& vel_j, const imuBias::ConstantBias& bias_i, + CombinedPreintegratedMeasurements& pim, + const Vector3& n_gravity, const Vector3& omegaCoriolis, + const bool use2ndOrderCoriolis = false); +#endif private: @@ -250,13 +304,8 @@ private: ar & boost::serialization::make_nvp("NoiseModelFactor6", boost::serialization::base_object(*this)); ar & BOOST_SERIALIZATION_NVP(_PIM_); - ar & BOOST_SERIALIZATION_NVP(gravity_); - ar & BOOST_SERIALIZATION_NVP(omegaCoriolis_); - ar & BOOST_SERIALIZATION_NVP(body_P_sensor_); } }; // class CombinedImuFactor -typedef CombinedImuFactor::CombinedPreintegratedMeasurements CombinedImuFactorPreintegratedMeasurements; - } /// namespace gtsam diff --git a/gtsam/navigation/GPSFactor.cpp b/gtsam/navigation/GPSFactor.cpp index bfd3ebb52..87913cda6 100644 --- a/gtsam/navigation/GPSFactor.cpp +++ b/gtsam/navigation/GPSFactor.cpp @@ -58,10 +58,10 @@ pair GPSFactor::EstimateState(double t1, const Point3& NED1, // Estimate Rotation double yaw = atan2(nV.y(), nV.x()); - Rot3 nRy = Rot3::yaw(yaw); // yaw frame + Rot3 nRy = Rot3::Yaw(yaw); // yaw frame Point3 yV = nRy.inverse() * nV; // velocity in yaw frame double pitch = -atan2(yV.z(), yV.x()), roll = 0; - Rot3 nRb = Rot3::ypr(yaw, pitch, roll); + Rot3 nRb = Rot3::Ypr(yaw, pitch, roll); // Construct initial pose Pose3 nTb(nRb, nT); // nTb diff --git a/gtsam/navigation/ImuBias.cpp b/gtsam/navigation/ImuBias.cpp new file mode 100644 index 000000000..0dbc5736f --- /dev/null +++ b/gtsam/navigation/ImuBias.cpp @@ -0,0 +1,82 @@ +/* ---------------------------------------------------------------------------- + + * 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 ImuBias.cpp + * @date Feb 2, 2012 + * @author Vadim Indelman, Stephen Williams + */ + +#include "ImuBias.h" + +#include +#include + +namespace gtsam { + +/// All bias models live in the imuBias namespace +namespace imuBias { + +/* + * NOTES: + * - Earth-rate correction: + * + Currently the user should supply R_ECEF_to_G, which is the rotation from ECEF to Local-Level system (NED or ENU as defined by the user). + * + R_ECEF_to_G can be calculated by approximated values of latitude and longitude of the system. + * + A relatively small distance is traveled w.r.t. to initial pose is assumed, since R_ECEF_to_G is constant. + * Otherwise, R_ECEF_to_G should be updated each time using the current lat-lon. + * + * - Currently, an empty constructed is not enabled so that the user is forced to specify R_ECEF_to_G. + */ +// // H1: Jacobian w.r.t. IMUBias +// // H2: Jacobian w.r.t. pose +// Vector CorrectGyroWithEarthRotRate(Vector measurement, const Pose3& pose, const Vector& w_earth_rate_G, +// boost::optional H1=boost::none, boost::optional H2=boost::none) const { +// +// Matrix R_G_to_I( pose.rotation().matrix().transpose() ); +// Vector w_earth_rate_I = R_G_to_I * w_earth_rate_G; +// +// if (H1){ +// Matrix zeros3_3(zeros(3,3)); +// Matrix m_eye3(-eye(3)); +// +// *H1 = collect(2, &zeros3_3, &m_eye3); +// } +// +// if (H2){ +// Matrix zeros3_3(zeros(3,3)); +// Matrix H = -skewSymmetric(w_earth_rate_I); +// +// *H2 = collect(2, &H, &zeros3_3); +// } +// +// //TODO: Make sure H2 is correct. +// +// return measurement - biasGyro_ - w_earth_rate_I; +// +//// Vector bias_gyro_temp((Vector(3) << -bias_gyro_(0), bias_gyro_(1), bias_gyro_(2))); +//// return measurement - bias_gyro_temp - R_G_to_I * w_earth_rate_G; +// } +/// ostream operator +std::ostream& operator<<(std::ostream& os, const ConstantBias& bias) { + os << "acc = " << Point3(bias.accelerometer()); + os << " gyro = " << Point3(bias.gyroscope()); + return os; +} + +/// print with optional string +void ConstantBias::print(const std::string& s) const { + std::cout << s << *this << std::endl; +} + +} // namespace imuBias + +} // namespace gtsam + diff --git a/gtsam/navigation/ImuBias.h b/gtsam/navigation/ImuBias.h index 571fb7249..11799f310 100644 --- a/gtsam/navigation/ImuBias.h +++ b/gtsam/navigation/ImuBias.h @@ -17,22 +17,11 @@ #pragma once -#include -#include +#include #include +#include #include -/* - * NOTES: - * - Earth-rate correction: - * + Currently the user should supply R_ECEF_to_G, which is the rotation from ECEF to Local-Level system (NED or ENU as defined by the user). - * + R_ECEF_to_G can be calculated by approximated values of latitude and longitude of the system. - * + A relatively small distance is traveled w.r.t. to initial pose is assumed, since R_ECEF_to_G is constant. - * Otherwise, R_ECEF_to_G should be updated each time using the current lat-lon. - * - * - Currently, an empty constructed is not enabled so that the user is forced to specify R_ECEF_to_G. - */ - namespace gtsam { /// All bias models live in the imuBias namespace @@ -78,64 +67,32 @@ public: /** Correct an accelerometer measurement using this bias model, and optionally compute Jacobians */ Vector3 correctAccelerometer(const Vector3& measurement, - boost::optional H = boost::none) const { - if (H) { - H->resize(3, 6); - (*H) << -Matrix3::Identity(), Matrix3::Zero(); - } + OptionalJacobian<3, 6> H1 = boost::none, + OptionalJacobian<3, 3> H2 = boost::none) const { + if (H1) (*H1) << -I_3x3, Z_3x3; + if (H2) (*H2) << I_3x3; return measurement - biasAcc_; } /** Correct a gyroscope measurement using this bias model, and optionally compute Jacobians */ Vector3 correctGyroscope(const Vector3& measurement, - boost::optional H = boost::none) const { - if (H) { - H->resize(3, 6); - (*H) << Matrix3::Zero(), -Matrix3::Identity(); - } + OptionalJacobian<3, 6> H1 = boost::none, + OptionalJacobian<3, 3> H2 = boost::none) const { + if (H1) (*H1) << Z_3x3, -I_3x3; + if (H2) (*H2) << I_3x3; return measurement - biasGyro_; } -// // H1: Jacobian w.r.t. IMUBias -// // H2: Jacobian w.r.t. pose -// Vector CorrectGyroWithEarthRotRate(Vector measurement, const Pose3& pose, const Vector& w_earth_rate_G, -// boost::optional H1=boost::none, boost::optional H2=boost::none) const { -// -// Matrix R_G_to_I( pose.rotation().matrix().transpose() ); -// Vector w_earth_rate_I = R_G_to_I * w_earth_rate_G; -// -// if (H1){ -// Matrix zeros3_3(zeros(3,3)); -// Matrix m_eye3(-eye(3)); -// -// *H1 = collect(2, &zeros3_3, &m_eye3); -// } -// -// if (H2){ -// Matrix zeros3_3(zeros(3,3)); -// Matrix H = -skewSymmetric(w_earth_rate_I); -// -// *H2 = collect(2, &H, &zeros3_3); -// } -// -// //TODO: Make sure H2 is correct. -// -// return measurement - biasGyro_ - w_earth_rate_I; -// -//// Vector bias_gyro_temp((Vector(3) << -bias_gyro_(0), bias_gyro_(1), bias_gyro_(2))); -//// return measurement - bias_gyro_temp - R_G_to_I * w_earth_rate_G; -// } + /// @} + /// @name Testable + /// @{ -/// @} -/// @name Testable -/// @{ + /// ostream operator + GTSAM_EXPORT friend std::ostream& operator<<(std::ostream& os, + const ConstantBias& bias); -/// print with optional string - void print(const std::string& s = "") const { - // explicit printing for now. - std::cout << s + ".Acc [" << biasAcc_.transpose() << "]" << std::endl; - std::cout << s + ".Gyro [" << biasGyro_.transpose() << "]" << std::endl; - } + /// print with optional string + void print(const std::string& s = "") const; /** equality up to tolerance */ inline bool equals(const ConstantBias& expected, double tol = 1e-5) const { @@ -203,7 +160,6 @@ private: friend class boost::serialization::access; template void serialize(ARCHIVE & ar, const unsigned int /*version*/) { - ar & boost::serialization::make_nvp("imuBias::ConstantBias", *this); ar & BOOST_SERIALIZATION_NVP(biasAcc_); ar & BOOST_SERIALIZATION_NVP(biasGyro_); } diff --git a/gtsam/navigation/ImuFactor.cpp b/gtsam/navigation/ImuFactor.cpp index 01de5a8f3..145359d91 100644 --- a/gtsam/navigation/ImuFactor.cpp +++ b/gtsam/navigation/ImuFactor.cpp @@ -1,6 +1,6 @@ /* ---------------------------------------------------------------------------- - * GTSAM Copyright 2010, Georgia Tech Research Corporation, + * 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) @@ -29,121 +29,102 @@ namespace gtsam { using namespace std; //------------------------------------------------------------------------------ -// Inner class PreintegratedMeasurements +// Inner class PreintegratedImuMeasurements //------------------------------------------------------------------------------ -ImuFactor::PreintegratedMeasurements::PreintegratedMeasurements( - const imuBias::ConstantBias& bias, const Matrix3& measuredAccCovariance, - const Matrix3& measuredOmegaCovariance, - const Matrix3& integrationErrorCovariance, - const bool use2ndOrderIntegration) : - PreintegrationBase(bias, measuredAccCovariance, measuredOmegaCovariance, - integrationErrorCovariance, use2ndOrderIntegration) { - preintMeasCov_.setZero(); -} - -//------------------------------------------------------------------------------ -void ImuFactor::PreintegratedMeasurements::print(const string& s) const { +void PreintegratedImuMeasurements::print(const string& s) const { PreintegrationBase::print(s); + cout << " preintMeasCov \n[" << preintMeasCov_ << "]" << endl; } //------------------------------------------------------------------------------ -bool ImuFactor::PreintegratedMeasurements::equals( - const PreintegratedMeasurements& expected, double tol) const { - return equal_with_abs_tol(preintMeasCov_, expected.preintMeasCov_, tol) - && PreintegrationBase::equals(expected, tol); +bool PreintegratedImuMeasurements::equals( + const PreintegratedImuMeasurements& other, double tol) const { + return PreintegrationBase::equals(other, tol) + && equal_with_abs_tol(preintMeasCov_, other.preintMeasCov_, tol); } //------------------------------------------------------------------------------ -void ImuFactor::PreintegratedMeasurements::resetIntegration() { +void PreintegratedImuMeasurements::resetIntegration() { PreintegrationBase::resetIntegration(); preintMeasCov_.setZero(); } //------------------------------------------------------------------------------ -void ImuFactor::PreintegratedMeasurements::integrateMeasurement( - const Vector3& measuredAcc, const Vector3& measuredOmega, double deltaT, - boost::optional body_P_sensor, OptionalJacobian<9, 9> F_test, - OptionalJacobian<9, 9> G_test) { - - Vector3 correctedAcc, correctedOmega; - correctMeasurementsByBiasAndSensorPose(measuredAcc, measuredOmega, - correctedAcc, correctedOmega, body_P_sensor); - - const Vector3 integratedOmega = correctedOmega * deltaT; // rotation vector describing rotation increment computed from the current rotation rate measurement - Matrix3 D_Rincr_integratedOmega; // Right jacobian computed at theta_incr - const Rot3 Rincr = Rot3::Expmap(integratedOmega, D_Rincr_integratedOmega); // rotation increment computed from the current rotation rate measurement - - // Update Jacobians - updatePreintegratedJacobians(correctedAcc, D_Rincr_integratedOmega, Rincr, deltaT); - +void PreintegratedImuMeasurements::integrateMeasurement( + const Vector3& measuredAcc, const Vector3& measuredOmega, double dt) { // Update preintegrated measurements (also get Jacobian) - const Matrix3 R_i = deltaRij(); // store this, which is useful to compute G_test - Matrix9 F; // overall Jacobian wrt preintegrated measurements (df/dx) - updatePreintegratedMeasurements(correctedAcc, Rincr, deltaT, F); + Matrix9 A; // overall Jacobian wrt preintegrated measurements (df/dx) + Matrix93 B, C; + PreintegrationBase::integrateMeasurement(measuredAcc, measuredOmega, dt, &A, &B, &C); // first order covariance propagation: - // as in [2] we consider a first order propagation that can be seen as a prediction phase in an EKF framework - /* ----------------------------------------------------------------------------------------------------------------------- */ - // preintMeasCov = F * preintMeasCov * F.transpose() + G * (1/deltaT) * measurementCovariance * G.transpose(); - // NOTE 1: (1/deltaT) allows to pass from continuous time noise to discrete time noise - // measurementCovariance_discrete = measurementCovariance_contTime * (1/deltaT) - // NOTE 2: the computation of G * (1/deltaT) * measurementCovariance * G.transpose() is done block-wise, - // as G and measurementCovariance are block-diagonal matrices - preintMeasCov_ = F * preintMeasCov_ * F.transpose(); - preintMeasCov_.block<3, 3>(0, 0) += integrationCovariance() * deltaT; - preintMeasCov_.block<3, 3>(3, 3) += R_i * accelerometerCovariance() - * R_i.transpose() * deltaT; - preintMeasCov_.block<3, 3>(6, 6) += D_Rincr_integratedOmega - * gyroscopeCovariance() * D_Rincr_integratedOmega.transpose() * deltaT; + // as in [2] we consider a first order propagation that can be seen as a + // prediction phase in EKF - Matrix3 F_pos_noiseacc; - if (use2ndOrderIntegration()) { - F_pos_noiseacc = 0.5 * R_i * deltaT * deltaT; - preintMeasCov_.block<3, 3>(0, 0) += (1 / deltaT) * F_pos_noiseacc - * accelerometerCovariance() * F_pos_noiseacc.transpose(); - Matrix3 temp = F_pos_noiseacc * accelerometerCovariance() * R_i.transpose(); // already includes 1/deltaT - preintMeasCov_.block<3, 3>(0, 3) += temp; - preintMeasCov_.block<3, 3>(3, 0) += temp.transpose(); - } + // propagate uncertainty + // TODO(frank): use noiseModel routine so we can have arbitrary noise models. + const Matrix3& aCov = p().accelerometerCovariance; + const Matrix3& wCov = p().gyroscopeCovariance; + const Matrix3& iCov = p().integrationCovariance; - // F_test and G_test are given as output for testing purposes and are not needed by the factor - if (F_test) { // This in only for testing - (*F_test) << F; - } - if (G_test) { // This in only for testing & documentation, while the actual computation is done block-wise - if (!use2ndOrderIntegration()) - F_pos_noiseacc = Z_3x3; + // (1/dt) allows to pass from continuous time noise to discrete time noise + preintMeasCov_ = A * preintMeasCov_ * A.transpose(); + preintMeasCov_.noalias() += B * (aCov / dt) * B.transpose(); + preintMeasCov_.noalias() += C * (wCov / dt) * C.transpose(); - // intNoise accNoise omegaNoise - (*G_test) << I_3x3 * deltaT, F_pos_noiseacc, Z_3x3, // pos - Z_3x3, R_i * deltaT, Z_3x3, // vel - Z_3x3, Z_3x3, D_Rincr_integratedOmega * deltaT; // angle - } + // NOTE(frank): (Gi*dt)*(C/dt)*(Gi'*dt) + static const Matrix93 Gi = (Matrix93() << Z_3x3, I_3x3, Z_3x3).finished(); + preintMeasCov_.noalias() += Gi * (iCov * dt) * Gi.transpose(); } +//------------------------------------------------------------------------------ +#ifdef GTSAM_ALLOW_DEPRECATED_SINCE_V4 +PreintegratedImuMeasurements::PreintegratedImuMeasurements( + const imuBias::ConstantBias& biasHat, const Matrix3& measuredAccCovariance, + const Matrix3& measuredOmegaCovariance, + const Matrix3& integrationErrorCovariance, bool use2ndOrderIntegration) { + if (!use2ndOrderIntegration) + throw("PreintegratedImuMeasurements no longer supports first-order integration: it incorrectly compensated for gravity"); + biasHat_ = biasHat; + boost::shared_ptr p = Params::MakeSharedD(); + p->gyroscopeCovariance = measuredOmegaCovariance; + p->accelerometerCovariance = measuredAccCovariance; + p->integrationCovariance = integrationErrorCovariance; + p_ = p; + resetIntegration(); +} + +void PreintegratedImuMeasurements::integrateMeasurement( + const Vector3& measuredAcc, const Vector3& measuredOmega, double deltaT, + boost::optional body_P_sensor) { + // modify parameters to accommodate deprecated method:-( + p_->body_P_sensor = body_P_sensor; + integrateMeasurement(measuredAcc, measuredOmega, deltaT); +} +#endif + //------------------------------------------------------------------------------ // ImuFactor methods -//------------------------------------------------------------------------------ -ImuFactor::ImuFactor() : - ImuFactorBase(), _PIM_(imuBias::ConstantBias(), Z_3x3, Z_3x3, Z_3x3) { -} - //------------------------------------------------------------------------------ ImuFactor::ImuFactor(Key pose_i, Key vel_i, Key pose_j, Key vel_j, Key bias, - const PreintegratedMeasurements& preintegratedMeasurements, - const Vector3& gravity, const Vector3& omegaCoriolis, - boost::optional body_P_sensor, const bool use2ndOrderCoriolis) : - Base( - noiseModel::Gaussian::Covariance( - preintegratedMeasurements.preintMeasCov_), pose_i, vel_i, pose_j, - vel_j, bias), ImuFactorBase(gravity, omegaCoriolis, body_P_sensor, - use2ndOrderCoriolis), _PIM_(preintegratedMeasurements) { + const PreintegratedImuMeasurements& pim) : + Base(noiseModel::Gaussian::Covariance(pim.preintMeasCov_), pose_i, vel_i, + pose_j, vel_j, bias), _PIM_(pim) { } //------------------------------------------------------------------------------ -gtsam::NonlinearFactor::shared_ptr ImuFactor::clone() const { - return boost::static_pointer_cast( - gtsam::NonlinearFactor::shared_ptr(new This(*this))); +NonlinearFactor::shared_ptr ImuFactor::clone() const { + return boost::static_pointer_cast( + NonlinearFactor::shared_ptr(new This(*this))); +} + +//------------------------------------------------------------------------------ +std::ostream& operator<<(std::ostream& os, const ImuFactor& f) { + os << " preintegrated measurements:\n" << f._PIM_; + ; + // Print standard deviations on covariance only + os << " noise model sigmas: " << f.noiseModel_->sigmas().transpose(); + return os; } //------------------------------------------------------------------------------ @@ -152,17 +133,15 @@ void ImuFactor::print(const string& s, const KeyFormatter& keyFormatter) const { << keyFormatter(this->key2()) << "," << keyFormatter(this->key3()) << "," << keyFormatter(this->key4()) << "," << keyFormatter(this->key5()) << ")\n"; - ImuFactorBase::print(""); - _PIM_.print(" preintegrated measurements:"); - // Print standard deviations on covariance only - cout << " noise model sigmas: " << this->noiseModel_->sigmas().transpose() << endl; + cout << *this << endl; } //------------------------------------------------------------------------------ -bool ImuFactor::equals(const NonlinearFactor& expected, double tol) const { - const This *e = dynamic_cast(&expected); - return e != NULL && Base::equals(*e, tol) && _PIM_.equals(e->_PIM_, tol) - && ImuFactorBase::equals(*e, tol); +bool ImuFactor::equals(const NonlinearFactor& other, double tol) const { + const This *e = dynamic_cast(&other); + const bool base = Base::equals(*e, tol); + const bool pim = _PIM_.equals(e->_PIM_, tol); + return e != nullptr && base && pim; } //------------------------------------------------------------------------------ @@ -171,9 +150,86 @@ Vector ImuFactor::evaluateError(const Pose3& pose_i, const Vector3& vel_i, const imuBias::ConstantBias& bias_i, boost::optional H1, boost::optional H2, boost::optional H3, boost::optional H4, boost::optional H5) const { - return _PIM_.computeErrorAndJacobians(pose_i, vel_i, pose_j, vel_j, bias_i, - gravity_, omegaCoriolis_, use2ndOrderCoriolis_, H1, H2, H3, H4, H5); + H1, H2, H3, H4, H5); } -} /// namespace gtsam +//------------------------------------------------------------------------------ +PreintegratedImuMeasurements ImuFactor::Merge( + const PreintegratedImuMeasurements& pim01, + const PreintegratedImuMeasurements& pim12) { + if (!pim01.matchesParamsWith(pim12)) + throw std::domain_error( + "Cannot merge PreintegratedImuMeasurements with different params"); + + if (pim01.params()->body_P_sensor) + throw std::domain_error( + "Cannot merge PreintegratedImuMeasurements with sensor pose yet"); + + // the bias for the merged factor will be the bias from 01 + PreintegratedImuMeasurements pim02 = pim01; + + Matrix9 H1, H2; + pim02.mergeWith(pim12, &H1, &H2); + + pim02.preintMeasCov_ = H1 * pim01.preintMeasCov_ * H1.transpose() + + H2 * pim12.preintMeasCov_ * H2.transpose(); + + return pim02; +} + +//------------------------------------------------------------------------------ +ImuFactor::shared_ptr ImuFactor::Merge(const shared_ptr& f01, + const shared_ptr& f12) { + // IMU bias keys must be the same. + if (f01->key5() != f12->key5()) + throw std::domain_error("ImuFactor::Merge: IMU bias keys must be the same"); + + // expect intermediate pose, velocity keys to matchup. + if (f01->key3() != f12->key1() || f01->key4() != f12->key2()) + throw std::domain_error( + "ImuFactor::Merge: intermediate pose, velocity keys need to match up"); + + // return new factor + auto pim02 = + Merge(f01->preintegratedMeasurements(), f12->preintegratedMeasurements()); + return boost::make_shared(f01->key1(), // P0 + f01->key2(), // V0 + f12->key3(), // P2 + f12->key4(), // V2 + f01->key5(), // B + pim02); +} + +//------------------------------------------------------------------------------ +#ifdef GTSAM_ALLOW_DEPRECATED_SINCE_V4 +ImuFactor::ImuFactor(Key pose_i, Key vel_i, Key pose_j, Key vel_j, Key bias, + const PreintegratedImuMeasurements& pim, const Vector3& n_gravity, + const Vector3& omegaCoriolis, const boost::optional& body_P_sensor, + const bool use2ndOrderCoriolis) : +Base(noiseModel::Gaussian::Covariance(pim.preintMeasCov_), pose_i, vel_i, + pose_j, vel_j, bias), _PIM_(pim) { + boost::shared_ptr p = boost::make_shared< + PreintegratedImuMeasurements::Params>(pim.p()); + p->n_gravity = n_gravity; + p->omegaCoriolis = omegaCoriolis; + p->body_P_sensor = body_P_sensor; + p->use2ndOrderCoriolis = use2ndOrderCoriolis; + _PIM_.p_ = p; +} + +void ImuFactor::Predict(const Pose3& pose_i, const Vector3& vel_i, + Pose3& pose_j, Vector3& vel_j, const imuBias::ConstantBias& bias_i, + PreintegratedImuMeasurements& pim, const Vector3& n_gravity, + const Vector3& omegaCoriolis, const bool use2ndOrderCoriolis) { + // use deprecated predict + PoseVelocityBias pvb = pim.predict(pose_i, vel_i, bias_i, n_gravity, + omegaCoriolis, use2ndOrderCoriolis); + pose_j = pvb.pose; + vel_j = pvb.velocity; +} +#endif +//------------------------------------------------------------------------------ + +} + // namespace gtsam diff --git a/gtsam/navigation/ImuFactor.h b/gtsam/navigation/ImuFactor.h index 50e6c835f..73a2f05d2 100644 --- a/gtsam/navigation/ImuFactor.h +++ b/gtsam/navigation/ImuFactor.h @@ -1,6 +1,6 @@ /* ---------------------------------------------------------------------------- - * GTSAM Copyright 2010, Georgia Tech Research Corporation, + * 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) @@ -24,21 +24,21 @@ /* GTSAM includes */ #include #include -#include #include namespace gtsam { -/** - * - * @addtogroup SLAM - * +/* * If you are using the factor, please cite: - * L. Carlone, Z. Kira, C. Beall, V. Indelman, F. Dellaert, Eliminating conditionally - * independent sets in factor graphs: a unifying perspective based on smart factors, - * Int. Conf. on Robotics and Automation (ICRA), 2014. + * L. Carlone, Z. Kira, C. Beall, V. Indelman, F. Dellaert, "Eliminating + * conditionally independent sets in factor graphs: a unifying perspective based + * on smart factors", Int. Conf. on Robotics and Automation (ICRA), 2014. * - ** REFERENCES: + * C. Forster, L. Carlone, F. Dellaert, D. Scaramuzza, "IMU Preintegration on + * Manifold for Efficient Visual-Inertial Maximum-a-Posteriori Estimation", + * Robotics: Science and Systems (RSS), 2015. + * + * REFERENCES: * [1] G.S. Chirikjian, "Stochastic Models, Information Theory, and Lie Groups", * Volume 2, 2008. * [2] T. Lupton and S.Sukkarieh, "Visual-Inertial-Aided Navigation for @@ -46,103 +46,131 @@ namespace gtsam { * TRO, 28(1):61-76, 2012. * [3] L. Carlone, S. Williams, R. Roberts, "Preintegrated IMU factor: * Computation of the Jacobian Matrices", Tech. Report, 2013. + * [4] C. Forster, L. Carlone, F. Dellaert, D. Scaramuzza, "IMU Preintegration on + * Manifold for Efficient Visual-Inertial Maximum-a-Posteriori Estimation", + * Robotics: Science and Systems (RSS), 2015. */ +/** + * PreintegratedIMUMeasurements accumulates (integrates) the IMU measurements + * (rotation rates and accelerations) and the corresponding covariance matrix. + * The measurements are then used to build the Preintegrated IMU factor. + * Integration is done incrementally (ideally, one integrates the measurement + * as soon as it is received from the IMU) so as to avoid costly integration + * at time of factor construction. + * + * @addtogroup SLAM + */ +class PreintegratedImuMeasurements: public PreintegrationBase { + + friend class ImuFactor; + +protected: + + Matrix9 preintMeasCov_; ///< COVARIANCE OF: [PreintPOSITION PreintVELOCITY PreintROTATION] + ///< (first-order propagation from *measurementCovariance*). + + /// Default constructor for serialization + PreintegratedImuMeasurements() { + preintMeasCov_.setZero(); + } + +public: + + /** + * Constructor, initializes the class with no measurements + * @param bias Current estimate of acceleration and rotation rate biases + * @param p Parameters, typically fixed in a single application + */ + PreintegratedImuMeasurements(const boost::shared_ptr& p, + const imuBias::ConstantBias& biasHat = imuBias::ConstantBias()) : + PreintegrationBase(p, biasHat) { + preintMeasCov_.setZero(); + } + +/** + * Construct preintegrated directly from members: base class and preintMeasCov + * @param base PreintegrationBase instance + * @param preintMeasCov Covariance matrix used in noise model. + */ + PreintegratedImuMeasurements(const PreintegrationBase& base, const Matrix9& preintMeasCov) + : PreintegrationBase(base), + preintMeasCov_(preintMeasCov) { + } + + /// print + void print(const std::string& s = "Preintegrated Measurements:") const; + + /// equals + bool equals(const PreintegratedImuMeasurements& expected, + double tol = 1e-9) const; + + /// Re-initialize PreintegratedIMUMeasurements + void resetIntegration(); + + /** + * Add a single IMU measurement to the preintegration. + * @param measuredAcc Measured acceleration (in body frame, as given by the sensor) + * @param measuredOmega Measured angular velocity (as given by the sensor) + * @param dt Time interval between this and the last IMU measurement + */ + void integrateMeasurement(const Vector3& measuredAcc, + const Vector3& measuredOmega, double dt); + + /// Return pre-integrated measurement covariance + Matrix preintMeasCov() const { return preintMeasCov_; } + +#ifdef GTSAM_ALLOW_DEPRECATED_SINCE_V4 + /// @deprecated constructor + /// NOTE(frank): assumes Z-Down convention, only second order integration supported + PreintegratedImuMeasurements(const imuBias::ConstantBias& biasHat, + const Matrix3& measuredAccCovariance, + const Matrix3& measuredOmegaCovariance, + const Matrix3& integrationErrorCovariance, + bool use2ndOrderIntegration = true); + + /// @deprecated version of integrateMeasurement with body_P_sensor + /// Use parameters instead + void integrateMeasurement(const Vector3& measuredAcc, + const Vector3& measuredOmega, double dt, + boost::optional body_P_sensor); +#endif + +private: + + /// Serialization function + friend class boost::serialization::access; + template + void serialize(ARCHIVE & ar, const unsigned int /*version*/) { + namespace bs = ::boost::serialization; + ar & BOOST_SERIALIZATION_BASE_OBJECT_NVP(PreintegrationBase); + ar & bs::make_nvp("preintMeasCov_", bs::make_array(preintMeasCov_.data(), preintMeasCov_.size())); + } +}; + /** * ImuFactor is a 5-ways factor involving previous state (pose and velocity of * the vehicle at previous time step), current state (pose and velocity at * current time step), and the bias estimate. Following the preintegration * scheme proposed in [2], the ImuFactor includes many IMU measurements, which - * are "summarized" using the PreintegratedMeasurements class. + * are "summarized" using the PreintegratedIMUMeasurements class. * Note that this factor does not model "temporal consistency" of the biases * (which are usually slowly varying quantities), which is up to the caller. * See also CombinedImuFactor for a class that does this for you. + * + * @addtogroup SLAM */ class ImuFactor: public NoiseModelFactor5, public ImuFactorBase { + imuBias::ConstantBias> { public: - /** - * PreintegratedMeasurements accumulates (integrates) the IMU measurements - * (rotation rates and accelerations) and the corresponding covariance matrix. - * The measurements are then used to build the Preintegrated IMU factor. - * Integration is done incrementally (ideally, one integrates the measurement - * as soon as it is received from the IMU) so as to avoid costly integration - * at time of factor construction. - */ - class PreintegratedMeasurements: public PreintegrationBase { - - friend class ImuFactor; - - protected: - - Eigen::Matrix preintMeasCov_; ///< COVARIANCE OF: [PreintPOSITION PreintVELOCITY PreintROTATION] - ///< (first-order propagation from *measurementCovariance*). - - public: - - /** - * Default constructor, initializes the class with no measurements - * @param bias Current estimate of acceleration and rotation rate biases - * @param measuredAccCovariance Covariance matrix of measuredAcc - * @param measuredOmegaCovariance Covariance matrix of measured Angular Rate - * @param integrationErrorCovariance Covariance matrix of integration errors (velocity -> position) - * @param use2ndOrderIntegration Controls the order of integration - * (if false: p(t+1) = p(t) + v(t) deltaT ; if true: p(t+1) = p(t) + v(t) deltaT + 0.5 * acc(t) deltaT^2) - */ - PreintegratedMeasurements(const imuBias::ConstantBias& bias, - const Matrix3& measuredAccCovariance, - const Matrix3& measuredOmegaCovariance, - const Matrix3& integrationErrorCovariance, - const bool use2ndOrderIntegration = false); - - /// print - void print(const std::string& s = "Preintegrated Measurements:") const; - - /// equals - bool equals(const PreintegratedMeasurements& expected, - double tol = 1e-9) const; - - /// Re-initialize PreintegratedMeasurements - void resetIntegration(); - - /** - * Add a single IMU measurement to the preintegration. - * @param measuredAcc Measured acceleration (in body frame, as given by the sensor) - * @param measuredOmega Measured angular velocity (as given by the sensor) - * @param deltaT Time interval between this and the last IMU measurement - * @param body_P_sensor Optional sensor frame (pose of the IMU in the body frame) - * @param Fout, Gout Jacobians used internally (only needed for testing) - */ - void integrateMeasurement(const Vector3& measuredAcc, - const Vector3& measuredOmega, double deltaT, - boost::optional body_P_sensor = boost::none, - OptionalJacobian<9, 9> Fout = boost::none, OptionalJacobian<9, 9> Gout = - boost::none); - - /// methods to access class variables - Matrix preintMeasCov() const { - return preintMeasCov_; - } - - private: - - /// Serialization function - friend class boost::serialization::access; - template - void serialize(ARCHIVE & ar, const unsigned int /*version*/) { - ar & BOOST_SERIALIZATION_BASE_OBJECT_NVP(PreintegrationBase); - ar & BOOST_SERIALIZATION_NVP(preintMeasCov_); - } - }; - private: typedef ImuFactor This; typedef NoiseModelFactor5 Base; - PreintegratedMeasurements _PIM_; + PreintegratedImuMeasurements _PIM_; public: @@ -154,7 +182,7 @@ public: #endif /** Default constructor - only use for serialization */ - ImuFactor(); + ImuFactor() {} /** * Constructor @@ -163,17 +191,9 @@ public: * @param pose_j Current pose key * @param vel_j Current velocity key * @param bias Previous bias key - * @param preintegratedMeasurements Preintegrated IMU measurements - * @param gravity Gravity vector expressed in the global frame - * @param omegaCoriolis Rotation rate of the global frame w.r.t. an inertial frame - * @param body_P_sensor Optional pose of the sensor frame in the body frame - * @param use2ndOrderCoriolis When true, the second-order term is used in the calculation of the Coriolis Effect */ ImuFactor(Key pose_i, Key vel_i, Key pose_j, Key vel_j, Key bias, - const PreintegratedMeasurements& preintegratedMeasurements, - const Vector3& gravity, const Vector3& omegaCoriolis, - boost::optional body_P_sensor = boost::none, - const bool use2ndOrderCoriolis = false); + const PreintegratedImuMeasurements& preintegratedMeasurements); virtual ~ImuFactor() { } @@ -181,18 +201,17 @@ public: /// @return a deep copy of this factor virtual gtsam::NonlinearFactor::shared_ptr clone() const; - /** implement functions needed for Testable */ - - /// print + /// @name Testable + /// @{ + GTSAM_EXPORT friend std::ostream& operator<<(std::ostream& os, const ImuFactor&); virtual void print(const std::string& s, const KeyFormatter& keyFormatter = DefaultKeyFormatter) const; - - /// equals virtual bool equals(const NonlinearFactor& expected, double tol = 1e-9) const; + /// @} /** Access the preintegrated measurements. */ - const PreintegratedMeasurements& preintegratedMeasurements() const { + const PreintegratedImuMeasurements& preintegratedMeasurements() const { return _PIM_; } @@ -206,20 +225,32 @@ public: boost::optional H3 = boost::none, boost::optional H4 = boost::none, boost::optional H5 = boost::none) const; - /** @deprecated The following function has been deprecated, use PreintegrationBase::predict with the same signature instead */ + /// Merge two pre-integrated measurement classes + static PreintegratedImuMeasurements Merge( + const PreintegratedImuMeasurements& pim01, + const PreintegratedImuMeasurements& pim12); + + /// Merge two factors + static shared_ptr Merge(const shared_ptr& f01, const shared_ptr& f12); + +#ifdef GTSAM_ALLOW_DEPRECATED_SINCE_V4 + /// @deprecated typename + typedef PreintegratedImuMeasurements PreintegratedMeasurements; + + /// @deprecated constructor, in the new one gravity, coriolis settings are in PreintegrationParams + ImuFactor(Key pose_i, Key vel_i, Key pose_j, Key vel_j, Key bias, + const PreintegratedMeasurements& preintegratedMeasurements, + const Vector3& n_gravity, const Vector3& omegaCoriolis, + const boost::optional& body_P_sensor = boost::none, + const bool use2ndOrderCoriolis = false); + + /// @deprecated use PreintegrationBase::predict, + /// in the new one gravity, coriolis settings are in PreintegrationParams static void Predict(const Pose3& pose_i, const Vector3& vel_i, Pose3& pose_j, Vector3& vel_j, const imuBias::ConstantBias& bias_i, - const PreintegratedMeasurements& PIM, const Vector3& gravity, - const Vector3& omegaCoriolis, const bool use2ndOrderCoriolis = false, - boost::optional deltaPij_biascorrected_out = boost::none, - boost::optional deltaVij_biascorrected_out = boost::none) { - PoseVelocityBias PVB( - PIM.predict(pose_i, vel_i, bias_i, gravity, omegaCoriolis, - use2ndOrderCoriolis, deltaPij_biascorrected_out, - deltaVij_biascorrected_out)); - pose_j = PVB.pose; - vel_j = PVB.velocity; - } + PreintegratedMeasurements& pim, const Vector3& n_gravity, + const Vector3& omegaCoriolis, const bool use2ndOrderCoriolis = false); +#endif private: @@ -230,13 +261,14 @@ private: ar & boost::serialization::make_nvp("NoiseModelFactor5", boost::serialization::base_object(*this)); ar & BOOST_SERIALIZATION_NVP(_PIM_); - ar & BOOST_SERIALIZATION_NVP(gravity_); - ar & BOOST_SERIALIZATION_NVP(omegaCoriolis_); - ar & BOOST_SERIALIZATION_NVP(body_P_sensor_); } }; // class ImuFactor -typedef ImuFactor::PreintegratedMeasurements ImuFactorPreintegratedMeasurements; +template <> +struct traits : public Testable {}; + +template <> +struct traits : public Testable {}; } /// namespace gtsam diff --git a/gtsam/navigation/ImuFactorBase.h b/gtsam/navigation/ImuFactorBase.h deleted file mode 100644 index 1e4e51220..000000000 --- a/gtsam/navigation/ImuFactorBase.h +++ /dev/null @@ -1,94 +0,0 @@ -/* ---------------------------------------------------------------------------- - - * 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 PreintegrationBase.h - * @author Luca Carlone - * @author Stephen Williams - * @author Richard Roberts - * @author Vadim Indelman - * @author David Jensen - * @author Frank Dellaert - **/ - -#pragma once - -/* GTSAM includes */ -#include -#include - -namespace gtsam { - -class ImuFactorBase { - -protected: - - Vector3 gravity_; - Vector3 omegaCoriolis_; - boost::optional body_P_sensor_; ///< The pose of the sensor in the body frame - bool use2ndOrderCoriolis_; ///< Controls whether higher order terms are included when calculating the Coriolis Effect - -public: - - /** Default constructor - only use for serialization */ - ImuFactorBase() : - gravity_(Vector3(0.0, 0.0, 9.81)), omegaCoriolis_(Vector3(0.0, 0.0, 0.0)), body_P_sensor_( - boost::none), use2ndOrderCoriolis_(false) { - } - - /** - * Default constructor, stores basic quantities required by the Imu factors - * @param gravity Gravity vector expressed in the global frame - * @param omegaCoriolis Rotation rate of the global frame w.r.t. an inertial frame - * @param body_P_sensor Optional pose of the sensor frame in the body frame - * @param use2ndOrderCoriolis When true, the second-order term is used in the calculation of the Coriolis Effect - */ - ImuFactorBase(const Vector3& gravity, const Vector3& omegaCoriolis, - boost::optional body_P_sensor = boost::none, - const bool use2ndOrderCoriolis = false) : - gravity_(gravity), omegaCoriolis_(omegaCoriolis), body_P_sensor_( - body_P_sensor), use2ndOrderCoriolis_(use2ndOrderCoriolis) { - } - - /// Methods to access class variables - const Vector3& gravity() const { - return gravity_; - } - const Vector3& omegaCoriolis() const { - return omegaCoriolis_; - } - - /// Needed for testable - //------------------------------------------------------------------------------ - void print(const std::string& /*s*/) const { - std::cout << " gravity: [ " << gravity_.transpose() << " ]" << std::endl; - std::cout << " omegaCoriolis: [ " << omegaCoriolis_.transpose() << " ]" - << std::endl; - std::cout << " use2ndOrderCoriolis: [ " << use2ndOrderCoriolis_ << " ]" - << std::endl; - if (this->body_P_sensor_) - this->body_P_sensor_->print(" sensor pose in body frame: "); - } - - /// Needed for testable - //------------------------------------------------------------------------------ - bool equals(const ImuFactorBase& expected, double tol) const { - return equal_with_abs_tol(gravity_, expected.gravity_, tol) - && equal_with_abs_tol(omegaCoriolis_, expected.omegaCoriolis_, tol) - && (use2ndOrderCoriolis_ == expected.use2ndOrderCoriolis_) - && ((!body_P_sensor_ && !expected.body_P_sensor_) - || (body_P_sensor_ && expected.body_P_sensor_ - && body_P_sensor_->equals(*expected.body_P_sensor_))); - } - -}; - -} /// namespace gtsam diff --git a/gtsam/navigation/MagFactor.h b/gtsam/navigation/MagFactor.h index f70bec8c6..fc1e69190 100644 --- a/gtsam/navigation/MagFactor.h +++ b/gtsam/navigation/MagFactor.h @@ -60,7 +60,7 @@ public: static Point3 unrotate(const Rot2& R, const Point3& p, boost::optional HR = boost::none) { - Point3 q = Rot3::yaw(R.theta()).unrotate(p, HR, boost::none); + Point3 q = Rot3::Yaw(R.theta()).unrotate(p, HR, boost::none); if (HR) { // assign to temporary first to avoid error in Win-Debug mode Matrix H = HR->col(2); diff --git a/gtsam/navigation/NavState.cpp b/gtsam/navigation/NavState.cpp new file mode 100644 index 000000000..860eaa85c --- /dev/null +++ b/gtsam/navigation/NavState.cpp @@ -0,0 +1,364 @@ +/* ---------------------------------------------------------------------------- + + * 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 NavState.h + * @brief Navigation state composing of attitude, position, and velocity + * @author Frank Dellaert + * @date July 2015 + **/ + +#include + +using namespace std; + +namespace gtsam { + +#define TIE(R,t,v,x) const Rot3& R = (x).R_;const Point3& t = (x).t_;const Velocity3& v = (x).v_; + +//------------------------------------------------------------------------------ +NavState NavState::FromPoseVelocity(const Pose3& pose, const Vector3& vel, + OptionalJacobian<9, 6> H1, OptionalJacobian<9, 3> H2) { + if (H1) + *H1 << I_3x3, Z_3x3, Z_3x3, I_3x3, Z_3x3, Z_3x3; + if (H2) + *H2 << Z_3x3, Z_3x3, pose.rotation().transpose(); + return NavState(pose, vel); +} + +//------------------------------------------------------------------------------ +const Rot3& NavState::attitude(OptionalJacobian<3, 9> H) const { + if (H) + *H << I_3x3, Z_3x3, Z_3x3; + return R_; +} + +//------------------------------------------------------------------------------ +const Point3& NavState::position(OptionalJacobian<3, 9> H) const { + if (H) + *H << Z_3x3, R(), Z_3x3; + return t_; +} + +//------------------------------------------------------------------------------ +const Vector3& NavState::velocity(OptionalJacobian<3, 9> H) const { + if (H) + *H << Z_3x3, Z_3x3, R(); + return v_; +} + +//------------------------------------------------------------------------------ +Vector3 NavState::bodyVelocity(OptionalJacobian<3, 9> H) const { + const Rot3& nRb = R_; + const Vector3& n_v = v_; + Matrix3 D_bv_nRb; + Vector3 b_v = nRb.unrotate(n_v, H ? &D_bv_nRb : 0); + if (H) + *H << D_bv_nRb, Z_3x3, I_3x3; + return b_v; +} + +//------------------------------------------------------------------------------ +Matrix7 NavState::matrix() const { + Matrix3 R = this->R(); + Matrix7 T; + T << R, Z_3x3, t(), Z_3x3, R, v(), Vector6::Zero().transpose(), 1.0; + return T; +} + +//------------------------------------------------------------------------------ +ostream& operator<<(ostream& os, const NavState& state) { + os << "R:" << state.attitude(); + os << "p:" << state.position() << endl; + os << "v:" << Point3(state.velocity()) << endl; + return os; +} + +//------------------------------------------------------------------------------ +void NavState::print(const string& s) const { + cout << s << *this << endl; +} + +//------------------------------------------------------------------------------ +bool NavState::equals(const NavState& other, double tol) const { + return R_.equals(other.R_, tol) && t_.equals(other.t_, tol) + && equal_with_abs_tol(v_, other.v_, tol); +} + +//------------------------------------------------------------------------------ +NavState NavState::inverse() const { + TIE(nRb, n_t, n_v, *this); + const Rot3 bRn = nRb.inverse(); + return NavState(bRn, -(bRn * n_t), -(bRn * n_v)); +} + +//------------------------------------------------------------------------------ +NavState NavState::operator*(const NavState& bTc) const { + TIE(nRb, n_t, n_v, *this); + TIE(bRc, b_t, b_v, bTc); + return NavState(nRb * bRc, nRb * b_t + n_t, nRb * b_v + n_v); +} + +//------------------------------------------------------------------------------ +NavState::PositionAndVelocity // +NavState::operator*(const PositionAndVelocity& b_tv) const { + TIE(nRb, n_t, n_v, *this); + const Point3& b_t = b_tv.first; + const Velocity3& b_v = b_tv.second; + return PositionAndVelocity(nRb * b_t + n_t, nRb * b_v + n_v); +} + +//------------------------------------------------------------------------------ +Point3 NavState::operator*(const Point3& b_t) const { + return Point3(R_ * b_t + t_); +} + +//------------------------------------------------------------------------------ +Velocity3 NavState::operator*(const Velocity3& b_v) const { + return Velocity3(R_ * b_v + v_); +} + +//------------------------------------------------------------------------------ +NavState NavState::ChartAtOrigin::Retract(const Vector9& xi, + OptionalJacobian<9, 9> H) { + Matrix3 D_R_xi; + const Rot3 R = Rot3::Expmap(dR(xi), H ? &D_R_xi : 0); + const Point3 p = Point3(dP(xi)); + const Vector v = dV(xi); + const NavState result(R, p, v); + if (H) { + *H << D_R_xi, Z_3x3, Z_3x3, // + Z_3x3, R.transpose(), Z_3x3, // + Z_3x3, Z_3x3, R.transpose(); + } + return result; +} + +//------------------------------------------------------------------------------ +Vector9 NavState::ChartAtOrigin::Local(const NavState& x, + OptionalJacobian<9, 9> H) { + Vector9 xi; + Matrix3 D_xi_R; + xi << Rot3::Logmap(x.R_, H ? &D_xi_R : 0), x.t(), x.v(); + if (H) { + *H << D_xi_R, Z_3x3, Z_3x3, // + Z_3x3, x.R(), Z_3x3, // + Z_3x3, Z_3x3, x.R(); + } + return xi; +} + +//------------------------------------------------------------------------------ +NavState NavState::Expmap(const Vector9& xi, OptionalJacobian<9, 9> H) { + if (H) + throw runtime_error("NavState::Expmap derivative not implemented yet"); + + Eigen::Block n_omega_nb = dR(xi); + Eigen::Block v = dP(xi); + Eigen::Block a = dV(xi); + + // NOTE(frank): See Pose3::Expmap + Rot3 nRb = Rot3::Expmap(n_omega_nb); + double theta2 = n_omega_nb.dot(n_omega_nb); + if (theta2 > numeric_limits::epsilon()) { + // Expmap implements a "screw" motion in the direction of n_omega_nb + Vector3 n_t_parallel = n_omega_nb * n_omega_nb.dot(v); // component along rotation axis + Vector3 omega_cross_v = n_omega_nb.cross(v); // points towards axis + Point3 n_t = Point3(omega_cross_v - nRb * omega_cross_v + n_t_parallel) + / theta2; + Vector3 n_v_parallel = n_omega_nb * n_omega_nb.dot(a); // component along rotation axis + Vector3 omega_cross_a = n_omega_nb.cross(a); // points towards axis + Vector3 n_v = (omega_cross_a - nRb * omega_cross_a + n_v_parallel) / theta2; + return NavState(nRb, n_t, n_v); + } else { + return NavState(nRb, Point3(v), a); + } +} + +//------------------------------------------------------------------------------ +Vector9 NavState::Logmap(const NavState& nTb, OptionalJacobian<9, 9> H) { + if (H) + throw runtime_error("NavState::Logmap derivative not implemented yet"); + + TIE(nRb, n_p, n_v, nTb); + Vector3 n_t = n_p.vector(); + + // NOTE(frank): See Pose3::Logmap + Vector9 xi; + Vector3 n_omega_nb = Rot3::Logmap(nRb); + double theta = n_omega_nb.norm(); + if (theta * theta <= numeric_limits::epsilon()) { + xi << n_omega_nb, n_t, n_v; + } else { + Matrix3 W = skewSymmetric(n_omega_nb / theta); + // Formula from Agrawal06iros, equation (14) + // simplified with Mathematica, and multiplying in n_t to avoid matrix math + double factor = (1 - theta / (2. * tan(0.5 * theta))); + Vector3 n_x = W * n_t; + Vector3 v = n_t - (0.5 * theta) * n_x + factor * (W * n_x); + Vector3 n_y = W * n_v; + Vector3 a = n_v - (0.5 * theta) * n_y + factor * (W * n_y); + xi << n_omega_nb, v, a; + } + return xi; +} + +//------------------------------------------------------------------------------ +Matrix9 NavState::AdjointMap() const { + // NOTE(frank): See Pose3::AdjointMap + const Matrix3 nRb = R(); + Matrix3 pAr = skewSymmetric(t()) * nRb; + Matrix3 vAr = skewSymmetric(v()) * nRb; + Matrix9 adj; + // nR/bR nR/bP nR/bV nP/bR nP/bP nP/bV nV/bR nV/bP nV/bV + adj << nRb, Z_3x3, Z_3x3, pAr, nRb, Z_3x3, vAr, Z_3x3, nRb; + return adj; +} + +//------------------------------------------------------------------------------ +Matrix7 NavState::wedge(const Vector9& xi) { + const Matrix3 Omega = skewSymmetric(dR(xi)); + Matrix7 T; + T << Omega, Z_3x3, dP(xi), Z_3x3, Omega, dV(xi), Vector6::Zero().transpose(), 1.0; + return T; +} + +//------------------------------------------------------------------------------ +// sugar for derivative blocks +#define D_R_R(H) (H)->block<3,3>(0,0) +#define D_R_t(H) (H)->block<3,3>(0,3) +#define D_R_v(H) (H)->block<3,3>(0,6) +#define D_t_R(H) (H)->block<3,3>(3,0) +#define D_t_t(H) (H)->block<3,3>(3,3) +#define D_t_v(H) (H)->block<3,3>(3,6) +#define D_v_R(H) (H)->block<3,3>(6,0) +#define D_v_t(H) (H)->block<3,3>(6,3) +#define D_v_v(H) (H)->block<3,3>(6,6) + +//------------------------------------------------------------------------------ +NavState NavState::update(const Vector3& b_acceleration, const Vector3& b_omega, + const double dt, OptionalJacobian<9, 9> F, OptionalJacobian<9, 3> G1, + OptionalJacobian<9, 3> G2) const { + + Vector9 xi; + Matrix39 D_xiP_state; + Vector3 b_v = bodyVelocity(F ? &D_xiP_state : 0); + double dt22 = 0.5 * dt * dt; + + // Integrate on tangent space. TODO(frank): coriolis? + dR(xi) << dt * b_omega; + dP(xi) << dt * b_v + dt22 * b_acceleration; + dV(xi) << dt * b_acceleration; + + // Bring back to manifold + Matrix9 D_newState_xi; + NavState newState = retract(xi, F, G1 || G2 ? &D_newState_xi : 0); + + // Derivative wrt state is computed by retract directly + // However, as dP(xi) also depends on state, we need to add that contribution + if (F) { + F->middleRows<3>(3) += dt * D_t_t(F) * D_xiP_state; + } + // derivative wrt acceleration + if (G1) { + // D_newState_dPxi = D_newState_xi.middleCols<3>(3) + // D_dPxi_acc = dt22 * I_3x3 + // D_newState_dVxi = D_newState_xi.rightCols<3>() + // D_dVxi_acc = dt * I_3x3 + // *G2 = D_newState_acc = D_newState_dPxi * D_dPxi_acc + D_newState_dVxi * D_dVxi_acc + *G1 = D_newState_xi.middleCols<3>(3) * dt22 + + D_newState_xi.rightCols<3>() * dt; + } + // derivative wrt omega + if (G2) { + // D_newState_dRxi = D_newState_xi.leftCols<3>() + // D_dRxi_omega = dt * I_3x3 + // *G1 = D_newState_omega = D_newState_dRxi * D_dRxi_omega + *G2 = D_newState_xi.leftCols<3>() * dt; + } + return newState; +} + +//------------------------------------------------------------------------------ +Vector9 NavState::coriolis(double dt, const Vector3& omega, bool secondOrder, + OptionalJacobian<9, 9> H) const { + TIE(nRb, n_t, n_v, *this); + const double dt2 = dt * dt; + const Vector3 omega_cross_vel = omega.cross(n_v); + + Vector9 xi; + Matrix3 D_dP_R; + dR(xi) << nRb.unrotate((-dt) * omega, H ? &D_dP_R : 0); + dP(xi) << ((-dt2) * omega_cross_vel); // NOTE(luca): we got rid of the 2 wrt INS paper + dV(xi) << ((-2.0 * dt) * omega_cross_vel); + if (secondOrder) { + const Vector3 omega_cross2_t = omega.cross(omega.cross(n_t.vector())); + dP(xi) -= (0.5 * dt2) * omega_cross2_t; + dV(xi) -= dt * omega_cross2_t; + } + if (H) { + H->setZero(); + const Matrix3 Omega = skewSymmetric(omega); + const Matrix3 D_cross_state = Omega * R(); + H->setZero(); + D_R_R(H) << D_dP_R; + D_t_v(H) << (-dt2) * D_cross_state; + D_v_v(H) << (-2.0 * dt) * D_cross_state; + if (secondOrder) { + const Matrix3 D_cross2_state = Omega * D_cross_state; + D_t_t(H) -= (0.5 * dt2) * D_cross2_state; + D_v_t(H) -= dt * D_cross2_state; + } + } + return xi; +} + +//------------------------------------------------------------------------------ +Vector9 NavState::correctPIM(const Vector9& pim, double dt, + const Vector3& n_gravity, const boost::optional& omegaCoriolis, + bool use2ndOrderCoriolis, OptionalJacobian<9, 9> H1, + OptionalJacobian<9, 9> H2) const { + const Rot3& nRb = R_; + const Velocity3& n_v = v_; // derivative is Ri ! + const double dt22 = 0.5 * dt * dt; + + Vector9 xi; + Matrix3 D_dP_Ri1, D_dP_Ri2, D_dP_nv, D_dV_Ri; + dR(xi) = dR(pim); + dP(xi) = dP(pim) + + dt * nRb.unrotate(n_v, H1 ? &D_dP_Ri1 : 0, H2 ? &D_dP_nv : 0) + + dt22 * nRb.unrotate(n_gravity, H1 ? &D_dP_Ri2 : 0); + dV(xi) = dV(pim) + dt * nRb.unrotate(n_gravity, H1 ? &D_dV_Ri : 0); + + if (omegaCoriolis) { + xi += coriolis(dt, *omegaCoriolis, use2ndOrderCoriolis, H1); + } + + if (H1 || H2) { + Matrix3 Ri = nRb.matrix(); + + if (H1) { + if (!omegaCoriolis) + H1->setZero(); // if coriolis H1 is already initialized + D_t_R(H1) += dt * D_dP_Ri1 + dt22 * D_dP_Ri2; + D_t_v(H1) += dt * D_dP_nv * Ri; + D_v_R(H1) += dt * D_dV_Ri; + } + if (H2) { + H2->setIdentity(); + } + } + + return xi; +} +//------------------------------------------------------------------------------ + +}/// namespace gtsam diff --git a/gtsam/navigation/NavState.h b/gtsam/navigation/NavState.h new file mode 100644 index 000000000..4c8b50776 --- /dev/null +++ b/gtsam/navigation/NavState.h @@ -0,0 +1,253 @@ +/* ---------------------------------------------------------------------------- + + * 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 NavState.h + * @brief Navigation state composing of attitude, position, and velocity + * @author Frank Dellaert + * @date July 2015 + **/ + +#pragma once + +#include +#include +#include + +namespace gtsam { + +/// Velocity is currently typedef'd to Vector3 +typedef Vector3 Velocity3; + +/** + * Navigation state: Pose (rotation, translation) + velocity + * Implements semi-direct Lie group product of SO(3) and R^6, where R^6 is position/velocity + */ +class NavState: public LieGroup { +private: + + // TODO(frank): + // - should we rename t_ to p_? if not, we should rename dP do dT + Rot3 R_; ///< Rotation nRb, rotates points/velocities in body to points/velocities in nav + Point3 t_; ///< position n_t, in nav frame + Velocity3 v_; ///< velocity n_v in nav frame + +public: + + typedef std::pair PositionAndVelocity; + + /// @name Constructors + /// @{ + + /// Default constructor + NavState() : + v_(Vector3::Zero()) { + } + /// Construct from attitude, position, velocity + NavState(const Rot3& R, const Point3& t, const Velocity3& v) : + R_(R), t_(t), v_(v) { + } + /// Construct from pose and velocity + NavState(const Pose3& pose, const Velocity3& v) : + R_(pose.rotation()), t_(pose.translation()), v_(v) { + } + /// Construct from Matrix group representation (no checking) + NavState(const Matrix7& T) : + R_(T.block<3, 3>(0, 0)), t_(T.block<3, 1>(0, 6)), v_(T.block<3, 1>(3, 6)) { + } + /// Construct from SO(3) and R^6 + NavState(const Matrix3& R, const Vector9 tv) : + R_(R), t_(tv.head<3>()), v_(tv.tail<3>()) { + } + /// Named constructor with derivatives + static NavState FromPoseVelocity(const Pose3& pose, const Vector3& vel, + OptionalJacobian<9, 6> H1, OptionalJacobian<9, 3> H2); + + /// @} + /// @name Component Access + /// @{ + + const Rot3& attitude(OptionalJacobian<3, 9> H = boost::none) const; + const Point3& position(OptionalJacobian<3, 9> H = boost::none) const; + const Velocity3& velocity(OptionalJacobian<3, 9> H = boost::none) const; + + const Pose3 pose() const { + return Pose3(attitude(), position()); + } + + /// @} + /// @name Derived quantities + /// @{ + + /// Return rotation matrix. Induces computation in quaternion mode + Matrix3 R() const { + return R_.matrix(); + } + /// Return quaternion. Induces computation in matrix mode + Quaternion quaternion() const { + return R_.toQuaternion(); + } + /// Return position as Vector3 + Vector3 t() const { + return t_.vector(); + } + /// Return velocity as Vector3. Computation-free. + const Vector3& v() const { + return v_; + } + // Return velocity in body frame + Velocity3 bodyVelocity(OptionalJacobian<3, 9> H = boost::none) const; + + /// Return matrix group representation, in MATLAB notation: + /// nTb = [nRb 0 n_t; 0 nRb n_v; 0 0 1] + /// With this embedding in GL(3), matrix product agrees with compose + Matrix7 matrix() const; + + /// @} + /// @name Testable + /// @{ + + /// Output stream operator + GTSAM_EXPORT friend std::ostream &operator<<(std::ostream &os, const NavState& state); + + /// print + void print(const std::string& s = "") const; + + /// equals + bool equals(const NavState& other, double tol = 1e-8) const; + + /// @} + /// @name Group + /// @{ + + /// identity for group operation + static NavState identity() { + return NavState(); + } + + /// inverse transformation with derivatives + NavState inverse() const; + + /// Group compose is the semi-direct product as specified below: + /// nTc = nTb * bTc = (nRb * bRc, nRb * b_t + n_t, nRb * b_v + n_v) + NavState operator*(const NavState& bTc) const; + + /// Native group action is on position/velocity pairs *in the body frame* as follows: + /// nTb * (b_t,b_v) = (nRb * b_t + n_t, nRb * b_v + n_v) + PositionAndVelocity operator*(const PositionAndVelocity& b_tv) const; + + /// Act on position alone, n_t = nRb * b_t + n_t + Point3 operator*(const Point3& b_t) const; + + /// Act on velocity alone, n_v = nRb * b_v + n_v + Velocity3 operator*(const Velocity3& b_v) const; + + /// @} + /// @name Manifold + /// @{ + + // Tangent space sugar. + // TODO(frank): move to private navstate namespace in cpp + static Eigen::Block dR(Vector9& v) { + return v.segment<3>(0); + } + static Eigen::Block dP(Vector9& v) { + return v.segment<3>(3); + } + static Eigen::Block dV(Vector9& v) { + return v.segment<3>(6); + } + static Eigen::Block dR(const Vector9& v) { + return v.segment<3>(0); + } + static Eigen::Block dP(const Vector9& v) { + return v.segment<3>(3); + } + static Eigen::Block dV(const Vector9& v) { + return v.segment<3>(6); + } + + // Chart at origin, constructs components separately (as opposed to Expmap) + struct ChartAtOrigin { + static NavState Retract(const Vector9& xi, // + OptionalJacobian<9, 9> H = boost::none); + static Vector9 Local(const NavState& x, // + OptionalJacobian<9, 9> H = boost::none); + }; + + /// @} + /// @name Lie Group + /// @{ + + /// Exponential map at identity - create a NavState from canonical coordinates + static NavState Expmap(const Vector9& xi, // + OptionalJacobian<9, 9> H = boost::none); + + /// Log map at identity - return the canonical coordinates for this NavState + static Vector9 Logmap(const NavState& p, // + OptionalJacobian<9, 9> H = boost::none); + + /// Calculate Adjoint map, a 9x9 matrix that takes a tangent vector in the body frame, and transforms + /// it to a tangent vector at identity, such that Exmap(AdjointMap()*xi) = (*this) * Exmpap(xi); + Matrix9 AdjointMap() const; + + /// wedge creates Lie algebra element from tangent vector + static Matrix7 wedge(const Vector9& xi); + + /// @} + /// @name Dynamics + /// @{ + + /// Integrate forward in time given angular velocity and acceleration in body frame + /// Uses second order integration for position, returns derivatives except dt. + NavState update(const Vector3& b_acceleration, const Vector3& b_omega, + const double dt, OptionalJacobian<9, 9> F, OptionalJacobian<9, 3> G1, + OptionalJacobian<9, 3> G2) const; + + /// Compute tangent space contribution due to Coriolis forces + Vector9 coriolis(double dt, const Vector3& omega, bool secondOrder = false, + OptionalJacobian<9, 9> H = boost::none) const; + + /// Correct preintegrated tangent vector with our velocity and rotated gravity, + /// taking into account Coriolis forces if omegaCoriolis is given. + Vector9 correctPIM(const Vector9& pim, double dt, const Vector3& n_gravity, + const boost::optional& omegaCoriolis, bool use2ndOrderCoriolis = + false, OptionalJacobian<9, 9> H1 = boost::none, + OptionalJacobian<9, 9> H2 = boost::none) const; + + /// @} + +private: + /// @{ + /// serialization + friend class boost::serialization::access; + template + void serialize(ARCHIVE & ar, const unsigned int /*version*/) { + ar & BOOST_SERIALIZATION_NVP(R_); + ar & BOOST_SERIALIZATION_NVP(t_); + ar & BOOST_SERIALIZATION_NVP(v_); + } + /// @} +}; + +// Specialize NavState traits to use a Retract/Local that agrees with IMUFactors +template<> +struct traits : Testable, internal::LieGroupTraits { +}; + +// Partial specialization of wedge +// TODO: deprecate, make part of traits +template<> +inline Matrix wedge(const Vector& xi) { + return NavState::wedge(xi); +} + +} // namespace gtsam diff --git a/gtsam/navigation/PreintegratedRotation.cpp b/gtsam/navigation/PreintegratedRotation.cpp new file mode 100644 index 000000000..df38df0b8 --- /dev/null +++ b/gtsam/navigation/PreintegratedRotation.cpp @@ -0,0 +1,131 @@ +/* ---------------------------------------------------------------------------- + + * 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 PreintegratedRotation.cpp + * @author Luca Carlone + * @author Stephen Williams + * @author Richard Roberts + * @author Vadim Indelman + * @author David Jensen + * @author Frank Dellaert + **/ + +#include "PreintegratedRotation.h" + +using namespace std; + +namespace gtsam { + +void PreintegratedRotation::Params::print(const string& s) const { + cout << s << endl; + cout << "gyroscopeCovariance:\n[\n" << gyroscopeCovariance << "\n]" << endl; + if (omegaCoriolis) + cout << "omegaCoriolis = (" << omegaCoriolis->transpose() << ")" << endl; + if (body_P_sensor) + body_P_sensor->print("body_P_sensor"); +} + +bool PreintegratedRotation::Params::equals( + const PreintegratedRotation::Params& other, double tol) const { + if (body_P_sensor) { + if (!other.body_P_sensor + || !assert_equal(*body_P_sensor, *other.body_P_sensor, tol)) + return false; + } + if (omegaCoriolis) { + if (!other.omegaCoriolis + || !equal_with_abs_tol(*omegaCoriolis, *other.omegaCoriolis, tol)) + return false; + } + return equal_with_abs_tol(gyroscopeCovariance, other.gyroscopeCovariance, tol); +} + +void PreintegratedRotation::resetIntegration() { + deltaTij_ = 0.0; + deltaRij_ = Rot3(); + delRdelBiasOmega_ = Z_3x3; +} + +void PreintegratedRotation::print(const string& s) const { + cout << s; + cout << " deltaTij [" << deltaTij_ << "]" << endl; + cout << " deltaRij.ypr = (" << deltaRij_.ypr().transpose() << ")" << endl; +} + +bool PreintegratedRotation::equals(const PreintegratedRotation& other, + double tol) const { + return p_->equals(*other.p_,tol) && deltaRij_.equals(other.deltaRij_, tol) + && fabs(deltaTij_ - other.deltaTij_) < tol + && equal_with_abs_tol(delRdelBiasOmega_, other.delRdelBiasOmega_, tol); +} + +Rot3 PreintegratedRotation::incrementalRotation(const Vector3& measuredOmega, + const Vector3& biasHat, double deltaT, + OptionalJacobian<3, 3> D_incrR_integratedOmega) const { + + // First we compensate the measurements for the bias + Vector3 correctedOmega = measuredOmega - biasHat; + + // Then compensate for sensor-body displacement: we express the quantities + // (originally in the IMU frame) into the body frame + if (p_->body_P_sensor) { + Matrix3 body_R_sensor = p_->body_P_sensor->rotation().matrix(); + // rotation rate vector in the body frame + correctedOmega = body_R_sensor * correctedOmega; + } + + // rotation vector describing rotation increment computed from the + // current rotation rate measurement + const Vector3 integratedOmega = correctedOmega * deltaT; + return Rot3::Expmap(integratedOmega, D_incrR_integratedOmega); // expensive !! +} + +void PreintegratedRotation::integrateMeasurement(const Vector3& measuredOmega, + const Vector3& biasHat, double deltaT, + OptionalJacobian<3, 3> optional_D_incrR_integratedOmega, + OptionalJacobian<3, 3> F) { + Matrix3 D_incrR_integratedOmega; + const Rot3 incrR = incrementalRotation(measuredOmega, biasHat, deltaT, + D_incrR_integratedOmega); + + // If asked, pass first derivative as well + if (optional_D_incrR_integratedOmega) { + *optional_D_incrR_integratedOmega << D_incrR_integratedOmega; + } + + // Update deltaTij and rotation + deltaTij_ += deltaT; + deltaRij_ = deltaRij_.compose(incrR, F); + + // Update Jacobian + const Matrix3 incrRt = incrR.transpose(); + delRdelBiasOmega_ = incrRt * delRdelBiasOmega_ + - D_incrR_integratedOmega * deltaT; +} + +Rot3 PreintegratedRotation::biascorrectedDeltaRij(const Vector3& biasOmegaIncr, + OptionalJacobian<3, 3> H) const { + const Vector3 biasInducedOmega = delRdelBiasOmega_ * biasOmegaIncr; + const Rot3 deltaRij_biascorrected = deltaRij_.expmap(biasInducedOmega, + boost::none, H); + if (H) + (*H) *= delRdelBiasOmega_; + return deltaRij_biascorrected; +} + +Vector3 PreintegratedRotation::integrateCoriolis(const Rot3& rot_i) const { + if (!p_->omegaCoriolis) + return Vector3::Zero(); + return rot_i.transpose() * (*p_->omegaCoriolis) * deltaTij_; +} + +} // namespace gtsam diff --git a/gtsam/navigation/PreintegratedRotation.h b/gtsam/navigation/PreintegratedRotation.h index 2379f58af..b170ea863 100644 --- a/gtsam/navigation/PreintegratedRotation.h +++ b/gtsam/navigation/PreintegratedRotation.h @@ -1,6 +1,6 @@ /* ---------------------------------------------------------------------------- - * GTSAM Copyright 2010, Georgia Tech Research Corporation, + * 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) @@ -21,7 +21,8 @@ #pragma once -#include +#include +#include namespace gtsam { @@ -31,124 +32,130 @@ namespace gtsam { * It includes the definitions of the preintegrated rotation. */ class PreintegratedRotation { + public: + /// Parameters for pre-integration: + /// Usage: Create just a single Params and pass a shared pointer to the constructor + struct Params { + Matrix3 gyroscopeCovariance; ///< continuous-time "Covariance" of gyroscope measurements + boost::optional omegaCoriolis; ///< Coriolis constant + boost::optional body_P_sensor; ///< The pose of the sensor in the body frame - Rot3 deltaRij_; ///< Preintegrated relative orientation (in frame i) - double deltaTij_; ///< Time interval from i to j + Params() : gyroscopeCovariance(I_3x3) {} - /// Jacobian of preintegrated rotation w.r.t. angular rate bias - Matrix3 delRdelBiasOmega_; - Matrix3 gyroscopeCovariance_; ///< continuous-time "Covariance" of gyroscope measurements + virtual void print(const std::string& s) const; + virtual bool equals(const Params& other, double tol=1e-9) const; -public: + private: + /** Serialization function */ + friend class boost::serialization::access; + template + void serialize(ARCHIVE & ar, const unsigned int /*version*/) { + namespace bs = ::boost::serialization; + ar & bs::make_nvp("gyroscopeCovariance", bs::make_array(gyroscopeCovariance.data(), gyroscopeCovariance.size())); + ar & BOOST_SERIALIZATION_NVP(omegaCoriolis); + ar & BOOST_SERIALIZATION_NVP(body_P_sensor); + } + }; - /** - * Default constructor, initializes the variables in the base class - */ - PreintegratedRotation(const Matrix3& measuredOmegaCovariance) : - deltaRij_(Rot3()), deltaTij_(0.0), delRdelBiasOmega_(Z_3x3), gyroscopeCovariance_( - measuredOmegaCovariance) { + protected: + /// Parameters + boost::shared_ptr p_; + + double deltaTij_; ///< Time interval from i to j + Rot3 deltaRij_; ///< Preintegrated relative orientation (in frame i) + Matrix3 delRdelBiasOmega_; ///< Jacobian of preintegrated rotation w.r.t. angular rate bias + + /// Default constructor for serialization + PreintegratedRotation() {} + + public: + /// @name Constructors + /// @{ + + /// Default constructor, resets integration to zero + explicit PreintegratedRotation(const boost::shared_ptr& p) : p_(p) { + resetIntegration(); } - /// methods to access class variables - Matrix3 deltaRij() const { - return deltaRij_.matrix(); - } // expensive - Vector3 thetaRij(OptionalJacobian<3, 3> H = boost::none) const { - return Rot3::Logmap(deltaRij_, H); - } // super-expensive + /// Explicit initialization of all class members + PreintegratedRotation(const boost::shared_ptr& p, + double deltaTij, const Rot3& deltaRij, + const Matrix3& delRdelBiasOmega) + : p_(p), deltaTij_(deltaTij), deltaRij_(deltaRij), delRdelBiasOmega_(delRdelBiasOmega) {} + + /// @} + + /// @name Basic utilities + /// @{ + + /// Re-initialize PreintegratedMeasurements + void resetIntegration(); + + /// check parameters equality: checks whether shared pointer points to same Params object. + bool matchesParamsWith(const PreintegratedRotation& other) const { + return p_ == other.p_; + } + /// @} + + /// @name Access instance variables + /// @{ + const boost::shared_ptr& params() const { + return p_; + } const double& deltaTij() const { return deltaTij_; } + const Rot3& deltaRij() const { + return deltaRij_; + } const Matrix3& delRdelBiasOmega() const { return delRdelBiasOmega_; } - const Matrix3& gyroscopeCovariance() const { - return gyroscopeCovariance_; - } + /// @} - /// Needed for testable - void print(const std::string& s) const { - std::cout << s << std::endl; - std::cout << " deltaTij [" << deltaTij_ << "]" << std::endl; - std::cout << " deltaRij.ypr = (" << deltaRij_.ypr().transpose() << ")" << std::endl; - } + /// @name Testable + /// @{ + void print(const std::string& s) const; + bool equals(const PreintegratedRotation& other, double tol) const; + /// @} - /// Needed for testable - bool equals(const PreintegratedRotation& expected, double tol) const { - return deltaRij_.equals(expected.deltaRij_, tol) - && fabs(deltaTij_ - expected.deltaTij_) < tol - && equal_with_abs_tol(delRdelBiasOmega_, expected.delRdelBiasOmega_, - tol) - && equal_with_abs_tol(gyroscopeCovariance_, - expected.gyroscopeCovariance_, tol); - } + /// @name Main functionality + /// @{ - /// Re-initialize PreintegratedMeasurements - void resetIntegration() { - deltaRij_ = Rot3(); - deltaTij_ = 0.0; - delRdelBiasOmega_ = Z_3x3; - } + /// Take the gyro measurement, correct it using the (constant) bias estimate + /// and possibly the sensor pose, and then integrate it forward in time to yield + /// an incremental rotation. + Rot3 incrementalRotation(const Vector3& measuredOmega, const Vector3& biasHat, double deltaT, + OptionalJacobian<3, 3> D_incrR_integratedOmega) const; - /// Update preintegrated measurements - void updateIntegratedRotationAndDeltaT(const Rot3& incrR, const double deltaT, - OptionalJacobian<3, 3> H = boost::none) { - deltaRij_ = deltaRij_.compose(incrR, H, boost::none); - deltaTij_ += deltaT; - } + /// Calculate an incremental rotation given the gyro measurement and a time interval, + /// and update both deltaTij_ and deltaRij_. + void integrateMeasurement(const Vector3& measuredOmega, const Vector3& biasHat, double deltaT, + OptionalJacobian<3, 3> D_incrR_integratedOmega = boost::none, + OptionalJacobian<3, 3> F = boost::none); - /** - * Update Jacobians to be used during preintegration - * TODO: explain arguments - */ - void update_delRdelBiasOmega(const Matrix3& D_Rincr_integratedOmega, - const Rot3& incrR, double deltaT) { - const Matrix3 incrRt = incrR.transpose(); - delRdelBiasOmega_ = incrRt * delRdelBiasOmega_ - - D_Rincr_integratedOmega * deltaT; - } - - /// Return a bias corrected version of the integrated rotation - expensive - Rot3 biascorrectedDeltaRij(const Vector3& biasOmegaIncr) const { - return deltaRij_ * Rot3::Expmap(delRdelBiasOmega_ * biasOmegaIncr); - } - - /// Get so<3> version of bias corrected rotation, with optional Jacobian - // Implements: log( deltaRij_ * expmap(delRdelBiasOmega_ * biasOmegaIncr) ) - Vector3 biascorrectedThetaRij(const Vector3& biasOmegaIncr, - OptionalJacobian<3, 3> H = boost::none) const { - // First, we correct deltaRij using the biasOmegaIncr, rotated - const Rot3 deltaRij_biascorrected = biascorrectedDeltaRij(biasOmegaIncr); - - if (H) { - Matrix3 Jrinv_theta_bc; - // This was done via an expmap, now we go *back* to so<3> - const Vector3 biascorrectedOmega = Rot3::Logmap(deltaRij_biascorrected, - Jrinv_theta_bc); - const Matrix3 Jr_JbiasOmegaIncr = // - Rot3::ExpmapDerivative(delRdelBiasOmega_ * biasOmegaIncr); - (*H) = Jrinv_theta_bc * Jr_JbiasOmegaIncr * delRdelBiasOmega_; - return biascorrectedOmega; - } - //else - return Rot3::Logmap(deltaRij_biascorrected); - } + /// Return a bias corrected version of the integrated rotation, with optional Jacobian + Rot3 biascorrectedDeltaRij(const Vector3& biasOmegaIncr, + OptionalJacobian<3, 3> H = boost::none) const; /// Integrate coriolis correction in body frame rot_i - Vector3 integrateCoriolis(const Rot3& rot_i, - const Vector3& omegaCoriolis) const { - return rot_i.transpose() * omegaCoriolis * deltaTij(); - } + Vector3 integrateCoriolis(const Rot3& rot_i) const; -private: + /// @} + + private: /** Serialization function */ friend class boost::serialization::access; - template - void serialize(ARCHIVE & ar, const unsigned int /*version*/) { - ar & BOOST_SERIALIZATION_NVP(deltaRij_); - ar & BOOST_SERIALIZATION_NVP(deltaTij_); - ar & BOOST_SERIALIZATION_NVP(delRdelBiasOmega_); + template + void serialize(ARCHIVE& ar, const unsigned int /*version*/) { // NOLINT + ar& BOOST_SERIALIZATION_NVP(p_); + ar& BOOST_SERIALIZATION_NVP(deltaTij_); + ar& BOOST_SERIALIZATION_NVP(deltaRij_); + ar& BOOST_SERIALIZATION_NVP(delRdelBiasOmega_); } }; -} /// namespace gtsam +template <> +struct traits : public Testable {}; + +} /// namespace gtsam diff --git a/gtsam/navigation/PreintegrationBase.cpp b/gtsam/navigation/PreintegrationBase.cpp index 496569599..c3f203849 100644 --- a/gtsam/navigation/PreintegrationBase.cpp +++ b/gtsam/navigation/PreintegrationBase.cpp @@ -1,6 +1,6 @@ /* ---------------------------------------------------------------------------- - * GTSAM Copyright 2010, Georgia Tech Research Corporation, + * 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) @@ -20,338 +20,396 @@ **/ #include "PreintegrationBase.h" +#include +#include + +using namespace std; namespace gtsam { -PreintegrationBase::PreintegrationBase(const imuBias::ConstantBias& bias, - const Matrix3& measuredAccCovariance, - const Matrix3& measuredOmegaCovariance, - const Matrix3&integrationErrorCovariance, - const bool use2ndOrderIntegration) - : PreintegratedRotation(measuredOmegaCovariance), - biasHat_(bias), - use2ndOrderIntegration_(use2ndOrderIntegration), - deltaPij_(Vector3::Zero()), - deltaVij_(Vector3::Zero()), - delPdelBiasAcc_(Z_3x3), - delPdelBiasOmega_(Z_3x3), - delVdelBiasAcc_(Z_3x3), - delVdelBiasOmega_(Z_3x3), - accelerometerCovariance_(measuredAccCovariance), - integrationCovariance_(integrationErrorCovariance) { -} - -/// Needed for testable -void PreintegrationBase::print(const std::string& s) const { - PreintegratedRotation::print(s); - std::cout << " deltaPij [ " << deltaPij_.transpose() << " ]" << std::endl; - std::cout << " deltaVij [ " << deltaVij_.transpose() << " ]" << std::endl; - biasHat_.print(" biasHat"); -} - -/// Needed for testable -bool PreintegrationBase::equals(const PreintegrationBase& other, double tol) const { - return PreintegratedRotation::equals(other, tol) && biasHat_.equals(other.biasHat_, tol) - && equal_with_abs_tol(deltaPij_, other.deltaPij_, tol) - && equal_with_abs_tol(deltaVij_, other.deltaVij_, tol) - && equal_with_abs_tol(delPdelBiasAcc_, other.delPdelBiasAcc_, tol) - && equal_with_abs_tol(delPdelBiasOmega_, other.delPdelBiasOmega_, tol) - && equal_with_abs_tol(delVdelBiasAcc_, other.delVdelBiasAcc_, tol) - && equal_with_abs_tol(delVdelBiasOmega_, other.delVdelBiasOmega_, tol) - && equal_with_abs_tol(accelerometerCovariance_, other.accelerometerCovariance_, tol) - && equal_with_abs_tol(integrationCovariance_, other.integrationCovariance_, tol); -} - -/// Re-initialize PreintegratedMeasurements -void PreintegrationBase::resetIntegration() { - PreintegratedRotation::resetIntegration(); - deltaPij_ = Vector3::Zero(); - deltaVij_ = Vector3::Zero(); - delPdelBiasAcc_ = Z_3x3; - delPdelBiasOmega_ = Z_3x3; - delVdelBiasAcc_ = Z_3x3; - delVdelBiasOmega_ = Z_3x3; -} - -/// Update preintegrated measurements -void PreintegrationBase::updatePreintegratedMeasurements(const Vector3& correctedAcc, - const Rot3& incrR, const double deltaT, - OptionalJacobian<9, 9> F) { - - const Matrix3 dRij = deltaRij(); // expensive - const Vector3 temp = dRij * correctedAcc * deltaT; - if (!use2ndOrderIntegration_) { - deltaPij_ += deltaVij_ * deltaT; - } else { - deltaPij_ += deltaVij_ * deltaT + 0.5 * temp * deltaT; - } - deltaVij_ += temp; - - Matrix3 R_i, F_angles_angles; - if (F) - R_i = deltaRij(); // has to be executed before updateIntegratedRotationAndDeltaT as that updates deltaRij - updateIntegratedRotationAndDeltaT(incrR, deltaT, F ? &F_angles_angles : 0); - - if (F) { - const Matrix3 F_vel_angles = -R_i * skewSymmetric(correctedAcc) * deltaT; - Matrix3 F_pos_angles; - if (use2ndOrderIntegration_) - F_pos_angles = 0.5 * F_vel_angles * deltaT; - else - F_pos_angles = Z_3x3; - - // pos vel angle - *F << // - I_3x3, I_3x3 * deltaT, F_pos_angles, // pos - Z_3x3, I_3x3, F_vel_angles, // vel - Z_3x3, Z_3x3, F_angles_angles; // angle - } -} - -/// Update Jacobians to be used during preintegration -void PreintegrationBase::updatePreintegratedJacobians(const Vector3& correctedAcc, - const Matrix3& D_Rincr_integratedOmega, - const Rot3& incrR, double deltaT) { - const Matrix3 dRij = deltaRij(); // expensive - const Matrix3 temp = -dRij * skewSymmetric(correctedAcc) * deltaT * delRdelBiasOmega(); - if (!use2ndOrderIntegration_) { - delPdelBiasAcc_ += delVdelBiasAcc_ * deltaT; - delPdelBiasOmega_ += delVdelBiasOmega_ * deltaT; - } else { - delPdelBiasAcc_ += delVdelBiasAcc_ * deltaT - 0.5 * dRij * deltaT * deltaT; - delPdelBiasOmega_ += deltaT * (delVdelBiasOmega_ + temp * 0.5); - } - delVdelBiasAcc_ += -dRij * deltaT; - delVdelBiasOmega_ += temp; - update_delRdelBiasOmega(D_Rincr_integratedOmega, incrR, deltaT); -} - -void PreintegrationBase::correctMeasurementsByBiasAndSensorPose( - const Vector3& measuredAcc, const Vector3& measuredOmega, Vector3& correctedAcc, - Vector3& correctedOmega, boost::optional body_P_sensor) { - correctedAcc = biasHat_.correctAccelerometer(measuredAcc); - correctedOmega = biasHat_.correctGyroscope(measuredOmega); - - // Then compensate for sensor-body displacement: we express the quantities - // (originally in the IMU frame) into the body frame - if (body_P_sensor) { - Matrix3 body_R_sensor = body_P_sensor->rotation().matrix(); - correctedOmega = body_R_sensor * correctedOmega; // rotation rate vector in the body frame - Matrix3 body_omega_body__cross = skewSymmetric(correctedOmega); - correctedAcc = body_R_sensor * correctedAcc - - body_omega_body__cross * body_omega_body__cross * body_P_sensor->translation().vector(); - // linear acceleration vector in the body frame - } -} - -/// Predict state at time j //------------------------------------------------------------------------------ -PoseVelocityBias PreintegrationBase::predict( - const Pose3& pose_i, const Vector3& vel_i, const imuBias::ConstantBias& bias_i, - const Vector3& gravity, const Vector3& omegaCoriolis, const bool use2ndOrderCoriolis, - boost::optional deltaPij_biascorrected_out, - boost::optional deltaVij_biascorrected_out) const { +PreintegrationBase::PreintegrationBase(const boost::shared_ptr& p, + const Bias& biasHat) + : p_(p), biasHat_(biasHat), deltaTij_(0.0) { + resetIntegration(); +} - const imuBias::ConstantBias biasIncr = bias_i - biasHat(); - const Vector3& biasAccIncr = biasIncr.accelerometer(); - const Vector3& biasOmegaIncr = biasIncr.gyroscope(); +//------------------------------------------------------------------------------ +void PreintegrationBase::resetIntegration() { + deltaTij_ = 0.0; + preintegrated_.setZero(); + preintegrated_H_biasAcc_.setZero(); + preintegrated_H_biasOmega_.setZero(); +} - const Rot3& Rot_i = pose_i.rotation(); - const Matrix3 Rot_i_matrix = Rot_i.matrix(); - const Vector3 pos_i = pose_i.translation().vector(); +//------------------------------------------------------------------------------ +ostream& operator<<(ostream& os, const PreintegrationBase& pim) { + os << " deltaTij " << pim.deltaTij_ << endl; + os << " deltaRij " << Point3(pim.theta()) << endl; + os << " deltaPij " << Point3(pim.deltaPij()) << endl; + os << " deltaVij " << Point3(pim.deltaVij()) << endl; + os << " gyrobias " << Point3(pim.biasHat_.gyroscope()) << endl; + os << " acc_bias " << Point3(pim.biasHat_.accelerometer()) << endl; + return os; +} + +//------------------------------------------------------------------------------ +void PreintegrationBase::print(const string& s) const { + cout << s << *this << endl; +} + +//------------------------------------------------------------------------------ +bool PreintegrationBase::equals(const PreintegrationBase& other, + double tol) const { + const bool params_match = p_->equals(*other.p_, tol); + return params_match && fabs(deltaTij_ - other.deltaTij_) < tol + && biasHat_.equals(other.biasHat_, tol) + && equal_with_abs_tol(preintegrated_, other.preintegrated_, tol) + && equal_with_abs_tol(preintegrated_H_biasAcc_, other.preintegrated_H_biasAcc_, tol) + && equal_with_abs_tol(preintegrated_H_biasOmega_, other.preintegrated_H_biasOmega_, tol); +} + +//------------------------------------------------------------------------------ +pair PreintegrationBase::correctMeasurementsBySensorPose( + const Vector3& unbiasedAcc, const Vector3& unbiasedOmega, + OptionalJacobian<3, 3> D_correctedAcc_unbiasedAcc, + OptionalJacobian<3, 3> D_correctedAcc_unbiasedOmega, + OptionalJacobian<3, 3> D_correctedOmega_unbiasedOmega) const { + assert(p().body_P_sensor); + + // Compensate for sensor-body displacement if needed: we express the quantities + // (originally in the IMU frame) into the body frame + // Equations below assume the "body" frame is the CG + + // Get sensor to body rotation matrix + const Matrix3 bRs = p().body_P_sensor->rotation().matrix(); + + // Convert angular velocity and acceleration from sensor to body frame + Vector3 correctedAcc = bRs * unbiasedAcc; + const Vector3 correctedOmega = bRs * unbiasedOmega; + + // Jacobians + if (D_correctedAcc_unbiasedAcc) *D_correctedAcc_unbiasedAcc = bRs; + if (D_correctedAcc_unbiasedOmega) *D_correctedAcc_unbiasedOmega = Z_3x3; + if (D_correctedOmega_unbiasedOmega) *D_correctedOmega_unbiasedOmega = bRs; + + // Centrifugal acceleration + const Vector3 b_arm = p().body_P_sensor->translation().vector(); + if (!b_arm.isZero()) { + // Subtract out the the centripetal acceleration from the unbiased one + // to get linear acceleration vector in the body frame: + const Matrix3 body_Omega_body = skewSymmetric(correctedOmega); + const Vector3 b_velocity_bs = body_Omega_body * b_arm; // magnitude: omega * arm + correctedAcc -= body_Omega_body * b_velocity_bs; + + // Update derivative: centrifugal causes the correlation between acc and omega!!! + if (D_correctedAcc_unbiasedOmega) { + double wdp = correctedOmega.dot(b_arm); + *D_correctedAcc_unbiasedOmega = -(diag(Vector3::Constant(wdp)) + + correctedOmega * b_arm.transpose()) * bRs.matrix() + + 2 * b_arm * unbiasedOmega.transpose(); + } + } + + return make_pair(correctedAcc, correctedOmega); +} + +//------------------------------------------------------------------------------ +// See extensive discussion in ImuFactor.lyx +Vector9 PreintegrationBase::UpdatePreintegrated( + const Vector3& a_body, const Vector3& w_body, double dt, + const Vector9& preintegrated, OptionalJacobian<9, 9> A, + OptionalJacobian<9, 3> B, OptionalJacobian<9, 3> C) { + const auto theta = preintegrated.segment<3>(0); + const auto position = preintegrated.segment<3>(3); + const auto velocity = preintegrated.segment<3>(6); + + // This functor allows for saving computation when exponential map and its + // derivatives are needed at the same location in so<3> + so3::DexpFunctor local(theta); + + // Calculate exact mean propagation + Matrix3 w_tangent_H_theta, invH; + const Vector3 w_tangent = // angular velocity mapped back to tangent space + local.applyInvDexp(w_body, A ? &w_tangent_H_theta : 0, C ? &invH : 0); + const SO3 R = local.expmap(); + const Vector3 a_nav = R * a_body; + const double dt22 = 0.5 * dt * dt; + + Vector9 preintegratedPlus; + preintegratedPlus << // new preintegrated vector: + theta + w_tangent* dt, // theta + position + velocity* dt + a_nav* dt22, // position + velocity + a_nav* dt; // velocity + + if (A) { + // Exact derivative of R*a with respect to theta: + const Matrix3 a_nav_H_theta = R * skewSymmetric(-a_body) * local.dexp(); + + A->setIdentity(); + A->block<3, 3>(0, 0).noalias() += w_tangent_H_theta * dt; // theta + A->block<3, 3>(3, 0) = a_nav_H_theta * dt22; // position wrpt theta... + A->block<3, 3>(3, 6) = I_3x3 * dt; // .. and velocity + A->block<3, 3>(6, 0) = a_nav_H_theta * dt; // velocity wrpt theta + } + if (B) { + B->block<3, 3>(0, 0) = Z_3x3; + B->block<3, 3>(3, 0) = R * dt22; + B->block<3, 3>(6, 0) = R * dt; + } + if (C) { + C->block<3, 3>(0, 0) = invH * dt; + C->block<3, 3>(3, 0) = Z_3x3; + C->block<3, 3>(6, 0) = Z_3x3; + } + + return preintegratedPlus; +} + +//------------------------------------------------------------------------------ +void PreintegrationBase::integrateMeasurement(const Vector3& measuredAcc, + const Vector3& measuredOmega, + double dt, Matrix9* A, + Matrix93* B, Matrix93* C) { + // Correct for bias in the sensor frame + Vector3 acc = biasHat_.correctAccelerometer(measuredAcc); + Vector3 omega = biasHat_.correctGyroscope(measuredOmega); + + // Possibly correct for sensor pose + Matrix3 D_correctedAcc_acc, D_correctedAcc_omega, D_correctedOmega_omega; + if (p().body_P_sensor) + boost::tie(acc, omega) = correctMeasurementsBySensorPose( acc, omega, + D_correctedAcc_acc, D_correctedAcc_omega, D_correctedOmega_omega); + + // Do update + deltaTij_ += dt; + preintegrated_ = UpdatePreintegrated(acc, omega, dt, preintegrated_, A, B, C); + + if (p().body_P_sensor) { + // More complicated derivatives in case of non-trivial sensor pose + *C *= D_correctedOmega_omega; + if (!p().body_P_sensor->translation().vector().isZero()) + *C += *B* D_correctedAcc_omega; + *B *= D_correctedAcc_acc; // NOTE(frank): needs to be last + } + + // D_plus_abias = D_plus_preintegrated * D_preintegrated_abias + D_plus_a * D_a_abias + preintegrated_H_biasAcc_ = (*A) * preintegrated_H_biasAcc_ - (*B); + + // D_plus_wbias = D_plus_preintegrated * D_preintegrated_wbias + D_plus_w * D_w_wbias + preintegrated_H_biasOmega_ = (*A) * preintegrated_H_biasOmega_ - (*C); +} + +void PreintegrationBase::integrateMeasurement(const Vector3& measuredAcc, + const Vector3& measuredOmega, + double dt) { + // NOTE(frank): integrateMeasuremtn always needs to compute the derivatives, + // even when not of interest to the caller. Provide scratch space here. + Matrix9 A; + Matrix93 B, C; + integrateMeasurement(measuredAcc, measuredOmega, dt, &A, &B, &C); +} +//------------------------------------------------------------------------------ +Vector9 PreintegrationBase::biasCorrectedDelta( + const imuBias::ConstantBias& bias_i, OptionalJacobian<9, 6> H) const { + // We correct for a change between bias_i and the biasHat_ used to integrate + // This is a simple linear correction with obvious derivatives + const imuBias::ConstantBias biasIncr = bias_i - biasHat_; + const Vector9 biasCorrected = + preintegrated() + preintegrated_H_biasAcc_ * biasIncr.accelerometer() + + preintegrated_H_biasOmega_ * biasIncr.gyroscope(); + + if (H) { + (*H) << preintegrated_H_biasAcc_, preintegrated_H_biasOmega_; + } + return biasCorrected; +} + +//------------------------------------------------------------------------------ +NavState PreintegrationBase::predict(const NavState& state_i, + const imuBias::ConstantBias& bias_i, + OptionalJacobian<9, 9> H1, + OptionalJacobian<9, 6> H2) const { + // TODO(frank): make sure this stuff is still correct + Matrix96 D_biasCorrected_bias; + Vector9 biasCorrected = + biasCorrectedDelta(bias_i, H2 ? &D_biasCorrected_bias : 0); + + // Correct for initial velocity and gravity + Matrix9 D_delta_state, D_delta_biasCorrected; + Vector9 xi = state_i.correctPIM(biasCorrected, deltaTij_, p().n_gravity, + p().omegaCoriolis, p().use2ndOrderCoriolis, + H1 ? &D_delta_state : 0, + H2 ? &D_delta_biasCorrected : 0); + + // Use retract to get back to NavState manifold + Matrix9 D_predict_state, D_predict_delta; + NavState state_j = state_i.retract(xi, D_predict_state, D_predict_delta); + if (H1) *H1 = D_predict_state + D_predict_delta* D_delta_state; + if (H2) *H2 = D_predict_delta* D_delta_biasCorrected* D_biasCorrected_bias; + return state_j; +} + +//------------------------------------------------------------------------------ +Vector9 PreintegrationBase::computeError(const NavState& state_i, + const NavState& state_j, + const imuBias::ConstantBias& bias_i, + OptionalJacobian<9, 9> H1, + OptionalJacobian<9, 9> H2, + OptionalJacobian<9, 6> H3) const { + // Predict state at time j + Matrix9 D_predict_state_i; + Matrix96 D_predict_bias_i; + NavState predictedState_j = predict( + state_i, bias_i, H1 ? &D_predict_state_i : 0, H3 ? &D_predict_bias_i : 0); + + // Calculate error + Matrix9 D_error_state_j, D_error_predict; + Vector9 error = + state_j.localCoordinates(predictedState_j, H2 ? &D_error_state_j : 0, + H1 || H3 ? &D_error_predict : 0); + + if (H1) *H1 << D_error_predict* D_predict_state_i; + if (H2) *H2 << D_error_state_j; + if (H3) *H3 << D_error_predict* D_predict_bias_i; + + return error; +} + +//------------------------------------------------------------------------------ +Vector9 PreintegrationBase::computeErrorAndJacobians(const Pose3& pose_i, + const Vector3& vel_i, const Pose3& pose_j, const Vector3& vel_j, + const imuBias::ConstantBias& bias_i, OptionalJacobian<9, 6> H1, + OptionalJacobian<9, 3> H2, OptionalJacobian<9, 6> H3, + OptionalJacobian<9, 3> H4, OptionalJacobian<9, 6> H5) const { + + // Note that derivative of constructors below is not identity for velocity, but + // a 9*3 matrix == Z_3x3, Z_3x3, state.R().transpose() + NavState state_i(pose_i, vel_i); + NavState state_j(pose_j, vel_j); // Predict state at time j - /* ---------------------------------------------------------------------------------------------------- */ - const Vector3 deltaPij_biascorrected = deltaPij() + delPdelBiasAcc() * biasAccIncr - + delPdelBiasOmega() * biasOmegaIncr; - if (deltaPij_biascorrected_out) // if desired, store this - *deltaPij_biascorrected_out = deltaPij_biascorrected; + Matrix9 D_error_state_i, D_error_state_j; + Vector9 error = computeError(state_i, state_j, bias_i, + H1 || H2 ? &D_error_state_i : 0, H3 || H4 ? &D_error_state_j : 0, H5); - const double dt = deltaTij(), dt2 = dt * dt; - Vector3 pos_j = pos_i + Rot_i_matrix * deltaPij_biascorrected + vel_i * dt - - omegaCoriolis.cross(vel_i) * dt2 // Coriolis term - we got rid of the 2 wrt ins paper - + 0.5 * gravity * dt2; + // Separate out derivatives in terms of 5 arguments + // Note that doing so requires special treatment of velocities, as when treated as + // separate variables the retract applied will not be the semi-direct product in NavState + // Instead, the velocities in nav are updated using a straight addition + // This is difference is accounted for by the R().transpose calls below + if (H1) *H1 << D_error_state_i.leftCols<6>(); + if (H2) *H2 << D_error_state_i.rightCols<3>() * state_i.R().transpose(); + if (H3) *H3 << D_error_state_j.leftCols<6>(); + if (H4) *H4 << D_error_state_j.rightCols<3>() * state_j.R().transpose(); - const Vector3 deltaVij_biascorrected = deltaVij() + delVdelBiasAcc() * biasAccIncr - + delVdelBiasOmega() * biasOmegaIncr; - if (deltaVij_biascorrected_out) // if desired, store this - *deltaVij_biascorrected_out = deltaVij_biascorrected; - - Vector3 vel_j = Vector3( - vel_i + Rot_i_matrix * deltaVij_biascorrected - 2 * omegaCoriolis.cross(vel_i) * dt // Coriolis term - + gravity * dt); - - if (use2ndOrderCoriolis) { - pos_j += -0.5 * omegaCoriolis.cross(omegaCoriolis.cross(pos_i)) * dt2; // 2nd order coriolis term for position - vel_j += -omegaCoriolis.cross(omegaCoriolis.cross(pos_i)) * dt; // 2nd order term for velocity - } - - const Rot3 deltaRij_biascorrected = biascorrectedDeltaRij(biasOmegaIncr); - // deltaRij_biascorrected = deltaRij * expmap(delRdelBiasOmega * biasOmegaIncr) - - const Vector3 biascorrectedOmega = Rot3::Logmap(deltaRij_biascorrected); - const Vector3 correctedOmega = biascorrectedOmega - - Rot_i_matrix.transpose() * omegaCoriolis * dt; // Coriolis term - const Rot3 correctedDeltaRij = Rot3::Expmap(correctedOmega); - const Rot3 Rot_j = Rot_i.compose(correctedDeltaRij); - - const Pose3 pose_j = Pose3(Rot_j, Point3(pos_j)); - return PoseVelocityBias(pose_j, vel_j, bias_i); // bias is predicted as a constant + return error; } -/// Compute errors w.r.t. preintegrated measurements and Jacobians wrpt pose_i, vel_i, bias_i, pose_j, bias_j //------------------------------------------------------------------------------ -Vector9 PreintegrationBase::computeErrorAndJacobians(const Pose3& pose_i, const Vector3& vel_i, - const Pose3& pose_j, const Vector3& vel_j, - const imuBias::ConstantBias& bias_i, - const Vector3& gravity, - const Vector3& omegaCoriolis, - const bool use2ndOrderCoriolis, - OptionalJacobian<9, 6> H1, - OptionalJacobian<9, 3> H2, - OptionalJacobian<9, 6> H3, - OptionalJacobian<9, 3> H4, - OptionalJacobian<9, 6> H5) const { +// sugar for derivative blocks +#define D_R_R(H) (H)->block<3,3>(0,0) +#define D_R_t(H) (H)->block<3,3>(0,3) +#define D_R_v(H) (H)->block<3,3>(0,6) +#define D_t_R(H) (H)->block<3,3>(3,0) +#define D_t_t(H) (H)->block<3,3>(3,3) +#define D_t_v(H) (H)->block<3,3>(3,6) +#define D_v_R(H) (H)->block<3,3>(6,0) +#define D_v_t(H) (H)->block<3,3>(6,3) +#define D_v_v(H) (H)->block<3,3>(6,6) - // We need the mismatch w.r.t. the biases used for preintegration - const Vector3 biasOmegaIncr = bias_i.gyroscope() - biasHat().gyroscope(); +//------------------------------------------------------------------------------ +Vector9 PreintegrationBase::Compose(const Vector9& zeta01, + const Vector9& zeta12, double deltaT12, + OptionalJacobian<9, 9> H1, + OptionalJacobian<9, 9> H2) { + const auto t01 = zeta01.segment<3>(0); + const auto p01 = zeta01.segment<3>(3); + const auto v01 = zeta01.segment<3>(6); - // we give some shorter name to rotations and translations - const Rot3& Ri = pose_i.rotation(); - const Matrix3 Ri_transpose_matrix = Ri.transpose(); + const auto t12 = zeta12.segment<3>(0); + const auto p12 = zeta12.segment<3>(3); + const auto v12 = zeta12.segment<3>(6); - const Rot3& Rj = pose_j.rotation(); - const Vector3 pos_j = pose_j.translation().vector(); + Matrix3 R01_H_t01, R12_H_t12; + const Rot3 R01 = Rot3::Expmap(t01, R01_H_t01); + const Rot3 R12 = Rot3::Expmap(t12, R12_H_t12); - // Evaluate residual error, according to [3] - /* ---------------------------------------------------------------------------------------------------- */ - Vector3 deltaPij_biascorrected, deltaVij_biascorrected; - PoseVelocityBias predictedState_j = predict(pose_i, vel_i, bias_i, gravity, omegaCoriolis, - use2ndOrderCoriolis, deltaPij_biascorrected, - deltaVij_biascorrected); + Matrix3 R02_H_R01, R02_H_R12; // NOTE(frank): R02_H_R12 == Identity + const Rot3 R02 = R01.compose(R12, R02_H_R01, R02_H_R12); - // Ri.transpose() is important here to preserve a model with *additive* Gaussian noise of correct covariance - const Vector3 fp = Ri_transpose_matrix * (pos_j - predictedState_j.pose.translation().vector()); + Matrix3 t02_H_R02; + Vector9 zeta02; + const Matrix3 R = R01.matrix(); + zeta02 << Rot3::Logmap(R02, t02_H_R02), // theta + p01 + v01 * deltaT12 + R * p12, // position + v01 + R * v12; // velocity - // Ri.transpose() is important here to preserve a model with *additive* Gaussian noise of correct covariance - const Vector3 fv = Ri_transpose_matrix * (vel_j - predictedState_j.velocity); - - // fR will be computed later. Note: it is the same as: fR = (predictedState_j.pose.translation()).between(Rot_j) - - /* ---------------------------------------------------------------------------------------------------- */ - // Get Get so<3> version of bias corrected rotation - // If H5 is asked for, we will need the Jacobian, which we store in H5 - // H5 will then be corrected below to take into account the Coriolis effect - Matrix3 D_cThetaRij_biasOmegaIncr; - const Vector3 biascorrectedOmega = biascorrectedThetaRij(biasOmegaIncr, - H5 ? &D_cThetaRij_biasOmegaIncr : 0); - - // Coriolis term, note inconsistent with AHRS, where coriolisHat is *after* integration - const Vector3 coriolis = integrateCoriolis(Ri, omegaCoriolis); - const Vector3 correctedOmega = biascorrectedOmega - coriolis; - - // Calculate Jacobians, matrices below needed only for some Jacobians... - Vector3 fR; - Matrix3 D_cDeltaRij_cOmega, D_coriolis, D_fR_fRrot, Ritranspose_omegaCoriolisHat; - - if (H1 || H2) - Ritranspose_omegaCoriolisHat = Ri_transpose_matrix * skewSymmetric(omegaCoriolis); - - // This is done to save computation: we ask for the jacobians only when they are needed - const double dt = deltaTij(), dt2 = dt*dt; - Rot3 fRrot; - const Rot3 RiBetweenRj = Rot3(Ri_transpose_matrix) * Rj; - if (H1 || H2 || H3 || H4 || H5) { - const Rot3 correctedDeltaRij = Rot3::Expmap(correctedOmega, D_cDeltaRij_cOmega); - // Residual rotation error - fRrot = correctedDeltaRij.between(RiBetweenRj); - fR = Rot3::Logmap(fRrot, D_fR_fRrot); - D_coriolis = -D_cDeltaRij_cOmega * skewSymmetric(coriolis); - } else { - const Rot3 correctedDeltaRij = Rot3::Expmap(correctedOmega); - // Residual rotation error - fRrot = correctedDeltaRij.between(RiBetweenRj); - fR = Rot3::Logmap(fRrot); - } if (H1) { - Matrix3 dfPdPi = -I_3x3, dfVdPi = Z_3x3; - if (use2ndOrderCoriolis) { - // this is the same as: Ri.transpose() * omegaCoriolisHat * omegaCoriolisHat * Ri.matrix() - const Matrix3 temp = Ritranspose_omegaCoriolisHat - * (-Ritranspose_omegaCoriolisHat.transpose()); - dfPdPi += 0.5 * temp * dt2; - dfVdPi += temp * dt; - } - (*H1) << - // dfP/dRi - skewSymmetric(fp + deltaPij_biascorrected), - // dfP/dPi - dfPdPi, - // dfV/dRi - skewSymmetric(fv + deltaVij_biascorrected), - // dfV/dPi - dfVdPi, - // dfR/dRi - D_fR_fRrot * (-Rj.between(Ri).matrix() - fRrot.inverse().matrix() * D_coriolis), - // dfR/dPi - Z_3x3; + H1->setIdentity(); + D_R_R(H1) = t02_H_R02 * R02_H_R01 * R01_H_t01; + D_t_R(H1) = R * skewSymmetric(-p12) * R01_H_t01; + D_t_v(H1) = I_3x3 * deltaT12; + D_v_R(H1) = R * skewSymmetric(-v12) * R01_H_t01; } + if (H2) { - (*H2) << - // dfP/dVi - -Ri_transpose_matrix * dt + Ritranspose_omegaCoriolisHat * dt2, // Coriolis term - we got rid of the 2 wrt ins paper - // dfV/dVi - -Ri_transpose_matrix + 2 * Ritranspose_omegaCoriolisHat * dt, // Coriolis term - // dfR/dVi - Z_3x3; + H2->setZero(); + D_R_R(H2) = t02_H_R02 * R02_H_R12 * R12_H_t12; + D_t_t(H2) = R; + D_v_v(H2) = R; } - if (H3) { - (*H3) << - // dfP/dPosej - Z_3x3, Ri_transpose_matrix * Rj.matrix(), - // dfV/dPosej - Matrix::Zero(3, 6), - // dfR/dPosej - D_fR_fRrot, Z_3x3; - } - if (H4) { - (*H4) << - // dfP/dVj - Z_3x3, - // dfV/dVj - Ri_transpose_matrix, - // dfR/dVj - Z_3x3; - } - if (H5) { - // H5 by this point already contains 3*3 biascorrectedThetaRij derivative - const Matrix3 JbiasOmega = D_cDeltaRij_cOmega * D_cThetaRij_biasOmegaIncr; - (*H5) << - // dfP/dBias - -delPdelBiasAcc(), -delPdelBiasOmega(), - // dfV/dBias - -delVdelBiasAcc(), -delVdelBiasOmega(), - // dfR/dBias - Z_3x3, D_fR_fRrot * (-fRrot.inverse().matrix() * JbiasOmega); - } - Vector9 r; - r << fp, fv, fR; - return r; + + return zeta02; } -ImuBase::ImuBase() - : gravity_(Vector3(0.0, 0.0, 9.81)), - omegaCoriolis_(Vector3(0.0, 0.0, 0.0)), - body_P_sensor_(boost::none), - use2ndOrderCoriolis_(false) { +//------------------------------------------------------------------------------ +void PreintegrationBase::mergeWith(const PreintegrationBase& pim12, Matrix9* H1, + Matrix9* H2) { + if (!matchesParamsWith(pim12)) + throw std::domain_error( + "Cannot merge pre-integrated measurements with different params"); + + if (params()->body_P_sensor) + throw std::domain_error( + "Cannot merge pre-integrated measurements with sensor pose yet"); + + const double& t01 = deltaTij(); + const double& t12 = pim12.deltaTij(); + deltaTij_ = t01 + t12; + + Vector9 zeta01 = preintegrated(); + Vector9 zeta12 = pim12.preintegrated(); + + // TODO(frank): adjust zeta12 due to bias difference + const imuBias::ConstantBias bias_incr_for_12 = biasHat() - pim12.biasHat(); + zeta12 += pim12.preintegrated_H_biasOmega_ * bias_incr_for_12.gyroscope() + + pim12.preintegrated_H_biasAcc_ * bias_incr_for_12.accelerometer(); + + preintegrated_ << PreintegrationBase::Compose(zeta01, zeta12, t12, H1, H2); + + preintegrated_H_biasAcc_ = + (*H1) * preintegrated_H_biasAcc_ + (*H2) * pim12.preintegrated_H_biasAcc_; + + preintegrated_H_biasOmega_ = (*H1) * preintegrated_H_biasOmega_ + + (*H2) * pim12.preintegrated_H_biasOmega_; } -ImuBase::ImuBase(const Vector3& gravity, const Vector3& omegaCoriolis, - boost::optional body_P_sensor, const bool use2ndOrderCoriolis) - : gravity_(gravity), - omegaCoriolis_(omegaCoriolis), - body_P_sensor_(body_P_sensor), - use2ndOrderCoriolis_(use2ndOrderCoriolis) { +//------------------------------------------------------------------------------ +#ifdef GTSAM_ALLOW_DEPRECATED_SINCE_V4 +PoseVelocityBias PreintegrationBase::predict(const Pose3& pose_i, + const Vector3& vel_i, const imuBias::ConstantBias& bias_i, + const Vector3& n_gravity, const Vector3& omegaCoriolis, + const bool use2ndOrderCoriolis) const { +// NOTE(frank): parameters are supposed to be constant, below is only provided for compatibility + boost::shared_ptr q = boost::make_shared(p()); + q->n_gravity = n_gravity; + q->omegaCoriolis = omegaCoriolis; + q->use2ndOrderCoriolis = use2ndOrderCoriolis; + p_ = q; + return PoseVelocityBias(predict(NavState(pose_i, vel_i), bias_i), bias_i); } +#endif +//------------------------------------------------------------------------------ -} /// namespace gtsam +} // namespace gtsam diff --git a/gtsam/navigation/PreintegrationBase.h b/gtsam/navigation/PreintegrationBase.h index f6b24e752..f8639cf79 100644 --- a/gtsam/navigation/PreintegrationBase.h +++ b/gtsam/navigation/PreintegrationBase.h @@ -1,6 +1,6 @@ /* ---------------------------------------------------------------------------- - * GTSAM Copyright 2010, Georgia Tech Research Corporation, + * 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) @@ -21,28 +21,33 @@ #pragma once -#include +#include +#include #include -#include -#include -#include +#include + +#include namespace gtsam { -/** - * Struct to hold all state variables of returned by Predict function - */ +#ifdef GTSAM_ALLOW_DEPRECATED_SINCE_V4 +/// @deprecated struct PoseVelocityBias { Pose3 pose; Vector3 velocity; imuBias::ConstantBias bias; - - PoseVelocityBias(const Pose3& _pose, const Vector3& _velocity, const imuBias::ConstantBias _bias) - : pose(_pose), - velocity(_velocity), - bias(_bias) { + PoseVelocityBias(const Pose3& _pose, const Vector3& _velocity, + const imuBias::ConstantBias _bias) : + pose(_pose), velocity(_velocity), bias(_bias) { + } + PoseVelocityBias(const NavState& navState, const imuBias::ConstantBias _bias) : + pose(navState.pose()), velocity(navState.velocity()), bias(_bias) { + } + NavState navState() const { + return NavState(pose, velocity); } }; +#endif /** * PreintegrationBase is the base class for PreintegratedMeasurements @@ -50,154 +55,208 @@ struct PoseVelocityBias { * It includes the definitions of the preintegrated variables and the methods * to access, print, and compare them. */ -class PreintegrationBase : public PreintegratedRotation { - - imuBias::ConstantBias biasHat_; ///< Acceleration and angular rate bias values used during preintegration - bool use2ndOrderIntegration_; ///< Controls the order of integration - - Vector3 deltaPij_; ///< Preintegrated relative position (does not take into account velocity at time i, see deltap+, in [2]) (in frame i) - Vector3 deltaVij_; ///< Preintegrated relative velocity (in global frame) - - Matrix3 delPdelBiasAcc_; ///< Jacobian of preintegrated position w.r.t. acceleration bias - Matrix3 delPdelBiasOmega_; ///< Jacobian of preintegrated position w.r.t. angular rate bias - Matrix3 delVdelBiasAcc_; ///< Jacobian of preintegrated velocity w.r.t. acceleration bias - Matrix3 delVdelBiasOmega_; ///< Jacobian of preintegrated velocity w.r.t. angular rate bias - - const Matrix3 accelerometerCovariance_; ///< continuous-time "Covariance" of accelerometer measurements - const Matrix3 integrationCovariance_; ///< continuous-time "Covariance" describing integration uncertainty - /// (to compensate errors in Euler integration) - +class PreintegrationBase { public: + typedef imuBias::ConstantBias Bias; + typedef PreintegrationParams Params; + + protected: + + /// Parameters. Declared mutable only for deprecated predict method. + /// TODO(frank): make const once deprecated method is removed +#ifdef GTSAM_ALLOW_DEPRECATED_SINCE_V4 + mutable +#endif + boost::shared_ptr p_; + + /// Acceleration and gyro bias used for preintegration + Bias biasHat_; + + /// Time interval from i to j + double deltaTij_; /** - * Default constructor, initializes the variables in the base class - * @param bias Current estimate of acceleration and rotation rate biases - * @param use2ndOrderIntegration Controls the order of integration - * (if false: p(t+1) = p(t) + v(t) deltaT ; if true: p(t+1) = p(t) + v(t) deltaT + 0.5 * acc(t) deltaT^2) + * Preintegrated navigation state, from frame i to frame j + * Note: relative position does not take into account velocity at time i, see deltap+, in [2] + * Note: velocity is now also in frame i, as opposed to deltaVij in [2] */ - PreintegrationBase(const imuBias::ConstantBias& bias, const Matrix3& measuredAccCovariance, - const Matrix3& measuredOmegaCovariance, - const Matrix3&integrationErrorCovariance, const bool use2ndOrderIntegration); + Vector9 preintegrated_; - /// methods to access class variables - bool use2ndOrderIntegration() const { - return use2ndOrderIntegration_; - } - const Vector3& deltaPij() const { - return deltaPij_; - } - const Vector3& deltaVij() const { - return deltaVij_; - } - const imuBias::ConstantBias& biasHat() const { - return biasHat_; - } - Vector6 biasHatVector() const { - return biasHat_.vector(); - } // expensive - const Matrix3& delPdelBiasAcc() const { - return delPdelBiasAcc_; - } - const Matrix3& delPdelBiasOmega() const { - return delPdelBiasOmega_; - } - const Matrix3& delVdelBiasAcc() const { - return delVdelBiasAcc_; - } - const Matrix3& delVdelBiasOmega() const { - return delVdelBiasOmega_; + Matrix93 preintegrated_H_biasAcc_; ///< Jacobian of preintegrated preintegrated w.r.t. acceleration bias + Matrix93 preintegrated_H_biasOmega_; ///< Jacobian of preintegrated preintegrated w.r.t. angular rate bias + + /// Default constructor for serialization + PreintegrationBase() { + resetIntegration(); } - const Matrix3& accelerometerCovariance() const { - return accelerometerCovariance_; - } - const Matrix3& integrationCovariance() const { - return integrationCovariance_; - } +public: + /// @name Constructors + /// @{ - /// print - void print(const std::string& s) const; + /** + * Constructor, initializes the variables in the base class + * @param p Parameters, typically fixed in a single application + * @param bias Current estimate of acceleration and rotation rate biases + */ + PreintegrationBase(const boost::shared_ptr& p, + const imuBias::ConstantBias& biasHat = imuBias::ConstantBias()); - /// check equality - bool equals(const PreintegrationBase& other, double tol) const; + /// @} + /// @name Basic utilities + /// @{ /// Re-initialize PreintegratedMeasurements void resetIntegration(); - /// Update preintegrated measurements - void updatePreintegratedMeasurements(const Vector3& correctedAcc, const Rot3& incrR, - const double deltaT, OptionalJacobian<9, 9> F); + /// check parameters equality: checks whether shared pointer points to same Params object. + bool matchesParamsWith(const PreintegrationBase& other) const { + return p_ == other.p_; + } - /// Update Jacobians to be used during preintegration - void updatePreintegratedJacobians(const Vector3& correctedAcc, - const Matrix3& D_Rincr_integratedOmega, const Rot3& incrR, - double deltaT); + /// shared pointer to params + const boost::shared_ptr& params() const { + return p_; + } - void correctMeasurementsByBiasAndSensorPose(const Vector3& measuredAcc, - const Vector3& measuredOmega, Vector3& correctedAcc, - Vector3& correctedOmega, - boost::optional body_P_sensor); + /// const reference to params + const Params& p() const { + return *boost::static_pointer_cast(p_); + } + +#ifdef GTSAM_ALLOW_DEPRECATED_SINCE_V4 + void set_body_P_sensor(const Pose3& body_P_sensor) { + p_->body_P_sensor = body_P_sensor; + } +#endif +/// @} + + /// @name Instance variables access + /// @{ + const imuBias::ConstantBias& biasHat() const { return biasHat_; } + const double& deltaTij() const { return deltaTij_; } + + const Vector9& preintegrated() const { return preintegrated_; } + + Vector3 theta() const { return preintegrated_.head<3>(); } + Vector3 deltaPij() const { return preintegrated_.segment<3>(3); } + Vector3 deltaVij() const { return preintegrated_.tail<3>(); } + + Rot3 deltaRij() const { return Rot3::Expmap(theta()); } + NavState deltaXij() const { return NavState::Retract(preintegrated_); } + + const Matrix93& preintegrated_H_biasAcc() const { return preintegrated_H_biasAcc_; } + const Matrix93& preintegrated_H_biasOmega() const { return preintegrated_H_biasOmega_; } + + // Exposed for MATLAB + Vector6 biasHatVector() const { return biasHat_.vector(); } + /// @} + + /// @name Testable + /// @{ + GTSAM_EXPORT friend std::ostream& operator<<(std::ostream& os, const PreintegrationBase& pim); + void print(const std::string& s) const; + bool equals(const PreintegrationBase& other, double tol) const; + /// @} + + /// @name Main functionality + /// @{ + + /// Subtract estimate and correct for sensor pose + /// Compute the derivatives due to non-identity body_P_sensor (rotation and centrifugal acc) + /// Ignore D_correctedOmega_measuredAcc as it is trivially zero + std::pair correctMeasurementsBySensorPose( + const Vector3& unbiasedAcc, const Vector3& unbiasedOmega, + OptionalJacobian<3, 3> D_correctedAcc_unbiasedAcc = boost::none, + OptionalJacobian<3, 3> D_correctedAcc_unbiasedOmega = boost::none, + OptionalJacobian<3, 3> D_correctedOmega_unbiasedOmega = boost::none) const; + + // Update integrated vector on tangent manifold preintegrated with acceleration + // Static, functional version. + static Vector9 UpdatePreintegrated(const Vector3& a_body, + const Vector3& w_body, double dt, + const Vector9& preintegrated, + OptionalJacobian<9, 9> A = boost::none, + OptionalJacobian<9, 3> B = boost::none, + OptionalJacobian<9, 3> C = boost::none); + + /// Update preintegrated measurements and get derivatives + /// It takes measured quantities in the j frame + /// Modifies preintegrated_ in place after correcting for bias and possibly sensor pose + void integrateMeasurement(const Vector3& measuredAcc, + const Vector3& measuredOmega, const double deltaT, + Matrix9* A, Matrix93* B, Matrix93* C); + + // Version without derivatives + void integrateMeasurement(const Vector3& measuredAcc, + const Vector3& measuredOmega, const double deltaT); + + /// Given the estimate of the bias, return a NavState tangent vector + /// summarizing the preintegrated IMU measurements so far + Vector9 biasCorrectedDelta(const imuBias::ConstantBias& bias_i, + OptionalJacobian<9, 6> H = boost::none) const; /// Predict state at time j - PoseVelocityBias predict( - const Pose3& pose_i, const Vector3& vel_i, const imuBias::ConstantBias& bias_i, - const Vector3& gravity, const Vector3& omegaCoriolis, const bool use2ndOrderCoriolis = false, - boost::optional deltaPij_biascorrected_out = boost::none, - boost::optional deltaVij_biascorrected_out = boost::none) const; + NavState predict(const NavState& state_i, const imuBias::ConstantBias& bias_i, + OptionalJacobian<9, 9> H1 = boost::none, + OptionalJacobian<9, 6> H2 = boost::none) const; + + /// Calculate error given navStates + Vector9 computeError(const NavState& state_i, const NavState& state_j, + const imuBias::ConstantBias& bias_i, + OptionalJacobian<9, 9> H1, OptionalJacobian<9, 9> H2, + OptionalJacobian<9, 6> H3) const; /// Compute errors w.r.t. preintegrated measurements and jacobians wrt pose_i, vel_i, bias_i, pose_j, bias_j - Vector9 computeErrorAndJacobians(const Pose3& pose_i, const Vector3& vel_i, const Pose3& pose_j, - const Vector3& vel_j, const imuBias::ConstantBias& bias_i, - const Vector3& gravity, const Vector3& omegaCoriolis, - const bool use2ndOrderCoriolis, OptionalJacobian<9, 6> H1 = - boost::none, - OptionalJacobian<9, 3> H2 = boost::none, - OptionalJacobian<9, 6> H3 = boost::none, - OptionalJacobian<9, 3> H4 = boost::none, - OptionalJacobian<9, 6> H5 = boost::none) const; + Vector9 computeErrorAndJacobians(const Pose3& pose_i, const Vector3& vel_i, + const Pose3& pose_j, const Vector3& vel_j, + const imuBias::ConstantBias& bias_i, OptionalJacobian<9, 6> H1 = + boost::none, OptionalJacobian<9, 3> H2 = boost::none, + OptionalJacobian<9, 6> H3 = boost::none, OptionalJacobian<9, 3> H4 = + boost::none, OptionalJacobian<9, 6> H5 = boost::none) const; - private: + // Compose the two preintegrated vectors + static Vector9 Compose(const Vector9& zeta01, const Vector9& zeta12, + double deltaT12, + OptionalJacobian<9, 9> H1 = boost::none, + OptionalJacobian<9, 9> H2 = boost::none); + + /// Merge in a different set of measurements and update bias derivatives accordingly + /// The derivatives apply to the preintegrated Vector9 + void mergeWith(const PreintegrationBase& pim, Matrix9* H1, Matrix9* H2); + /// @} + + /** Dummy clone for MATLAB */ + virtual boost::shared_ptr clone() const { + return boost::shared_ptr(); + } + + +#ifdef GTSAM_ALLOW_DEPRECATED_SINCE_V4 + /// @name Deprecated + /// @{ + + /// @deprecated predict + PoseVelocityBias predict(const Pose3& pose_i, const Vector3& vel_i, + const imuBias::ConstantBias& bias_i, const Vector3& n_gravity, + const Vector3& omegaCoriolis, const bool use2ndOrderCoriolis = false) const; + + /// @} +#endif + +private: /** Serialization function */ friend class boost::serialization::access; template void serialize(ARCHIVE & ar, const unsigned int /*version*/) { - ar & BOOST_SERIALIZATION_BASE_OBJECT_NVP(PreintegratedRotation); + namespace bs = ::boost::serialization; + ar & BOOST_SERIALIZATION_NVP(p_); ar & BOOST_SERIALIZATION_NVP(biasHat_); - ar & BOOST_SERIALIZATION_NVP(deltaPij_); - ar & BOOST_SERIALIZATION_NVP(deltaVij_); - ar & BOOST_SERIALIZATION_NVP(delPdelBiasAcc_); - ar & BOOST_SERIALIZATION_NVP(delPdelBiasOmega_); - ar & BOOST_SERIALIZATION_NVP(delVdelBiasAcc_); - ar & BOOST_SERIALIZATION_NVP(delVdelBiasOmega_); + ar & BOOST_SERIALIZATION_NVP(deltaTij_); + ar & bs::make_nvp("preintegrated_", bs::make_array(preintegrated_.data(), preintegrated_.size())); + ar & bs::make_nvp("preintegrated_H_biasAcc_", bs::make_array(preintegrated_H_biasAcc_.data(), preintegrated_H_biasAcc_.size())); + ar & bs::make_nvp("preintegrated_H_biasOmega_", bs::make_array(preintegrated_H_biasOmega_.data(), preintegrated_H_biasOmega_.size())); } }; -class ImuBase { - - protected: - - Vector3 gravity_; - Vector3 omegaCoriolis_; - boost::optional body_P_sensor_; ///< The pose of the sensor in the body frame - bool use2ndOrderCoriolis_; ///< Controls whether higher order terms are included when calculating the Coriolis Effect - - public: - - /// Default constructor, with decent gravity and zero coriolis - ImuBase(); - - /// Fully fledge constructor - ImuBase(const Vector3& gravity, const Vector3& omegaCoriolis, - boost::optional body_P_sensor = boost::none, - const bool use2ndOrderCoriolis = false); - - const Vector3& gravity() const { - return gravity_; - } - const Vector3& omegaCoriolis() const { - return omegaCoriolis_; - } - -}; - -} /// namespace gtsam +} /// namespace gtsam diff --git a/gtsam/navigation/PreintegrationParams.cpp b/gtsam/navigation/PreintegrationParams.cpp new file mode 100644 index 000000000..61cd1617c --- /dev/null +++ b/gtsam/navigation/PreintegrationParams.cpp @@ -0,0 +1,54 @@ +/* ---------------------------------------------------------------------------- + + * 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 PreintegrationParams.h + * @author Luca Carlone + * @author Stephen Williams + * @author Richard Roberts + * @author Vadim Indelman + * @author David Jensen + * @author Frank Dellaert + **/ + +#include "PreintegrationParams.h" + +using namespace std; + +namespace gtsam { + +//------------------------------------------------------------------------------ +void PreintegrationParams::print(const string& s) const { + PreintegratedRotation::Params::print(s); + cout << "accelerometerCovariance:\n[\n" << accelerometerCovariance << "\n]" + << endl; + cout << "integrationCovariance:\n[\n" << integrationCovariance << "\n]" + << endl; + if (omegaCoriolis && use2ndOrderCoriolis) + cout << "Using 2nd-order Coriolis" << endl; + if (body_P_sensor) body_P_sensor->print(" "); + cout << "n_gravity = (" << n_gravity.transpose() << ")" << endl; +} + +//------------------------------------------------------------------------------ +bool PreintegrationParams::equals(const PreintegratedRotation::Params& other, + double tol) const { + auto e = dynamic_cast(&other); + return e != nullptr && PreintegratedRotation::Params::equals(other, tol) && + use2ndOrderCoriolis == e->use2ndOrderCoriolis && + equal_with_abs_tol(accelerometerCovariance, e->accelerometerCovariance, + tol) && + equal_with_abs_tol(integrationCovariance, e->integrationCovariance, + tol) && + equal_with_abs_tol(n_gravity, e->n_gravity, tol); +} + +} // namespace gtsam diff --git a/gtsam/navigation/PreintegrationParams.h b/gtsam/navigation/PreintegrationParams.h new file mode 100644 index 000000000..f68f711f1 --- /dev/null +++ b/gtsam/navigation/PreintegrationParams.h @@ -0,0 +1,71 @@ +/* ---------------------------------------------------------------------------- + + * 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 PreintegrationParams.h + * @author Frank Dellaert + **/ + +#pragma once + +#include +#include + +namespace gtsam { + +/// Parameters for pre-integration: +/// Usage: Create just a single Params and pass a shared pointer to the constructor +struct PreintegrationParams: PreintegratedRotation::Params { + Matrix3 accelerometerCovariance; ///< continuous-time "Covariance" of accelerometer + Matrix3 integrationCovariance; ///< continuous-time "Covariance" describing integration uncertainty + bool use2ndOrderCoriolis; ///< Whether to use second order Coriolis integration + Vector3 n_gravity; ///< Gravity vector in nav frame + + /// The Params constructor insists on getting the navigation frame gravity vector + /// For convenience, two commonly used conventions are provided by named constructors below + PreintegrationParams(const Vector3& n_gravity) + : accelerometerCovariance(I_3x3), + integrationCovariance(I_3x3), + use2ndOrderCoriolis(false), + n_gravity(n_gravity) {} + + // Default Params for a Z-down navigation frame, such as NED: gravity points along positive Z-axis + static boost::shared_ptr MakeSharedD(double g = 9.81) { + return boost::make_shared(Vector3(0, 0, g)); + } + + // Default Params for a Z-up navigation frame, such as ENU: gravity points along negative Z-axis + static boost::shared_ptr MakeSharedU(double g = 9.81) { + return boost::make_shared(Vector3(0, 0, -g)); + } + + void print(const std::string& s) const; + bool equals(const PreintegratedRotation::Params& other, double tol) const; + +protected: + /// Default constructor for serialization only: uninitialized! + PreintegrationParams() {} + + /** Serialization function */ + friend class boost::serialization::access; + template + void serialize(ARCHIVE & ar, const unsigned int /*version*/) { + namespace bs = ::boost::serialization; + ar & boost::serialization::make_nvp("PreintegratedRotation_Params", + boost::serialization::base_object(*this)); + ar & bs::make_nvp("accelerometerCovariance", bs::make_array(accelerometerCovariance.data(), accelerometerCovariance.size())); + ar & bs::make_nvp("integrationCovariance", bs::make_array(integrationCovariance.data(), integrationCovariance.size())); + ar & BOOST_SERIALIZATION_NVP(use2ndOrderCoriolis); + ar & BOOST_SERIALIZATION_NVP(n_gravity); + } +}; + +} // namespace gtsam diff --git a/gtsam/navigation/Scenario.h b/gtsam/navigation/Scenario.h new file mode 100644 index 000000000..ad684f5f8 --- /dev/null +++ b/gtsam/navigation/Scenario.h @@ -0,0 +1,97 @@ +/* ---------------------------------------------------------------------------- + + * 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 Scenario.h + * @brief Simple class to test navigation scenarios + * @author Frank Dellaert + */ + +#pragma once +#include +#include + +namespace gtsam { + +/// Simple trajectory simulator. +class Scenario { + public: + // Quantities a Scenario needs to specify: + + virtual Pose3 pose(double t) const = 0; + virtual Vector3 omega_b(double t) const = 0; + virtual Vector3 velocity_n(double t) const = 0; + virtual Vector3 acceleration_n(double t) const = 0; + + // Derived quantities: + + Rot3 rotation(double t) const { return pose(t).rotation(); } + NavState navState(double t) const { return NavState(pose(t), velocity_n(t)); } + + Vector3 velocity_b(double t) const { + const Rot3 nRb = rotation(t); + return nRb.transpose() * velocity_n(t); + } + + Vector3 acceleration_b(double t) const { + const Rot3 nRb = rotation(t); + return nRb.transpose() * acceleration_n(t); + } +}; + +/** + * Scenario with constant twist 3D trajectory. + * Note that a plane flying level does not feel any acceleration: gravity is + * being perfectly compensated by the lift generated by the wings, and drag is + * compensated by thrust. The accelerometer will add the gravity component back + * in, as modeled by the specificForce method in ScenarioRunner. + */ +class ConstantTwistScenario : public Scenario { + public: + /// Construct scenario with constant twist [w,v] + ConstantTwistScenario(const Vector3& w, const Vector3& v) + : twist_((Vector6() << w, v).finished()), a_b_(w.cross(v)) {} + + Pose3 pose(double t) const override { return Pose3::Expmap(twist_ * t); } + Vector3 omega_b(double t) const override { return twist_.head<3>(); } + Vector3 velocity_n(double t) const override { + return rotation(t).matrix() * twist_.tail<3>(); + } + Vector3 acceleration_n(double t) const override { return rotation(t) * a_b_; } + + private: + const Vector6 twist_; + const Vector3 a_b_; // constant centripetal acceleration in body = w_b * v_b +}; + +/// Accelerating from an arbitrary initial state, with optional rotation +class AcceleratingScenario : public Scenario { + public: + /// Construct scenario with constant acceleration in navigation frame and + /// optional angular velocity in body: rotating while translating... + AcceleratingScenario(const Rot3& nRb, const Point3& p0, const Vector3& v0, + const Vector3& a_n, + const Vector3& omega_b = Vector3::Zero()) + : nRb_(nRb), p0_(p0.vector()), v0_(v0), a_n_(a_n), omega_b_(omega_b) {} + + Pose3 pose(double t) const override { + return Pose3(nRb_.expmap(omega_b_ * t), p0_ + v0_ * t + a_n_ * t * t / 2.0); + } + Vector3 omega_b(double t) const override { return omega_b_; } + Vector3 velocity_n(double t) const override { return v0_ + a_n_ * t; } + Vector3 acceleration_n(double t) const override { return a_n_; } + + private: + const Rot3 nRb_; + const Vector3 p0_, v0_, a_n_, omega_b_; +}; + +} // namespace gtsam diff --git a/gtsam/navigation/ScenarioRunner.cpp b/gtsam/navigation/ScenarioRunner.cpp new file mode 100644 index 000000000..79f3f42cc --- /dev/null +++ b/gtsam/navigation/ScenarioRunner.cpp @@ -0,0 +1,107 @@ +/* ---------------------------------------------------------------------------- + + * 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 ScenarioRunner.h + * @brief Simple class to test navigation scenarios + * @author Frank Dellaert + */ + +#include +#include + +#include +#include + +using namespace std; +using namespace boost::assign; + +namespace gtsam { + +static double intNoiseVar = 0.0000001; +static const Matrix3 kIntegrationErrorCovariance = intNoiseVar * I_3x3; + +PreintegratedImuMeasurements ScenarioRunner::integrate( + double T, const Bias& estimatedBias, bool corrupted) const { + PreintegratedImuMeasurements pim(p_, estimatedBias); + + const double dt = imuSampleTime(); + const size_t nrSteps = T / dt; + double t = 0; + for (size_t k = 0; k < nrSteps; k++, t += dt) { + Vector3 measuredOmega = + corrupted ? measuredAngularVelocity(t) : actualAngularVelocity(t); + Vector3 measuredAcc = + corrupted ? measuredSpecificForce(t) : actualSpecificForce(t); + pim.integrateMeasurement(measuredAcc, measuredOmega, dt); + } + + return pim; +} + +NavState ScenarioRunner::predict(const PreintegratedImuMeasurements& pim, + const Bias& estimatedBias) const { + const NavState state_i(scenario_->pose(0), scenario_->velocity_n(0)); + return pim.predict(state_i, estimatedBias); +} + +Matrix9 ScenarioRunner::estimateCovariance(double T, size_t N, + const Bias& estimatedBias) const { + gttic_(estimateCovariance); + + // Get predict prediction from ground truth measurements + NavState prediction = predict(integrate(T)); + + // Sample ! + Matrix samples(9, N); + Vector9 sum = Vector9::Zero(); + for (size_t i = 0; i < N; i++) { + auto pim = integrate(T, estimatedBias, true); + NavState sampled = predict(pim); + Vector9 xi = sampled.localCoordinates(prediction); + samples.col(i) = xi; + sum += xi; + } + + // Compute MC covariance + Vector9 sampleMean = sum / N; + Matrix9 Q; + Q.setZero(); + for (size_t i = 0; i < N; i++) { + Vector9 xi = samples.col(i) - sampleMean; + Q += xi * xi.transpose(); + } + + return Q / (N - 1); +} + +Matrix6 ScenarioRunner::estimateNoiseCovariance(size_t N) const { + Matrix samples(6, N); + Vector6 sum = Vector6::Zero(); + for (size_t i = 0; i < N; i++) { + samples.col(i) << accSampler_.sample() / sqrt_dt_, + gyroSampler_.sample() / sqrt_dt_; + sum += samples.col(i); + } + + // Compute MC covariance + Vector6 sampleMean = sum / N; + Matrix6 Q; + Q.setZero(); + for (size_t i = 0; i < N; i++) { + Vector6 xi = samples.col(i) - sampleMean; + Q += xi * xi.transpose(); + } + + return Q / (N - 1); +} + +} // namespace gtsam diff --git a/gtsam/navigation/ScenarioRunner.h b/gtsam/navigation/ScenarioRunner.h new file mode 100644 index 000000000..b038a831b --- /dev/null +++ b/gtsam/navigation/ScenarioRunner.h @@ -0,0 +1,109 @@ +/* ---------------------------------------------------------------------------- + + * 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 ScenarioRunner.h + * @brief Simple class to test navigation scenarios + * @author Frank Dellaert + */ + +#pragma once +#include +#include +#include + +namespace gtsam { + +// Convert covariance to diagonal noise model, if possible, otherwise throw +static noiseModel::Diagonal::shared_ptr Diagonal(const Matrix& covariance) { + bool smart = true; + auto model = noiseModel::Gaussian::Covariance(covariance, smart); + auto diagonal = boost::dynamic_pointer_cast(model); + if (!diagonal) + throw std::invalid_argument("ScenarioRunner::Diagonal: not a diagonal"); + return diagonal; +} + +/* + * Simple class to test navigation scenarios. + * Takes a trajectory scenario as input, and can generate IMU measurements + */ +class ScenarioRunner { + public: + typedef imuBias::ConstantBias Bias; + typedef boost::shared_ptr SharedParams; + + private: + const Scenario* scenario_; + const SharedParams p_; + const double imuSampleTime_, sqrt_dt_; + const Bias estimatedBias_; + + // Create two samplers for acceleration and omega noise + mutable Sampler gyroSampler_, accSampler_; + + public: + ScenarioRunner(const Scenario* scenario, const SharedParams& p, + double imuSampleTime = 1.0 / 100.0, const Bias& bias = Bias()) + : scenario_(scenario), + p_(p), + imuSampleTime_(imuSampleTime), + sqrt_dt_(std::sqrt(imuSampleTime)), + estimatedBias_(bias), + // NOTE(duy): random seeds that work well: + gyroSampler_(Diagonal(p->gyroscopeCovariance), 10), + accSampler_(Diagonal(p->accelerometerCovariance), 29284) {} + + // NOTE(frank): hardcoded for now with Z up (gravity points in negative Z) + // also, uses g=10 for easy debugging + const Vector3& gravity_n() const { return p_->n_gravity; } + + // A gyro simply measures angular velocity in body frame + Vector3 actualAngularVelocity(double t) const { + return scenario_->omega_b(t); + } + + // An accelerometer measures acceleration in body, but not gravity + Vector3 actualSpecificForce(double t) const { + Rot3 bRn = scenario_->rotation(t).transpose(); + return scenario_->acceleration_b(t) - bRn * gravity_n(); + } + + // versions corrupted by bias and noise + Vector3 measuredAngularVelocity(double t) const { + return actualAngularVelocity(t) + estimatedBias_.gyroscope() + + gyroSampler_.sample() / sqrt_dt_; + } + Vector3 measuredSpecificForce(double t) const { + return actualSpecificForce(t) + estimatedBias_.accelerometer() + + accSampler_.sample() / sqrt_dt_; + } + + const double& imuSampleTime() const { return imuSampleTime_; } + + /// Integrate measurements for T seconds into a PIM + PreintegratedImuMeasurements integrate(double T, + const Bias& estimatedBias = Bias(), + bool corrupted = false) const; + + /// Predict predict given a PIM + NavState predict(const PreintegratedImuMeasurements& pim, + const Bias& estimatedBias = Bias()) const; + + /// Compute a Monte Carlo estimate of the predict covariance using N samples + Matrix9 estimateCovariance(double T, size_t N = 1000, + const Bias& estimatedBias = Bias()) const; + + /// Estimate covariance of sampled noise for sanity-check + Matrix6 estimateNoiseCovariance(size_t N = 1000) const; +}; + +} // namespace gtsam diff --git a/gtsam/navigation/tests/imuFactorTesting.h b/gtsam/navigation/tests/imuFactorTesting.h new file mode 100644 index 000000000..3247b56ee --- /dev/null +++ b/gtsam/navigation/tests/imuFactorTesting.h @@ -0,0 +1,76 @@ +/* ---------------------------------------------------------------------------- + + * 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 imuFactorTesting.h + * @brief Common testing infrastructure + * @author Frank Dellaert + */ + +#pragma once + +#include +#include + +using namespace std; +using namespace gtsam; + +// Convenience for named keys +using symbol_shorthand::X; +using symbol_shorthand::V; +using symbol_shorthand::B; + +typedef imuBias::ConstantBias Bias; +static const Vector3 Z_3x1 = Vector3::Zero(); +static const Bias kZeroBiasHat, kZeroBias; + +static const Vector3 kZeroOmegaCoriolis(0, 0, 0); +static const Vector3 kNonZeroOmegaCoriolis(0, 0.1, 0.1); + +static const double kGravity = 10; +static const Vector3 kGravityAlongNavZDown(0, 0, kGravity); + +// Realistic MEMS white noise characteristics. Angular and velocity random walk +// expressed in degrees respectively m/s per sqrt(hr). +auto radians = [](double t) { return t * M_PI / 180; }; +static const double kGyroSigma = radians(0.5) / 60; // 0.5 degree ARW +static const double kAccelSigma = 0.1 / 60; // 10 cm VRW + +namespace testing { + +struct ImuMeasurement { + ImuMeasurement(const Vector3& acc, const Vector3& gyro, double dt) + : acc(acc), gyro(gyro), dt(dt) {} + const Vector3 acc, gyro; + const double dt; +}; + +template +void integrateMeasurements(const vector& measurements, + PIM* pim) { + for (const auto& m : measurements) + pim->integrateMeasurement(m.acc, m.gyro, m.dt); +} + +struct SomeMeasurements : vector { + SomeMeasurements() { + reserve(102); + const double dt = 0.01, pi100 = M_PI / 100; + emplace_back(Vector3(0.1, 0, 0), Vector3(pi100, 0, 0), dt); + emplace_back(Vector3(0.1, 0, 0), Vector3(pi100, 0, 0), dt); + for (int i = 1; i < 100; i++) { + emplace_back(Vector3(0.05, 0.09, 0.01), + Vector3(pi100, pi100 * 3, 2 * pi100), dt); + } + } +}; + +} // namespace testing diff --git a/gtsam/navigation/tests/testAHRSFactor.cpp b/gtsam/navigation/tests/testAHRSFactor.cpp index 928c0f74f..02911acb1 100644 --- a/gtsam/navigation/tests/testAHRSFactor.cpp +++ b/gtsam/navigation/tests/testAHRSFactor.cpp @@ -35,6 +35,12 @@ using symbol_shorthand::X; using symbol_shorthand::V; using symbol_shorthand::B; +Vector3 kZeroOmegaCoriolis(0,0,0); + +// Define covariance matrices +double accNoiseVar = 0.01; +const Matrix3 kMeasuredAccCovariance = accNoiseVar * I_3x3; + //****************************************************************************** namespace { Vector callEvaluateError(const AHRSFactor& factor, const Rot3 rot_i, @@ -50,8 +56,8 @@ Rot3 evaluateRotationError(const AHRSFactor& factor, const Rot3 rot_i, AHRSFactor::PreintegratedMeasurements evaluatePreintegratedMeasurements( const Vector3& bias, const list& measuredOmegas, const list& deltaTs, - const Vector3& initialRotationRate = Vector3()) { - AHRSFactor::PreintegratedMeasurements result(bias, Matrix3::Identity()); + const Vector3& initialRotationRate = Vector3::Zero()) { + AHRSFactor::PreintegratedMeasurements result(bias, I_3x3); list::const_iterator itOmega = measuredOmegas.begin(); list::const_iterator itDeltaT = deltaTs.begin(); @@ -95,7 +101,7 @@ TEST( AHRSFactor, PreintegratedMeasurements ) { double expectedDeltaT1(0.5); // Actual preintegrated values - AHRSFactor::PreintegratedMeasurements actual1(bias, Matrix3::Zero()); + AHRSFactor::PreintegratedMeasurements actual1(bias, Z_3x3); actual1.integrateMeasurement(measuredOmega, deltaT); EXPECT(assert_equal(expectedDeltaR1, Rot3(actual1.deltaRij()), 1e-6)); @@ -121,18 +127,14 @@ TEST(AHRSFactor, Error) { Rot3 x2(Rot3::RzRyRx(M_PI / 12.0 + M_PI / 100.0, M_PI / 6.0, M_PI / 4.0)); // Measurements - Vector3 gravity; - gravity << 0, 0, 9.81; - Vector3 omegaCoriolis; - omegaCoriolis << 0, 0, 0; Vector3 measuredOmega; measuredOmega << M_PI / 100, 0, 0; double deltaT = 1.0; - AHRSFactor::PreintegratedMeasurements pre_int_data(bias, Matrix3::Zero()); - pre_int_data.integrateMeasurement(measuredOmega, deltaT); + AHRSFactor::PreintegratedMeasurements pim(bias, Z_3x3); + pim.integrateMeasurement(measuredOmega, deltaT); // Create factor - AHRSFactor factor(X(1), X(2), B(1), pre_int_data, omegaCoriolis, boost::none); + AHRSFactor factor(X(1), X(2), B(1), pim, kZeroOmegaCoriolis, boost::none); Vector3 errorActual = factor.evaluateError(x1, x2, bias); @@ -182,18 +184,16 @@ TEST(AHRSFactor, ErrorWithBiases) { Rot3 x2(Rot3::Expmap(Vector3(0, 0, M_PI / 4.0 + M_PI / 10.0))); // Measurements - Vector3 omegaCoriolis; - omegaCoriolis << 0, 0.0, 0.0; Vector3 measuredOmega; measuredOmega << 0, 0, M_PI / 10.0 + 0.3; double deltaT = 1.0; - AHRSFactor::PreintegratedMeasurements pre_int_data(Vector3(0,0,0), - Matrix3::Zero()); - pre_int_data.integrateMeasurement(measuredOmega, deltaT); + AHRSFactor::PreintegratedMeasurements pim(Vector3(0,0,0), + Z_3x3); + pim.integrateMeasurement(measuredOmega, deltaT); // Create factor - AHRSFactor factor(X(1), X(2), B(1), pre_int_data, omegaCoriolis); + AHRSFactor factor(X(1), X(2), B(1), pim, kZeroOmegaCoriolis); Vector errorActual = factor.evaluateError(x1, x2, bias); @@ -269,7 +269,7 @@ TEST( AHRSFactor, PartialDerivativeLogmap ) { const Vector3 x = thetahat; // parametrization of so(3) const Matrix3 X = skewSymmetric(x); // element of Lie algebra so(3): X = x^ double normx = norm_2(x); - const Matrix3 actualDelFdeltheta = Matrix3::Identity() + 0.5 * X + const Matrix3 actualDelFdeltheta = I_3x3 + 0.5 * X + (1 / (normx * normx) - (1 + cos(normx)) / (2 * normx * sin(normx))) * X * X; @@ -359,8 +359,6 @@ TEST( AHRSFactor, ErrorWithBiasesAndSensorBodyDisplacement ) { Rot3 x2(Rot3::Expmap(Vector3(0, 0, M_PI / 4.0 + M_PI / 10.0))); // Measurements - Vector3 gravity; - gravity << 0, 0, 9.81; Vector3 omegaCoriolis; omegaCoriolis << 0, 0.1, 0.1; Vector3 measuredOmega; @@ -370,13 +368,15 @@ TEST( AHRSFactor, ErrorWithBiasesAndSensorBodyDisplacement ) { const Pose3 body_P_sensor(Rot3::Expmap(Vector3(0, 0.10, 0.10)), Point3(1, 0, 0)); - AHRSFactor::PreintegratedMeasurements pre_int_data(Vector3::Zero(), - Matrix3::Zero()); + AHRSFactor::PreintegratedMeasurements pim(Vector3::Zero(), kMeasuredAccCovariance); - pre_int_data.integrateMeasurement(measuredOmega, deltaT); + pim.integrateMeasurement(measuredOmega, deltaT); + + // Check preintegrated covariance + EXPECT(assert_equal(kMeasuredAccCovariance, pim.preintMeasCov())); // Create factor - AHRSFactor factor(X(1), X(2), B(1), pre_int_data, omegaCoriolis); + AHRSFactor factor(X(1), X(2), B(1), pim, omegaCoriolis); // Expected Jacobians Matrix H1e = numericalDerivative11( @@ -407,34 +407,35 @@ TEST (AHRSFactor, predictTest) { Vector3 bias(0,0,0); // Measurements - Vector3 gravity; - gravity << 0, 0, 9.81; - Vector3 omegaCoriolis; - omegaCoriolis << 0, 0.0, 0.0; Vector3 measuredOmega; measuredOmega << 0, 0, M_PI / 10.0; - double deltaT = 0.001; - AHRSFactor::PreintegratedMeasurements pre_int_data(bias, Matrix3::Zero()); + double deltaT = 0.2; + AHRSFactor::PreintegratedMeasurements pim(bias, kMeasuredAccCovariance); for (int i = 0; i < 1000; ++i) { - pre_int_data.integrateMeasurement(measuredOmega, deltaT); + pim.integrateMeasurement(measuredOmega, deltaT); } - AHRSFactor factor(X(1), X(2), B(1), pre_int_data, omegaCoriolis); + // Check preintegrated covariance + Matrix expectedMeasCov(3,3); + expectedMeasCov = 200*kMeasuredAccCovariance; + EXPECT(assert_equal(expectedMeasCov, pim.preintMeasCov())); + + AHRSFactor factor(X(1), X(2), B(1), pim, kZeroOmegaCoriolis); // Predict Rot3 x; - Rot3 expectedRot = Rot3().ypr(M_PI / 10, 0, 0); - Rot3 actualRot = factor.predict(x, bias, pre_int_data, omegaCoriolis); + Rot3 expectedRot = Rot3::Ypr(20*M_PI, 0, 0); + Rot3 actualRot = factor.predict(x, bias, pim, kZeroOmegaCoriolis); EXPECT(assert_equal(expectedRot, actualRot, 1e-6)); // AHRSFactor::PreintegratedMeasurements::predict Matrix expectedH = numericalDerivative11( boost::bind(&AHRSFactor::PreintegratedMeasurements::predict, - &pre_int_data, _1, boost::none), bias); + &pim, _1, boost::none), bias); // Actual Jacobians Matrix H; - (void) pre_int_data.predict(bias,H); - EXPECT(assert_equal(expectedH, H)); + (void) pim.predict(bias,H); + EXPECT(assert_equal(expectedH, H, 1e-8)); } //****************************************************************************** #include @@ -448,12 +449,7 @@ TEST (AHRSFactor, graphTest) { // PreIntegrator Vector3 biasHat(0, 0, 0); - Vector3 gravity; - gravity << 0, 0, 9.81; - Vector3 omegaCoriolis; - omegaCoriolis << 0, 0, 0; - AHRSFactor::PreintegratedMeasurements pre_int_data(biasHat, - Matrix3::Identity()); + AHRSFactor::PreintegratedMeasurements pim(biasHat, kMeasuredAccCovariance); // Pre-integrate measurements Vector3 measuredOmega(0, M_PI / 20, 0); @@ -461,15 +457,15 @@ TEST (AHRSFactor, graphTest) { // Create Factor noiseModel::Base::shared_ptr model = // - noiseModel::Gaussian::Covariance(pre_int_data.preintMeasCov()); + noiseModel::Gaussian::Covariance(pim.preintMeasCov()); NonlinearFactorGraph graph; Values values; for (size_t i = 0; i < 5; ++i) { - pre_int_data.integrateMeasurement(measuredOmega, deltaT); + pim.integrateMeasurement(measuredOmega, deltaT); } - // pre_int_data.print("Pre integrated measurementes"); - AHRSFactor factor(X(1), X(2), B(1), pre_int_data, omegaCoriolis); + // pim.print("Pre integrated measurementes"); + AHRSFactor factor(X(1), X(2), B(1), pim, kZeroOmegaCoriolis); values.insert(X(1), x1); values.insert(X(2), x2); values.insert(B(1), bias); diff --git a/gtsam/navigation/tests/testCombinedImuFactor.cpp b/gtsam/navigation/tests/testCombinedImuFactor.cpp index 9fb0f939b..743fc9baf 100644 --- a/gtsam/navigation/tests/testCombinedImuFactor.cpp +++ b/gtsam/navigation/tests/testCombinedImuFactor.cpp @@ -13,8 +13,9 @@ * @file testCombinedImuFactor.cpp * @brief Unit test for Lupton-style combined IMU factor * @author Luca Carlone - * @author Stephen Williams + * @author Frank Dellaert * @author Richard Roberts + * @author Stephen Williams */ #include @@ -31,103 +32,23 @@ #include #include -using namespace std; -using namespace gtsam; +#include "imuFactorTesting.h" -// Convenience for named keys -using symbol_shorthand::X; -using symbol_shorthand::V; -using symbol_shorthand::B; - -namespace { -/* ************************************************************************* */ -// Auxiliary functions to test Jacobians F and G used for -// covariance propagation during preintegration -/* ************************************************************************* */ -Vector updatePreintegratedMeasurementsTest(const Vector3 deltaPij_old, - const Vector3& deltaVij_old, const Rot3& deltaRij_old, - const imuBias::ConstantBias& bias_old, const Vector3& correctedAcc, - const Vector3& correctedOmega, const double deltaT, - const bool use2ndOrderIntegration) { - - Matrix3 dRij = deltaRij_old.matrix(); - Vector3 temp = dRij * (correctedAcc - bias_old.accelerometer()) * deltaT; - Vector3 deltaPij_new; - if (!use2ndOrderIntegration) { - deltaPij_new = deltaPij_old + deltaVij_old * deltaT; - } else { - deltaPij_new = deltaPij_old + deltaVij_old * deltaT + 0.5 * temp * deltaT; - } - Vector3 deltaVij_new = deltaVij_old + temp; - Rot3 deltaRij_new = deltaRij_old - * Rot3::Expmap((correctedOmega - bias_old.gyroscope()) * deltaT); - Vector3 logDeltaRij_new = Rot3::Logmap(deltaRij_new); // not important any more - imuBias::ConstantBias bias_new(bias_old); - Vector result(15); - result << deltaPij_new, deltaVij_new, logDeltaRij_new, bias_new.vector(); - return result; +namespace testing { +// Create default parameters with Z-down and above noise parameters +static boost::shared_ptr Params() { + auto p = PreintegratedCombinedMeasurements::Params::MakeSharedD(kGravity); + p->gyroscopeCovariance = kGyroSigma * kGyroSigma * I_3x3; + p->accelerometerCovariance = kAccelSigma * kAccelSigma * I_3x3; + p->integrationCovariance = 0.0001 * I_3x3; + return p; } - -Rot3 updatePreintegratedMeasurementsRot(const Vector3 deltaPij_old, - const Vector3& deltaVij_old, const Rot3& deltaRij_old, - const imuBias::ConstantBias& bias_old, const Vector3& correctedAcc, - const Vector3& correctedOmega, const double deltaT, - const bool use2ndOrderIntegration) { - - Vector result = updatePreintegratedMeasurementsTest(deltaPij_old, - deltaVij_old, deltaRij_old, bias_old, correctedAcc, correctedOmega, - deltaT, use2ndOrderIntegration); - - return Rot3::Expmap(result.segment<3>(6)); -} - -// Auxiliary functions to test preintegrated Jacobians -// delPdelBiasAcc_ delPdelBiasOmega_ delVdelBiasAcc_ delVdelBiasOmega_ delRdelBiasOmega_ -/* ************************************************************************* */ -CombinedImuFactor::CombinedPreintegratedMeasurements evaluatePreintegratedMeasurements( - const imuBias::ConstantBias& bias, const list& measuredAccs, - const list& measuredOmegas, const list& deltaTs) { - CombinedImuFactor::CombinedPreintegratedMeasurements result(bias, - Matrix3::Identity(), Matrix3::Identity(), Matrix3::Identity(), - Matrix3::Identity(), Matrix3::Identity(), Matrix::Identity(6, 6), false); - - list::const_iterator itAcc = measuredAccs.begin(); - list::const_iterator itOmega = measuredOmegas.begin(); - list::const_iterator itDeltaT = deltaTs.begin(); - for (; itAcc != measuredAccs.end(); ++itAcc, ++itOmega, ++itDeltaT) { - result.integrateMeasurement(*itAcc, *itOmega, *itDeltaT); - } - return result; -} - -Vector3 evaluatePreintegratedMeasurementsPosition( - const imuBias::ConstantBias& bias, const list& measuredAccs, - const list& measuredOmegas, const list& deltaTs) { - return evaluatePreintegratedMeasurements(bias, measuredAccs, measuredOmegas, - deltaTs).deltaPij(); -} - -Vector3 evaluatePreintegratedMeasurementsVelocity( - const imuBias::ConstantBias& bias, const list& measuredAccs, - const list& measuredOmegas, const list& deltaTs) { - return evaluatePreintegratedMeasurements(bias, measuredAccs, measuredOmegas, - deltaTs).deltaVij(); -} - -Rot3 evaluatePreintegratedMeasurementsRotation( - const imuBias::ConstantBias& bias, const list& measuredAccs, - const list& measuredOmegas, const list& deltaTs) { - return Rot3( - evaluatePreintegratedMeasurements(bias, measuredAccs, measuredOmegas, - deltaTs).deltaRij()); -} - } /* ************************************************************************* */ TEST( CombinedImuFactor, PreintegratedMeasurements ) { // Linearization point - imuBias::ConstantBias bias(Vector3(0, 0, 0), Vector3(0, 0, 0)); ///< Current estimate of acceleration and angular rate biases + Bias bias(Vector3(0, 0, 0), Vector3(0, 0, 0)); ///< Current estimate of acceleration and angular rate biases // Measurements Vector3 measuredAcc(0.1, 0.0, 0.0); @@ -135,91 +56,72 @@ TEST( CombinedImuFactor, PreintegratedMeasurements ) { double deltaT = 0.5; double tol = 1e-6; + auto p = testing::Params(); + // Actual preintegrated values - ImuFactor::PreintegratedMeasurements expected1(bias, Matrix3::Zero(), - Matrix3::Zero(), Matrix3::Zero()); + PreintegratedImuMeasurements expected1(p, bias); expected1.integrateMeasurement(measuredAcc, measuredOmega, deltaT); - CombinedImuFactor::CombinedPreintegratedMeasurements actual1(bias, - Matrix3::Zero(), Matrix3::Zero(), Matrix3::Zero(), Matrix3::Zero(), - Matrix3::Zero(), Matrix::Zero(6, 6)); + PreintegratedCombinedMeasurements actual1(p, bias); actual1.integrateMeasurement(measuredAcc, measuredOmega, deltaT); - EXPECT( - assert_equal(Vector(expected1.deltaPij()), Vector(actual1.deltaPij()), - tol)); - EXPECT( - assert_equal(Vector(expected1.deltaVij()), Vector(actual1.deltaVij()), - tol)); - EXPECT( - assert_equal(Matrix(expected1.deltaRij()), Matrix(actual1.deltaRij()), - tol)); + EXPECT(assert_equal(Vector(expected1.deltaPij()), actual1.deltaPij(), tol)); + EXPECT(assert_equal(Vector(expected1.deltaVij()), actual1.deltaVij(), tol)); + EXPECT(assert_equal(expected1.deltaRij(), actual1.deltaRij(), tol)); DOUBLES_EQUAL(expected1.deltaTij(), actual1.deltaTij(), tol); } /* ************************************************************************* */ TEST( CombinedImuFactor, ErrorWithBiases ) { - imuBias::ConstantBias bias(Vector3(0.2, 0, 0), Vector3(0, 0, 0.3)); // Biases (acc, rot) - imuBias::ConstantBias bias2(Vector3(0.2, 0.2, 0), Vector3(1, 0, 0.3)); // Biases (acc, rot) + Bias bias(Vector3(0.2, 0, 0), Vector3(0, 0, 0.3)); // Biases (acc, rot) + Bias bias2(Vector3(0.2, 0.2, 0), Vector3(1, 0, 0.3)); // Biases (acc, rot) Pose3 x1(Rot3::Expmap(Vector3(0, 0, M_PI / 4.0)), Point3(5.0, 1.0, -50.0)); Vector3 v1(0.5, 0.0, 0.0); Pose3 x2(Rot3::Expmap(Vector3(0, 0, M_PI / 4.0 + M_PI / 10.0)), Point3(5.5, 1.0, -50.0)); Vector3 v2(0.5, 0.0, 0.0); + auto p = testing::Params(); + p->omegaCoriolis = Vector3(0,0.1,0.1); + PreintegratedImuMeasurements pim( + p, Bias(Vector3(0.2, 0.0, 0.0), Vector3(0.0, 0.0, 0.0))); + // Measurements - Vector3 gravity; - gravity << 0, 0, 9.81; - Vector3 omegaCoriolis; - omegaCoriolis << 0, 0.1, 0.1; Vector3 measuredOmega; measuredOmega << 0, 0, M_PI / 10.0 + 0.3; - Vector3 measuredAcc = x1.rotation().unrotate(-Point3(gravity)).vector() - + Vector3(0.2, 0.0, 0.0); + Vector3 measuredAcc = + x1.rotation().unrotate(-p->n_gravity) + Vector3(0.2, 0.0, 0.0); double deltaT = 1.0; double tol = 1e-6; - Matrix I6x6(6, 6); - I6x6 = Matrix::Identity(6, 6); + pim.integrateMeasurement(measuredAcc, measuredOmega, deltaT); - ImuFactor::PreintegratedMeasurements pre_int_data( - imuBias::ConstantBias(Vector3(0.2, 0.0, 0.0), Vector3(0.0, 0.0, 0.0)), - Matrix3::Identity(), Matrix3::Identity(), Matrix3::Identity()); + PreintegratedCombinedMeasurements combined_pim(p, + Bias(Vector3(0.2, 0.0, 0.0), Vector3(0.0, 0.0, 0.0))); - pre_int_data.integrateMeasurement(measuredAcc, measuredOmega, deltaT); - - CombinedImuFactor::CombinedPreintegratedMeasurements Combined_pre_int_data( - imuBias::ConstantBias(Vector3(0.2, 0.0, 0.0), Vector3(0.0, 0.0, 0.0)), - Matrix3::Identity(), Matrix3::Identity(), Matrix3::Identity(), - Matrix3::Identity(), 2 * Matrix3::Identity(), I6x6); - - Combined_pre_int_data.integrateMeasurement(measuredAcc, measuredOmega, - deltaT); + combined_pim.integrateMeasurement(measuredAcc, measuredOmega, deltaT); // Create factor - ImuFactor factor(X(1), V(1), X(2), V(2), B(1), pre_int_data, gravity, - omegaCoriolis); + ImuFactor imuFactor(X(1), V(1), X(2), V(2), B(1), pim); noiseModel::Gaussian::shared_ptr Combinedmodel = - noiseModel::Gaussian::Covariance(Combined_pre_int_data.preintMeasCov()); - CombinedImuFactor Combinedfactor(X(1), V(1), X(2), V(2), B(1), B(2), - Combined_pre_int_data, gravity, omegaCoriolis); + noiseModel::Gaussian::Covariance(combined_pim.preintMeasCov()); + CombinedImuFactor combinedfactor(X(1), V(1), X(2), V(2), B(1), B(2), + combined_pim); - Vector errorExpected = factor.evaluateError(x1, v1, x2, v2, bias); - - Vector errorActual = Combinedfactor.evaluateError(x1, v1, x2, v2, bias, + Vector errorExpected = imuFactor.evaluateError(x1, v1, x2, v2, bias); + Vector errorActual = combinedfactor.evaluateError(x1, v1, x2, v2, bias, bias2); - EXPECT(assert_equal(errorExpected, errorActual.head(9), tol)); // Expected Jacobians Matrix H1e, H2e, H3e, H4e, H5e; - (void) factor.evaluateError(x1, v1, x2, v2, bias, H1e, H2e, H3e, H4e, H5e); + (void) imuFactor.evaluateError(x1, v1, x2, v2, bias, H1e, H2e, H3e, H4e, H5e); // Actual Jacobians Matrix H1a, H2a, H3a, H4a, H5a, H6a; - (void) Combinedfactor.evaluateError(x1, v1, x2, v2, bias, bias2, H1a, H2a, + (void) combinedfactor.evaluateError(x1, v1, x2, v2, bias, bias2, H1a, H2a, H3a, H4a, H5a, H6a); EXPECT(assert_equal(H1e, H1a.topRows(9))); @@ -230,298 +132,75 @@ TEST( CombinedImuFactor, ErrorWithBiases ) { } /* ************************************************************************* */ -TEST( CombinedImuFactor, FirstOrderPreIntegratedMeasurements ) { - // Linearization point - imuBias::ConstantBias bias; ///< Current estimate of acceleration and rotation rate biases +TEST(CombinedImuFactor, FirstOrderPreIntegratedMeasurements) { + auto p = testing::Params(); + testing::SomeMeasurements measurements; - Pose3 body_P_sensor(Rot3::Expmap(Vector3(0, 0.1, 0.1)), Point3(1, 0, 1)); + boost::function preintegrated = + [=](const Vector3& a, const Vector3& w) { + PreintegratedImuMeasurements pim(p, Bias(a, w)); + testing::integrateMeasurements(measurements, &pim); + return pim.preintegrated(); + }; - // Measurements - list measuredAccs, measuredOmegas; - list deltaTs; - measuredAccs.push_back(Vector3(0.1, 0.0, 0.0)); - measuredOmegas.push_back(Vector3(M_PI / 100.0, 0.0, 0.0)); - deltaTs.push_back(0.01); - measuredAccs.push_back(Vector3(0.1, 0.0, 0.0)); - measuredOmegas.push_back(Vector3(M_PI / 100.0, 0.0, 0.0)); - deltaTs.push_back(0.01); - for (int i = 1; i < 100; i++) { - measuredAccs.push_back(Vector3(0.05, 0.09, 0.01)); - measuredOmegas.push_back( - Vector3(M_PI / 100.0, M_PI / 300.0, 2 * M_PI / 100.0)); - deltaTs.push_back(0.01); - } + // Actual pre-integrated values + PreintegratedCombinedMeasurements pim(p); + testing::integrateMeasurements(measurements, &pim); - // Actual preintegrated values - CombinedImuFactor::CombinedPreintegratedMeasurements preintegrated = - evaluatePreintegratedMeasurements(bias, measuredAccs, measuredOmegas, - deltaTs); - - // Compute numerical derivatives - Matrix expectedDelPdelBias = numericalDerivative11( - boost::bind(&evaluatePreintegratedMeasurementsPosition, _1, measuredAccs, - measuredOmegas, deltaTs), bias); - Matrix expectedDelPdelBiasAcc = expectedDelPdelBias.leftCols(3); - Matrix expectedDelPdelBiasOmega = expectedDelPdelBias.rightCols(3); - - Matrix expectedDelVdelBias = numericalDerivative11( - boost::bind(&evaluatePreintegratedMeasurementsVelocity, _1, measuredAccs, - measuredOmegas, deltaTs), bias); - Matrix expectedDelVdelBiasAcc = expectedDelVdelBias.leftCols(3); - Matrix expectedDelVdelBiasOmega = expectedDelVdelBias.rightCols(3); - - Matrix expectedDelRdelBias = - numericalDerivative11( - boost::bind(&evaluatePreintegratedMeasurementsRotation, _1, - measuredAccs, measuredOmegas, deltaTs), bias); - Matrix expectedDelRdelBiasAcc = expectedDelRdelBias.leftCols(3); - Matrix expectedDelRdelBiasOmega = expectedDelRdelBias.rightCols(3); - - // Compare Jacobians - EXPECT(assert_equal(expectedDelPdelBiasAcc, preintegrated.delPdelBiasAcc())); - EXPECT( - assert_equal(expectedDelPdelBiasOmega, preintegrated.delPdelBiasOmega())); - EXPECT(assert_equal(expectedDelVdelBiasAcc, preintegrated.delVdelBiasAcc())); - EXPECT( - assert_equal(expectedDelVdelBiasOmega, preintegrated.delVdelBiasOmega())); - EXPECT(assert_equal(expectedDelRdelBiasAcc, Matrix::Zero(3, 3))); - EXPECT( - assert_equal(expectedDelRdelBiasOmega, preintegrated.delRdelBiasOmega(), - 1e-3)); // 1e-3 needs to be added only when using quaternions for rotations + EXPECT(assert_equal(numericalDerivative21(preintegrated, Z_3x1, Z_3x1), + pim.preintegrated_H_biasAcc())); + EXPECT(assert_equal(numericalDerivative22(preintegrated, Z_3x1, Z_3x1), + pim.preintegrated_H_biasOmega(), 1e-3)); } /* ************************************************************************* */ TEST(CombinedImuFactor, PredictPositionAndVelocity) { - imuBias::ConstantBias bias(Vector3(0, 0.1, 0), Vector3(0, 0.1, 0)); // Biases (acc, rot) + const Bias bias(Vector3(0, 0.1, 0), Vector3(0, 0.1, 0)); // Biases (acc, rot) + + auto p = testing::Params(); // Measurements - Vector3 gravity; - gravity << 0, 0, 9.81; - Vector3 omegaCoriolis; - omegaCoriolis << 0, 0, 0; - Vector3 measuredOmega; - measuredOmega << 0, 0.1, 0; //M_PI/10.0+0.3; - Vector3 measuredAcc; - measuredAcc << 0, 1.1, -9.81; - double deltaT = 0.001; + const Vector3 measuredOmega(0, 0.1, 0); // M_PI/10.0+0.3; + const Vector3 measuredAcc(0, 1.1, -kGravity); + const double deltaT = 0.001; - Matrix I6x6(6, 6); - I6x6 = Matrix::Identity(6, 6); - - CombinedImuFactor::CombinedPreintegratedMeasurements Combined_pre_int_data( - bias, Matrix3::Identity(), Matrix3::Identity(), Matrix3::Identity(), - Matrix3::Identity(), 2 * Matrix3::Identity(), I6x6, true); + PreintegratedCombinedMeasurements pim(p, bias); for (int i = 0; i < 1000; ++i) - Combined_pre_int_data.integrateMeasurement(measuredAcc, measuredOmega, - deltaT); + pim.integrateMeasurement(measuredAcc, measuredOmega, deltaT); // Create factor - noiseModel::Gaussian::shared_ptr Combinedmodel = - noiseModel::Gaussian::Covariance(Combined_pre_int_data.preintMeasCov()); - CombinedImuFactor Combinedfactor(X(1), V(1), X(2), V(2), B(1), B(2), - Combined_pre_int_data, gravity, omegaCoriolis); + const noiseModel::Gaussian::shared_ptr combinedmodel = + noiseModel::Gaussian::Covariance(pim.preintMeasCov()); + const CombinedImuFactor Combinedfactor(X(1), V(1), X(2), V(2), B(1), B(2), pim); // Predict - Pose3 x1; - Vector3 v1(0, 0.0, 0.0); - PoseVelocityBias poseVelocityBias = Combined_pre_int_data.predict(x1, v1, - bias, gravity, omegaCoriolis); - Pose3 expectedPose(Rot3(), Point3(0, 0.5, 0)); - Vector3 expectedVelocity; - expectedVelocity << 0, 1, 0; - EXPECT(assert_equal(expectedPose, poseVelocityBias.pose)); - EXPECT( - assert_equal(Vector(expectedVelocity), Vector(poseVelocityBias.velocity))); + const NavState actual = pim.predict(NavState(), bias); + const Pose3 expectedPose(Rot3(), Point3(0, 0.5, 0)); + const Vector3 expectedVelocity(0, 1, 0); + EXPECT(assert_equal(expectedPose, actual.pose())); + EXPECT(assert_equal(Vector(expectedVelocity), Vector(actual.velocity()))); } /* ************************************************************************* */ TEST(CombinedImuFactor, PredictRotation) { - imuBias::ConstantBias bias(Vector3(0, 0, 0), Vector3(0, 0, 0)); // Biases (acc, rot) - Matrix I6x6(6, 6); - CombinedImuFactor::CombinedPreintegratedMeasurements Combined_pre_int_data( - bias, Matrix3::Identity(), Matrix3::Identity(), Matrix3::Identity(), - Matrix3::Identity(), 2 * Matrix3::Identity(), I6x6, true); - Vector3 measuredAcc; - measuredAcc << 0, 0, -9.81; - Vector3 gravity; - gravity << 0, 0, 9.81; - Vector3 omegaCoriolis; - omegaCoriolis << 0, 0, 0; - Vector3 measuredOmega; - measuredOmega << 0, 0, M_PI / 10.0; - double deltaT = 0.001; - double tol = 1e-4; + const Bias bias(Vector3(0, 0, 0), Vector3(0, 0, 0)); // Biases (acc, rot) + auto p = testing::Params(); + PreintegratedCombinedMeasurements pim(p, bias); + const Vector3 measuredAcc = - kGravityAlongNavZDown; + const Vector3 measuredOmega(0, 0, M_PI / 10.0); + const double deltaT = 0.001; + const double tol = 1e-4; for (int i = 0; i < 1000; ++i) - Combined_pre_int_data.integrateMeasurement(measuredAcc, measuredOmega, - deltaT); - CombinedImuFactor Combinedfactor(X(1), V(1), X(2), V(2), B(1), B(2), - Combined_pre_int_data, gravity, omegaCoriolis); + pim.integrateMeasurement(measuredAcc, measuredOmega, deltaT); + const CombinedImuFactor Combinedfactor(X(1), V(1), X(2), V(2), B(1), B(2), pim); // Predict - Pose3 x(Rot3().ypr(0, 0, 0), Point3(0, 0, 0)), x2; - Vector3 v(0, 0, 0), v2; - CombinedImuFactor::Predict(x, v, x2, v2, bias, - Combinedfactor.preintegratedMeasurements(), gravity, omegaCoriolis); - Pose3 expectedPose(Rot3().ypr(M_PI / 10, 0, 0), Point3(0, 0, 0)); - EXPECT(assert_equal(expectedPose, x2, tol)); -} - -/* ************************************************************************* */ -TEST( CombinedImuFactor, JacobianPreintegratedCovariancePropagation ) { - // Linearization point - imuBias::ConstantBias bias_old = imuBias::ConstantBias(); ///< Current estimate of acceleration and rotation rate biases - Pose3 body_P_sensor = Pose3(); - - // Measurements - list measuredAccs, measuredOmegas; - list deltaTs; - measuredAccs.push_back(Vector3(0.1, 0.0, 0.0)); - measuredOmegas.push_back(Vector3(M_PI / 100.0, 0.0, 0.0)); - deltaTs.push_back(0.01); - measuredAccs.push_back(Vector3(0.1, 0.0, 0.0)); - measuredOmegas.push_back(Vector3(M_PI / 100.0, 0.0, 0.0)); - deltaTs.push_back(0.01); - for (int i = 1; i < 100; i++) { - measuredAccs.push_back(Vector3(0.05, 0.09, 0.01)); - measuredOmegas.push_back( - Vector3(M_PI / 100.0, M_PI / 300.0, 2 * M_PI / 100.0)); - deltaTs.push_back(0.01); - } - // Actual preintegrated values - CombinedImuFactor::CombinedPreintegratedMeasurements preintegrated = - evaluatePreintegratedMeasurements(bias_old, measuredAccs, measuredOmegas, - deltaTs); - - // so far we only created a nontrivial linearization point for the preintegrated measurements - // Now we add a new measurement and ask for Jacobians - const Vector3 newMeasuredAcc = Vector3(0.1, 0.0, 0.0); - const Vector3 newMeasuredOmega = Vector3(M_PI / 100.0, 0.0, 0.0); - const double newDeltaT = 0.01; - const Rot3 deltaRij_old = preintegrated.deltaRij(); // before adding new measurement - const Vector3 deltaVij_old = preintegrated.deltaVij(); // before adding new measurement - const Vector3 deltaPij_old = preintegrated.deltaPij(); // before adding new measurement - - Matrix oldPreintCovariance = preintegrated.preintMeasCov(); - - Matrix Factual, Gactual; - preintegrated.integrateMeasurement(newMeasuredAcc, newMeasuredOmega, - newDeltaT, body_P_sensor, Factual, Gactual); - - bool use2ndOrderIntegration = false; - - ////////////////////////////////////////////////////////////////////////////////////////////// - // COMPUTE NUMERICAL DERIVATIVES FOR F - ////////////////////////////////////////////////////////////////////////////////////////////// - // Compute expected F wrt positions (15,3) - Matrix df_dpos = numericalDerivative11( - boost::bind(&updatePreintegratedMeasurementsTest, _1, deltaVij_old, - deltaRij_old, bias_old, newMeasuredAcc, newMeasuredOmega, newDeltaT, - use2ndOrderIntegration), deltaPij_old); - // rotation part has to be done properly, on manifold - df_dpos.block<3, 3>(6, 0) = numericalDerivative11( - boost::bind(&updatePreintegratedMeasurementsRot, _1, deltaVij_old, - deltaRij_old, bias_old, newMeasuredAcc, newMeasuredOmega, newDeltaT, - use2ndOrderIntegration), deltaPij_old); - - // Compute expected F wrt velocities (15,3) - Matrix df_dvel = numericalDerivative11( - boost::bind(&updatePreintegratedMeasurementsTest, deltaPij_old, _1, - deltaRij_old, bias_old, newMeasuredAcc, newMeasuredOmega, newDeltaT, - use2ndOrderIntegration), deltaVij_old); - // rotation part has to be done properly, on manifold - df_dvel.block<3, 3>(6, 0) = numericalDerivative11( - boost::bind(&updatePreintegratedMeasurementsRot, deltaPij_old, _1, - deltaRij_old, bias_old, newMeasuredAcc, newMeasuredOmega, newDeltaT, - use2ndOrderIntegration), deltaVij_old); - - // Compute expected F wrt angles (15,3) - Matrix df_dangle = numericalDerivative11( - boost::bind(&updatePreintegratedMeasurementsTest, deltaPij_old, - deltaVij_old, _1, bias_old, newMeasuredAcc, newMeasuredOmega, - newDeltaT, use2ndOrderIntegration), deltaRij_old); - // rotation part has to be done properly, on manifold - df_dangle.block<3, 3>(6, 0) = numericalDerivative11( - boost::bind(&updatePreintegratedMeasurementsRot, deltaPij_old, - deltaVij_old, _1, bias_old, newMeasuredAcc, newMeasuredOmega, - newDeltaT, use2ndOrderIntegration), deltaRij_old); - - // Compute expected F wrt biases (15,6) - Matrix df_dbias = numericalDerivative11( - boost::bind(&updatePreintegratedMeasurementsTest, deltaPij_old, - deltaVij_old, deltaRij_old, _1, newMeasuredAcc, newMeasuredOmega, - newDeltaT, use2ndOrderIntegration), bias_old); - // rotation part has to be done properly, on manifold - df_dbias.block<3, 6>(6, 0) = - numericalDerivative11( - boost::bind(&updatePreintegratedMeasurementsRot, deltaPij_old, - deltaVij_old, deltaRij_old, _1, newMeasuredAcc, newMeasuredOmega, - newDeltaT, use2ndOrderIntegration), bias_old); - - Matrix Fexpected(15, 15); - Fexpected << df_dpos, df_dvel, df_dangle, df_dbias; - EXPECT(assert_equal(Fexpected, Factual)); - - ////////////////////////////////////////////////////////////////////////////////////////////// - // COMPUTE NUMERICAL DERIVATIVES FOR G - ////////////////////////////////////////////////////////////////////////////////////////////// - // Compute expected G wrt integration noise - Matrix df_dintNoise(15, 3); - df_dintNoise << I_3x3 * newDeltaT, Z_3x3, Z_3x3, Z_3x3, Z_3x3; - - // Compute expected G wrt acc noise (15,3) - Matrix df_daccNoise = numericalDerivative11( - boost::bind(&updatePreintegratedMeasurementsTest, deltaPij_old, - deltaVij_old, deltaRij_old, bias_old, _1, newMeasuredOmega, newDeltaT, - use2ndOrderIntegration), newMeasuredAcc); - // rotation part has to be done properly, on manifold - df_daccNoise.block<3, 3>(6, 0) = numericalDerivative11( - boost::bind(&updatePreintegratedMeasurementsRot, deltaPij_old, - deltaVij_old, deltaRij_old, bias_old, _1, newMeasuredOmega, newDeltaT, - use2ndOrderIntegration), newMeasuredAcc); - - // Compute expected G wrt gyro noise (15,3) - Matrix df_domegaNoise = numericalDerivative11( - boost::bind(&updatePreintegratedMeasurementsTest, deltaPij_old, - deltaVij_old, deltaRij_old, bias_old, newMeasuredAcc, _1, newDeltaT, - use2ndOrderIntegration), newMeasuredOmega); - // rotation part has to be done properly, on manifold - df_domegaNoise.block<3, 3>(6, 0) = numericalDerivative11( - boost::bind(&updatePreintegratedMeasurementsRot, deltaPij_old, - deltaVij_old, deltaRij_old, bias_old, newMeasuredAcc, _1, newDeltaT, - use2ndOrderIntegration), newMeasuredOmega); - - // Compute expected G wrt bias random walk noise (15,6) - Matrix df_rwBias(15, 6); // random walk on the bias does not appear in the first 9 entries - df_rwBias.setZero(); - df_rwBias.block<6, 6>(9, 0) = eye(6); - - // Compute expected G wrt gyro noise (15,6) - Matrix df_dinitBias = numericalDerivative11( - boost::bind(&updatePreintegratedMeasurementsTest, deltaPij_old, - deltaVij_old, deltaRij_old, _1, newMeasuredAcc, newMeasuredOmega, - newDeltaT, use2ndOrderIntegration), bias_old); - // rotation part has to be done properly, on manifold - df_dinitBias.block<3, 6>(6, 0) = numericalDerivative11( - boost::bind(&updatePreintegratedMeasurementsRot, deltaPij_old, - deltaVij_old, deltaRij_old, _1, newMeasuredAcc, newMeasuredOmega, - newDeltaT, use2ndOrderIntegration), bias_old); - df_dinitBias.block<6, 6>(9, 0) = Matrix::Zero(6, 6); // only has to influence first 9 rows - - Matrix Gexpected(15, 21); - Gexpected << df_dintNoise, df_daccNoise, df_domegaNoise, df_rwBias, df_dinitBias; - - EXPECT(assert_equal(Gexpected, Gactual)); - - // Check covariance propagation - Matrix newPreintCovarianceExpected = Factual * oldPreintCovariance - * Factual.transpose() + (1 / newDeltaT) * Gactual * Gactual.transpose(); - - Matrix newPreintCovarianceActual = preintegrated.preintMeasCov(); - EXPECT(assert_equal(newPreintCovarianceExpected, newPreintCovarianceActual)); + const Pose3 x(Rot3::Ypr(0, 0, 0), Point3(0, 0, 0)), x2; + const Vector3 v(0, 0, 0), v2; + const NavState actual = pim.predict(NavState(x, v), bias); + const Pose3 expectedPose(Rot3::Ypr(M_PI / 10, 0, 0), Point3(0, 0, 0)); + EXPECT(assert_equal(expectedPose, actual.pose(), tol)); } /* ************************************************************************* */ diff --git a/gtsam/navigation/tests/testGPSFactor.cpp b/gtsam/navigation/tests/testGPSFactor.cpp index 8c93020c9..6149c1651 100644 --- a/gtsam/navigation/tests/testGPSFactor.cpp +++ b/gtsam/navigation/tests/testGPSFactor.cpp @@ -89,7 +89,7 @@ TEST(GPSData, init) { // Check values values EXPECT(assert_equal((Vector )Vector3(29.9575, -29.0564, -1.95993), nV, 1e-4)); - EXPECT( assert_equal(Rot3::ypr(-0.770131, 0.046928, 0), T.rotation(), 1e-5)); + EXPECT( assert_equal(Rot3::Ypr(-0.770131, 0.046928, 0), T.rotation(), 1e-5)); Point3 expectedT(2.38461, -2.31289, -0.156011); EXPECT(assert_equal(expectedT, T.translation(), 1e-5)); } diff --git a/gtsam/navigation/tests/testImuBias.cpp b/gtsam/navigation/tests/testImuBias.cpp index 4d5df3f05..596b76f6a 100644 --- a/gtsam/navigation/tests/testImuBias.cpp +++ b/gtsam/navigation/tests/testImuBias.cpp @@ -16,113 +16,135 @@ */ #include +#include + #include +#include using namespace std; using namespace gtsam; +typedef imuBias::ConstantBias Bias; + Vector biasAcc1(Vector3(0.2, -0.1, 0)); Vector biasGyro1(Vector3(0.1, -0.3, -0.2)); -imuBias::ConstantBias bias1(biasAcc1, biasGyro1); +Bias bias1(biasAcc1, biasGyro1); Vector biasAcc2(Vector3(0.1, 0.2, 0.04)); Vector biasGyro2(Vector3(-0.002, 0.005, 0.03)); -imuBias::ConstantBias bias2(biasAcc2, biasGyro2); +Bias bias2(biasAcc2, biasGyro2); /* ************************************************************************* */ -TEST( ImuBias, Constructor) { +TEST(ImuBias, Constructor) { // Default Constructor - imuBias::ConstantBias bias1; + Bias bias1; // Acc + Gyro Constructor - imuBias::ConstantBias bias2(biasAcc2, biasGyro2); + Bias bias2(biasAcc2, biasGyro2); // Copy Constructor - imuBias::ConstantBias bias3(bias2); + Bias bias3(bias2); } /* ************************************************************************* */ -TEST( ImuBias, inverse) { - imuBias::ConstantBias biasActual = bias1.inverse(); - imuBias::ConstantBias biasExpected = imuBias::ConstantBias(-biasAcc1, - -biasGyro1); +TEST(ImuBias, inverse) { + Bias biasActual = bias1.inverse(); + Bias biasExpected = Bias(-biasAcc1, -biasGyro1); EXPECT(assert_equal(biasExpected, biasActual)); } /* ************************************************************************* */ -TEST( ImuBias, compose) { - imuBias::ConstantBias biasActual = bias2.compose(bias1); - imuBias::ConstantBias biasExpected = imuBias::ConstantBias( - biasAcc1 + biasAcc2, biasGyro1 + biasGyro2); +TEST(ImuBias, compose) { + Bias biasActual = bias2.compose(bias1); + Bias biasExpected = Bias(biasAcc1 + biasAcc2, biasGyro1 + biasGyro2); EXPECT(assert_equal(biasExpected, biasActual)); } /* ************************************************************************* */ -TEST( ImuBias, between) { +TEST(ImuBias, between) { // p.between(q) == q - p - imuBias::ConstantBias biasActual = bias2.between(bias1); - imuBias::ConstantBias biasExpected = imuBias::ConstantBias( - biasAcc1 - biasAcc2, biasGyro1 - biasGyro2); + Bias biasActual = bias2.between(bias1); + Bias biasExpected = Bias(biasAcc1 - biasAcc2, biasGyro1 - biasGyro2); EXPECT(assert_equal(biasExpected, biasActual)); } /* ************************************************************************* */ -TEST( ImuBias, localCoordinates) { +TEST(ImuBias, localCoordinates) { Vector deltaActual = Vector(bias2.localCoordinates(bias1)); - Vector deltaExpected = (imuBias::ConstantBias(biasAcc1 - biasAcc2, - biasGyro1 - biasGyro2)).vector(); + Vector deltaExpected = + (Bias(biasAcc1 - biasAcc2, biasGyro1 - biasGyro2)).vector(); EXPECT(assert_equal(deltaExpected, deltaActual)); } /* ************************************************************************* */ -TEST( ImuBias, retract) { +TEST(ImuBias, retract) { Vector6 delta; delta << 0.1, 0.2, -0.3, 0.1, -0.1, 0.2; - imuBias::ConstantBias biasActual = bias2.retract(delta); - imuBias::ConstantBias biasExpected = imuBias::ConstantBias( - biasAcc2 + delta.block<3, 1>(0, 0), biasGyro2 + delta.block<3, 1>(3, 0)); + Bias biasActual = bias2.retract(delta); + Bias biasExpected = Bias(biasAcc2 + delta.block<3, 1>(0, 0), + biasGyro2 + delta.block<3, 1>(3, 0)); EXPECT(assert_equal(biasExpected, biasActual)); } /* ************************************************************************* */ -TEST( ImuBias, Logmap) { +TEST(ImuBias, Logmap) { Vector deltaActual = bias2.Logmap(bias1); Vector deltaExpected = bias1.vector(); EXPECT(assert_equal(deltaExpected, deltaActual)); } /* ************************************************************************* */ -TEST( ImuBias, Expmap) { +TEST(ImuBias, Expmap) { Vector6 delta; delta << 0.1, 0.2, -0.3, 0.1, -0.1, 0.2; - imuBias::ConstantBias biasActual = bias2.Expmap(delta); - imuBias::ConstantBias biasExpected = imuBias::ConstantBias(delta); + Bias biasActual = bias2.Expmap(delta); + Bias biasExpected = Bias(delta); EXPECT(assert_equal(biasExpected, biasActual)); } /* ************************************************************************* */ -TEST( ImuBias, operatorSub) { - imuBias::ConstantBias biasActual = -bias1; - imuBias::ConstantBias biasExpected(-biasAcc1, -biasGyro1); +TEST(ImuBias, operatorSub) { + Bias biasActual = -bias1; + Bias biasExpected(-biasAcc1, -biasGyro1); EXPECT(assert_equal(biasExpected, biasActual)); } /* ************************************************************************* */ -TEST( ImuBias, operatorAdd) { - imuBias::ConstantBias biasActual = bias2 + bias1; - imuBias::ConstantBias biasExpected(biasAcc2 + biasAcc1, - biasGyro2 + biasGyro1); +TEST(ImuBias, operatorAdd) { + Bias biasActual = bias2 + bias1; + Bias biasExpected(biasAcc2 + biasAcc1, biasGyro2 + biasGyro1); EXPECT(assert_equal(biasExpected, biasActual)); } /* ************************************************************************* */ -TEST( ImuBias, operatorSubB) { - imuBias::ConstantBias biasActual = bias2 - bias1; - imuBias::ConstantBias biasExpected(biasAcc2 - biasAcc1, - biasGyro2 - biasGyro1); +TEST(ImuBias, operatorSubB) { + Bias biasActual = bias2 - bias1; + Bias biasExpected(biasAcc2 - biasAcc1, biasGyro2 - biasGyro1); EXPECT(assert_equal(biasExpected, biasActual)); } +/* ************************************************************************* */ +TEST(ImuBias, Correct1) { + Matrix aH1, aH2; + const Vector3 measurement(1, 2, 3); + boost::function f = boost::bind( + &Bias::correctAccelerometer, _1, _2, boost::none, boost::none); + bias1.correctAccelerometer(measurement, aH1, aH2); + EXPECT(assert_equal(numericalDerivative21(f, bias1, measurement), aH1)); + EXPECT(assert_equal(numericalDerivative22(f, bias1, measurement), aH2)); +} + +/* ************************************************************************* */ +TEST(ImuBias, Correct2) { + Matrix aH1, aH2; + const Vector3 measurement(1, 2, 3); + boost::function f = + boost::bind(&Bias::correctGyroscope, _1, _2, boost::none, boost::none); + bias1.correctGyroscope(measurement, aH1, aH2); + EXPECT(assert_equal(numericalDerivative21(f, bias1, measurement), aH1)); + EXPECT(assert_equal(numericalDerivative22(f, bias1, measurement), aH2)); +} + /* ************************************************************************* */ int main() { TestResult tr; diff --git a/gtsam/navigation/tests/testImuFactor.cpp b/gtsam/navigation/tests/testImuFactor.cpp index c27921fc9..f1d761cb0 100644 --- a/gtsam/navigation/tests/testImuFactor.cpp +++ b/gtsam/navigation/tests/testImuFactor.cpp @@ -12,485 +12,376 @@ /** * @file testImuFactor.cpp * @brief Unit test for ImuFactor - * @author Luca Carlone, Stephen Williams, Richard Roberts + * @author Luca Carlone + * @author Frank Dellaert + * @author Richard Roberts + * @author Stephen Williams */ #include +#include +#include #include #include -#include -#include -#include +#include #include #include -#include +#include #include #include -using namespace std; -using namespace gtsam; +#include "imuFactorTesting.h" -// Convenience for named keys -using symbol_shorthand::X; -using symbol_shorthand::V; -using symbol_shorthand::B; +namespace testing { +// Create default parameters with Z-down and above noise parameters +static boost::shared_ptr Params() { + auto p = PreintegrationParams::MakeSharedD(kGravity); + p->gyroscopeCovariance = kGyroSigma * kGyroSigma * I_3x3; + p->accelerometerCovariance = kAccelSigma * kAccelSigma * I_3x3; + p->integrationCovariance = 0.0001 * I_3x3; + return p; +} +} /* ************************************************************************* */ namespace { // Auxiliary functions to test evaluate error in ImuFactor /* ************************************************************************* */ -Vector callEvaluateError(const ImuFactor& factor, const Pose3& pose_i, - const Vector3& vel_i, const Pose3& pose_j, const Vector3& vel_j, - const imuBias::ConstantBias& bias) { - return factor.evaluateError(pose_i, vel_i, pose_j, vel_j, bias); -} - Rot3 evaluateRotationError(const ImuFactor& factor, const Pose3& pose_i, const Vector3& vel_i, const Pose3& pose_j, const Vector3& vel_j, - const imuBias::ConstantBias& bias) { + const Bias& bias) { return Rot3::Expmap( - factor.evaluateError(pose_i, vel_i, pose_j, vel_j, bias).tail(3)); + factor.evaluateError(pose_i, vel_i, pose_j, vel_j, bias).head(3)); } -// Auxiliary functions to test Jacobians F and G used for -// covariance propagation during preintegration +} // namespace + /* ************************************************************************* */ -Vector updatePreintegratedPosVel(const Vector3 deltaPij_old, - const Vector3& deltaVij_old, const Rot3& deltaRij_old, - const Vector3& correctedAcc, const Vector3& correctedOmega, - const double deltaT, const bool use2ndOrderIntegration_) { +TEST(ImuFactor, Accelerating) { + const double a = 0.2, v = 50; - Matrix3 dRij = deltaRij_old.matrix(); - Vector3 temp = dRij * correctedAcc * deltaT; - Vector3 deltaPij_new; - if (!use2ndOrderIntegration_) { - deltaPij_new = deltaPij_old + deltaVij_old * deltaT; - } else { - deltaPij_new = deltaPij_old + deltaVij_old * deltaT + 0.5 * temp * deltaT; - } - Vector3 deltaVij_new = deltaVij_old + temp; + // Set up body pointing towards y axis, and start at 10,20,0 with velocity going in X + // The body itself has Z axis pointing down + const Rot3 nRb(Point3(0, 1, 0), Point3(1, 0, 0), Point3(0, 0, -1)); + const Point3 initial_position(10, 20, 0); + const Vector3 initial_velocity(v, 0, 0); - Vector result(6); - result << deltaPij_new, deltaVij_new; - return result; -} + const AcceleratingScenario scenario(nRb, initial_position, initial_velocity, + Vector3(a, 0, 0)); -Rot3 updatePreintegratedRot(const Rot3& deltaRij_old, - const Vector3& correctedOmega, const double deltaT) { - Rot3 deltaRij_new = deltaRij_old * Rot3::Expmap(correctedOmega * deltaT); - return deltaRij_new; -} + const double T = 3.0; // seconds + ScenarioRunner runner(&scenario, testing::Params(), T / 10); -// Define covariance matrices -/* ************************************************************************* */ -double accNoiseVar = 0.01; -double omegaNoiseVar = 0.03; -double intNoiseVar = 0.0001; -const Matrix3 kMeasuredAccCovariance = accNoiseVar * Matrix3::Identity(); -const Matrix3 kMeasuredOmegaCovariance = omegaNoiseVar * Matrix3::Identity(); -const Matrix3 kIntegrationErrorCovariance = intNoiseVar * Matrix3::Identity(); - -// Auxiliary functions to test preintegrated Jacobians -// delPdelBiasAcc_ delPdelBiasOmega_ delVdelBiasAcc_ delVdelBiasOmega_ delRdelBiasOmega_ -/* ************************************************************************* */ -ImuFactor::PreintegratedMeasurements evaluatePreintegratedMeasurements( - const imuBias::ConstantBias& bias, const list& measuredAccs, - const list& measuredOmegas, const list& deltaTs, - const bool use2ndOrderIntegration = false) { - ImuFactor::PreintegratedMeasurements result(bias, - kMeasuredAccCovariance, - kMeasuredOmegaCovariance, - kIntegrationErrorCovariance, - use2ndOrderIntegration); - - list::const_iterator itAcc = measuredAccs.begin(); - list::const_iterator itOmega = measuredOmegas.begin(); - list::const_iterator itDeltaT = deltaTs.begin(); - for (; itAcc != measuredAccs.end(); ++itAcc, ++itOmega, ++itDeltaT) { - result.integrateMeasurement(*itAcc, *itOmega, *itDeltaT); - } - return result; -} - -Vector3 evaluatePreintegratedMeasurementsPosition( - const imuBias::ConstantBias& bias, const list& measuredAccs, - const list& measuredOmegas, const list& deltaTs) { - return evaluatePreintegratedMeasurements(bias, measuredAccs, measuredOmegas, - deltaTs).deltaPij(); -} - -Vector3 evaluatePreintegratedMeasurementsVelocity( - const imuBias::ConstantBias& bias, const list& measuredAccs, - const list& measuredOmegas, const list& deltaTs) { - return evaluatePreintegratedMeasurements(bias, measuredAccs, measuredOmegas, - deltaTs).deltaVij(); -} - -Rot3 evaluatePreintegratedMeasurementsRotation( - const imuBias::ConstantBias& bias, const list& measuredAccs, - const list& measuredOmegas, const list& deltaTs) { - return Rot3( - evaluatePreintegratedMeasurements(bias, measuredAccs, measuredOmegas, - deltaTs).deltaRij()); -} - -Rot3 evaluateRotation(const Vector3 measuredOmega, const Vector3 biasOmega, - const double deltaT) { - return Rot3::Expmap((measuredOmega - biasOmega) * deltaT); -} - -Vector3 evaluateLogRotation(const Vector3 thetahat, const Vector3 deltatheta) { - return Rot3::Logmap(Rot3::Expmap(thetahat).compose(Rot3::Expmap(deltatheta))); -} + PreintegratedImuMeasurements pim = runner.integrate(T); + EXPECT(assert_equal(scenario.pose(T), runner.predict(pim).pose(), 1e-9)); + Matrix9 estimatedCov = runner.estimateCovariance(T); + EXPECT(assert_equal(estimatedCov, pim.preintMeasCov(), 0.1)); } /* ************************************************************************* */ -TEST( ImuFactor, PreintegratedMeasurements ) { - // Linearization point - imuBias::ConstantBias bias(Vector3(0, 0, 0), Vector3(0, 0, 0)); ///< Current estimate of acceleration and angular rate biases - +TEST(ImuFactor, PreintegratedMeasurements) { // Measurements Vector3 measuredAcc(0.1, 0.0, 0.0); Vector3 measuredOmega(M_PI / 100.0, 0.0, 0.0); double deltaT = 0.5; - // Expected preintegrated values - Vector3 expectedDeltaP1; - expectedDeltaP1 << 0.5 * 0.1 * 0.5 * 0.5, 0, 0; + // Expected pre-integrated values + Vector3 expectedDeltaR1(0.5 * M_PI / 100.0, 0.0, 0.0); + Vector3 expectedDeltaP1(0.5 * 0.1 * 0.5 * 0.5, 0, 0); Vector3 expectedDeltaV1(0.05, 0.0, 0.0); - Rot3 expectedDeltaR1 = Rot3::RzRyRx(0.5 * M_PI / 100.0, 0.0, 0.0); - double expectedDeltaT1(0.5); - bool use2ndOrderIntegration = true; - // Actual preintegrated values - ImuFactor::PreintegratedMeasurements actual1(bias, - kMeasuredAccCovariance, - kMeasuredOmegaCovariance, - kIntegrationErrorCovariance, - use2ndOrderIntegration); - actual1.integrateMeasurement(measuredAcc, measuredOmega, deltaT); + // Actual pre-integrated values + PreintegratedImuMeasurements actual(testing::Params()); + EXPECT(assert_equal(Z_3x1, actual.theta())); + EXPECT(assert_equal(Z_3x1, actual.deltaPij())); + EXPECT(assert_equal(Z_3x1, actual.deltaVij())); + DOUBLES_EQUAL(0.0, actual.deltaTij(), 1e-9); - EXPECT( - assert_equal(Vector(expectedDeltaP1), Vector(actual1.deltaPij()), 1e-6)); - EXPECT( - assert_equal(Vector(expectedDeltaV1), Vector(actual1.deltaVij()), 1e-6)); - EXPECT(assert_equal(expectedDeltaR1, Rot3(actual1.deltaRij()), 1e-6)); - DOUBLES_EQUAL(expectedDeltaT1, actual1.deltaTij(), 1e-6); + actual.integrateMeasurement(measuredAcc, measuredOmega, deltaT); + EXPECT(assert_equal(expectedDeltaR1, actual.theta())); + EXPECT(assert_equal(expectedDeltaP1, actual.deltaPij())); + EXPECT(assert_equal(expectedDeltaV1, actual.deltaVij())); + DOUBLES_EQUAL(0.5, actual.deltaTij(), 1e-9); + + // Check derivatives of computeError + Bias bias(Vector3(0.2, 0, 0), Vector3(0.1, 0, 0.3)); // Biases (acc, rot) + NavState x1, x2 = actual.predict(x1, bias); + + { + Matrix9 aH1, aH2; + Matrix96 aH3; + actual.computeError(x1, x2, bias, aH1, aH2, aH3); + boost::function f = + boost::bind(&PreintegrationBase::computeError, actual, _1, _2, _3, + boost::none, boost::none, boost::none); + EXPECT(assert_equal(numericalDerivative31(f, x1, x2, bias), aH1, 1e-9)); + EXPECT(assert_equal(numericalDerivative32(f, x1, x2, bias), aH2, 1e-9)); + EXPECT(assert_equal(numericalDerivative33(f, x1, x2, bias), aH3, 1e-9)); + } // Integrate again - Vector3 expectedDeltaP2; - expectedDeltaP2 << 0.025 + expectedDeltaP1(0) + 0.5 * 0.1 * 0.5 * 0.5, 0, 0; - Vector3 expectedDeltaV2 = Vector3(0.05, 0.0, 0.0) - + expectedDeltaR1.matrix() * measuredAcc * 0.5; - Rot3 expectedDeltaR2 = Rot3::RzRyRx(2.0 * 0.5 * M_PI / 100.0, 0.0, 0.0); - double expectedDeltaT2(1); + Vector3 expectedDeltaR2(2.0 * 0.5 * M_PI / 100.0, 0.0, 0.0); + Vector3 expectedDeltaP2(0.025 + expectedDeltaP1(0) + 0.5 * 0.1 * 0.5 * 0.5, 0, 0); + Vector3 expectedDeltaV2 = Vector3(0.05, 0.0, 0.0) + + Rot3::Expmap(expectedDeltaR1) * measuredAcc * 0.5; - // Actual preintegrated values - ImuFactor::PreintegratedMeasurements actual2 = actual1; - actual2.integrateMeasurement(measuredAcc, measuredOmega, deltaT); + // Actual pre-integrated values + actual.integrateMeasurement(measuredAcc, measuredOmega, deltaT); + EXPECT(assert_equal(expectedDeltaR2, actual.theta())); + EXPECT(assert_equal(expectedDeltaP2, actual.deltaPij())); + EXPECT(assert_equal(expectedDeltaV2, actual.deltaVij())); + DOUBLES_EQUAL(1.0, actual.deltaTij(), 1e-9); +} +/* ************************************************************************* */ +// Common linearization point and measurements for tests +namespace common { +static const Pose3 x1(Rot3::RzRyRx(M_PI / 12.0, M_PI / 6.0, M_PI / 4.0), + Point3(5.0, 1.0, 0)); +static const Vector3 v1(Vector3(0.5, 0.0, 0.0)); +static const NavState state1(x1, v1); + +// Measurements +static const double w = M_PI / 100; +static const Vector3 measuredOmega(w, 0, 0); +static const Vector3 measuredAcc = x1.rotation().unrotate( + -kGravityAlongNavZDown); +static const double deltaT = 1.0; + +static const Pose3 x2(Rot3::RzRyRx(M_PI / 12.0 + w, M_PI / 6.0, M_PI / 4.0), + Point3(5.5, 1.0, 0)); +static const Vector3 v2(Vector3(0.5, 0.0, 0.0)); +static const NavState state2(x2, v2); +} // namespace common + +/* ************************************************************************* */ +TEST(ImuFactor, PreintegrationBaseMethods) { + using namespace common; + auto p = testing::Params(); + p->omegaCoriolis = Vector3(0.02, 0.03, 0.04); + p->use2ndOrderCoriolis = true; + + PreintegratedImuMeasurements pim(p, kZeroBiasHat); + pim.integrateMeasurement(measuredAcc, measuredOmega, deltaT); + pim.integrateMeasurement(measuredAcc, measuredOmega, deltaT); + + // biasCorrectedDelta + Matrix96 actualH; + pim.biasCorrectedDelta(kZeroBias, actualH); + Matrix expectedH = numericalDerivative11( + boost::bind(&PreintegrationBase::biasCorrectedDelta, pim, _1, + boost::none), kZeroBias); + EXPECT(assert_equal(expectedH, actualH)); + + Matrix9 aH1; + Matrix96 aH2; + NavState predictedState = pim.predict(state1, kZeroBias, aH1, aH2); + Matrix eH1 = numericalDerivative11( + boost::bind(&PreintegrationBase::predict, pim, _1, kZeroBias, boost::none, + boost::none), state1); + EXPECT(assert_equal(eH1, aH1)); + Matrix eH2 = numericalDerivative11( + boost::bind(&PreintegrationBase::predict, pim, state1, _1, boost::none, + boost::none), kZeroBias); + EXPECT(assert_equal(eH2, aH2)); + return; - EXPECT( - assert_equal(Vector(expectedDeltaP2), Vector(actual2.deltaPij()), 1e-6)); - EXPECT( - assert_equal(Vector(expectedDeltaV2), Vector(actual2.deltaVij()), 1e-6)); - EXPECT(assert_equal(expectedDeltaR2, Rot3(actual2.deltaRij()), 1e-6)); - DOUBLES_EQUAL(expectedDeltaT2, actual2.deltaTij(), 1e-6); } /* ************************************************************************* */ -TEST( ImuFactor, ErrorAndJacobians ) { - // Linearization point - imuBias::ConstantBias bias; // Bias - Pose3 x1(Rot3::RzRyRx(M_PI / 12.0, M_PI / 6.0, M_PI / 4.0), - Point3(5.0, 1.0, -50.0)); - Vector3 v1(Vector3(0.5, 0.0, 0.0)); - Pose3 x2(Rot3::RzRyRx(M_PI / 12.0 + M_PI / 100.0, M_PI / 6.0, M_PI / 4.0), - Point3(5.5, 1.0, -50.0)); - Vector3 v2(Vector3(0.5, 0.0, 0.0)); +TEST(ImuFactor, ErrorAndJacobians) { + using namespace common; + PreintegratedImuMeasurements pim(testing::Params()); - // Measurements - Vector3 gravity; - gravity << 0, 0, 9.81; - Vector3 omegaCoriolis; - omegaCoriolis << 0, 0, 0; - Vector3 measuredOmega; - measuredOmega << M_PI / 100, 0, 0; - Vector3 measuredAcc = x1.rotation().unrotate(-Point3(gravity)).vector(); - double deltaT = 1.0; - bool use2ndOrderIntegration = true; - ImuFactor::PreintegratedMeasurements pre_int_data(bias, - kMeasuredAccCovariance, - kMeasuredOmegaCovariance, - kIntegrationErrorCovariance, - use2ndOrderIntegration); - pre_int_data.integrateMeasurement(measuredAcc, measuredOmega, deltaT); + pim.integrateMeasurement(measuredAcc, measuredOmega, deltaT); + EXPECT(assert_equal(state2, pim.predict(state1, kZeroBias))); // Create factor - ImuFactor factor(X(1), V(1), X(2), V(2), B(1), pre_int_data, gravity, - omegaCoriolis); - - Vector errorActual = factor.evaluateError(x1, v1, x2, v2, bias); + ImuFactor factor(X(1), V(1), X(2), V(2), B(1), pim); // Expected error - Vector errorExpected(9); - errorExpected << 0, 0, 0, 0, 0, 0, 0, 0, 0; - EXPECT(assert_equal(errorExpected, errorActual, 1e-6)); - - // Actual Jacobians - Matrix H1a, H2a, H3a, H4a, H5a; - (void) factor.evaluateError(x1, v1, x2, v2, bias, H1a, H2a, H3a, H4a, H5a); - - // Expected Jacobians - /////////////////// H1 /////////////////////////// - Matrix H1e = numericalDerivative11( - boost::bind(&callEvaluateError, factor, _1, v1, x2, v2, bias), x1); - // Jacobians are around zero, so the rotation part is the same as: - Matrix H1Rot3 = numericalDerivative11( - boost::bind(&evaluateRotationError, factor, _1, v1, x2, v2, bias), x1); - EXPECT(assert_equal(H1Rot3, H1e.bottomRows(3))); - EXPECT(assert_equal(H1e, H1a)); - - /////////////////// H2 /////////////////////////// - Matrix H2e = numericalDerivative11( - boost::bind(&callEvaluateError, factor, x1, _1, x2, v2, bias), v1); - EXPECT(assert_equal(H2e, H2a)); - - /////////////////// H3 /////////////////////////// - Matrix H3e = numericalDerivative11( - boost::bind(&callEvaluateError, factor, x1, v1, _1, v2, bias), x2); - // Jacobians are around zero, so the rotation part is the same as: - Matrix H3Rot3 = numericalDerivative11( - boost::bind(&evaluateRotationError, factor, x1, v1, _1, v2, bias), x2); - EXPECT(assert_equal(H3Rot3, H3e.bottomRows(3))); - EXPECT(assert_equal(H3e, H3a)); - - /////////////////// H4 /////////////////////////// - Matrix H4e = numericalDerivative11( - boost::bind(&callEvaluateError, factor, x1, v1, x2, _1, bias), v2); - EXPECT(assert_equal(H4e, H4a)); - - /////////////////// H5 /////////////////////////// - Matrix H5e = numericalDerivative11( - boost::bind(&callEvaluateError, factor, x1, v1, x2, v2, _1), bias); - EXPECT(assert_equal(H5e, H5a)); - - //////////////////////////////////////////////////////////////////////////// - // Evaluate error with wrong values - Vector3 v2_wrong = v2 + Vector3(0.1, 0.1, 0.1); - errorActual = factor.evaluateError(x1, v1, x2, v2_wrong, bias); - errorExpected << 0, 0, 0, 0.0724744871, 0.040715657, 0.151952901, 0, 0, 0; - EXPECT(assert_equal(errorExpected, errorActual, 1e-6)); + Vector expectedError(9); + expectedError << 0, 0, 0, 0, 0, 0, 0, 0, 0; + EXPECT( + assert_equal(expectedError, + factor.evaluateError(x1, v1, x2, v2, kZeroBias))); Values values; values.insert(X(1), x1); values.insert(V(1), v1); values.insert(X(2), x2); - values.insert(V(2), v2_wrong); - values.insert(B(1), bias); - errorExpected << 0, 0, 0, 0.0724744871, 0.040715657, 0.151952901, 0, 0, 0; - EXPECT(assert_equal(factor.unwhitenedError(values), errorActual, 1e-6)); + values.insert(V(2), v2); + values.insert(B(1), kZeroBias); + EXPECT(assert_equal(expectedError, factor.unwhitenedError(values))); + + // Make sure linearization is correct + double diffDelta = 1e-7; + EXPECT_CORRECT_FACTOR_JACOBIANS(factor, values, diffDelta, 1e-3); + + // Actual Jacobians + Matrix H1a, H2a, H3a, H4a, H5a; + (void) factor.evaluateError(x1, v1, x2, v2, kZeroBias, H1a, H2a, H3a, H4a, + H5a); + + // Make sure rotation part is correct when error is interpreted as axis-angle + // Jacobians are around zero, so the rotation part is the same as: + Matrix H1Rot3 = numericalDerivative11( + boost::bind(&evaluateRotationError, factor, _1, v1, x2, v2, kZeroBias), + x1); + EXPECT(assert_equal(H1Rot3, H1a.topRows(3))); + + Matrix H3Rot3 = numericalDerivative11( + boost::bind(&evaluateRotationError, factor, x1, v1, _1, v2, kZeroBias), + x2); + EXPECT(assert_equal(H3Rot3, H3a.topRows(3))); + + // Evaluate error with wrong values + Vector3 v2_wrong = v2 + Vector3(0.1, 0.1, 0.1); + values.update(V(2), v2_wrong); + expectedError << 0, 0, 0, 0, 0, 0, -0.0724744871, -0.040715657, -0.151952901; + EXPECT( + assert_equal(expectedError, + factor.evaluateError(x1, v1, x2, v2_wrong, kZeroBias), 1e-2)); + EXPECT(assert_equal(expectedError, factor.unwhitenedError(values), 1e-2)); // Make sure the whitening is done correctly - Matrix cov = pre_int_data.preintMeasCov(); + Matrix cov = pim.preintMeasCov(); Matrix R = RtR(cov.inverse()); - Vector whitened = R * errorActual; - EXPECT(assert_equal(0.5 * whitened.squaredNorm(), factor.error(values), 1e-6)); + Vector whitened = R * expectedError; + EXPECT(assert_equal(0.5 * whitened.squaredNorm(), factor.error(values), 1e-4)); - /////////////////////////////////////////////////////////////////////////////// // Make sure linearization is correct - // Create expected value by numerical differentiation - JacobianFactor expected = linearizeNumerically(factor, values, 1e-8); - - // Create actual value by linearize - GaussianFactor::shared_ptr linearized = factor.linearize(values); - JacobianFactor* actual = dynamic_cast(linearized.get()); - - // Check cast result and then equality - EXPECT(assert_equal(expected, *actual, 1e-4)); + EXPECT_CORRECT_FACTOR_JACOBIANS(factor, values, diffDelta, 1e-3); } /* ************************************************************************* */ -TEST( ImuFactor, ErrorAndJacobianWithBiases ) { - imuBias::ConstantBias bias(Vector3(0.2, 0, 0), Vector3(0.1, 0, 0.3)); // Biases (acc, rot) - Pose3 x1(Rot3::RzRyRx(M_PI / 12.0, M_PI / 6.0, M_PI / 10.0), - Point3(5.0, 1.0, -50.0)); - Vector3 v1(Vector3(0.5, 0.0, 0.0)); +TEST(ImuFactor, ErrorAndJacobianWithBiases) { + using common::x1; + using common::v1; + using common::v2; + Bias bias(Vector3(0.2, 0, 0), Vector3(0.1, 0, 0.3)); // Biases (acc, rot) Pose3 x2(Rot3::Expmap(Vector3(0, 0, M_PI / 10.0 + M_PI / 10.0)), Point3(5.5, 1.0, -50.0)); - Vector3 v2(Vector3(0.5, 0.0, 0.0)); // Measurements - Vector3 gravity; - gravity << 0, 0, 9.81; - Vector3 omegaCoriolis; - omegaCoriolis << 0, 0.1, 0.1; Vector3 measuredOmega; measuredOmega << 0, 0, M_PI / 10.0 + 0.3; - Vector3 measuredAcc = x1.rotation().unrotate(-Point3(gravity)).vector() + Vector3 measuredAcc = x1.rotation().unrotate(-kGravityAlongNavZDown) + Vector3(0.2, 0.0, 0.0); double deltaT = 1.0; - ImuFactor::PreintegratedMeasurements pre_int_data( - imuBias::ConstantBias(Vector3(0.2, 0.0, 0.0), Vector3(0.0, 0.0, 0.1)), kMeasuredAccCovariance, - kMeasuredOmegaCovariance, kIntegrationErrorCovariance); - pre_int_data.integrateMeasurement(measuredAcc, measuredOmega, deltaT); + auto p = testing::Params(); + p->omegaCoriolis = kNonZeroOmegaCoriolis; + + Bias biasHat(Vector3(0.2, 0.0, 0.0), Vector3(0.0, 0.0, 0.1)); + PreintegratedImuMeasurements pim(p, biasHat); + pim.integrateMeasurement(measuredAcc, measuredOmega, deltaT); + + // Make sure of biasCorrectedDelta + Matrix96 actualH; + pim.biasCorrectedDelta(bias, actualH); + Matrix expectedH = numericalDerivative11( + boost::bind(&PreintegrationBase::biasCorrectedDelta, pim, _1, + boost::none), bias); + EXPECT(assert_equal(expectedH, actualH)); // Create factor - ImuFactor factor(X(1), V(1), X(2), V(2), B(1), pre_int_data, gravity, - omegaCoriolis); + ImuFactor factor(X(1), V(1), X(2), V(2), B(1), pim); - SETDEBUG("ImuFactor evaluateError", false); - Vector errorActual = factor.evaluateError(x1, v1, x2, v2, bias); - SETDEBUG("ImuFactor evaluateError", false); + Values values; + values.insert(X(1), x1); + values.insert(V(1), v1); + values.insert(X(2), x2); + values.insert(V(2), v2); + values.insert(B(1), bias); - // Expected error (should not be zero in this test, as we want to evaluate Jacobians - // at a nontrivial linearization point) - // Vector errorExpected(9); errorExpected << 0, 0, 0, 0, 0, 0, 0, 0, 0; - // EXPECT(assert_equal(errorExpected, errorActual, 1e-6)); - - // Expected Jacobians - Matrix H1e = numericalDerivative11( - boost::bind(&callEvaluateError, factor, _1, v1, x2, v2, bias), x1); - Matrix H2e = numericalDerivative11( - boost::bind(&callEvaluateError, factor, x1, _1, x2, v2, bias), v1); - Matrix H3e = numericalDerivative11( - boost::bind(&callEvaluateError, factor, x1, v1, _1, v2, bias), x2); - Matrix H4e = numericalDerivative11( - boost::bind(&callEvaluateError, factor, x1, v1, x2, _1, bias), v2); - Matrix H5e = numericalDerivative11( - boost::bind(&callEvaluateError, factor, x1, v1, x2, v2, _1), bias); - - // Check rotation Jacobians - Matrix RH1e = numericalDerivative11( - boost::bind(&evaluateRotationError, factor, _1, v1, x2, v2, bias), x1); - Matrix RH3e = numericalDerivative11( - boost::bind(&evaluateRotationError, factor, x1, v1, _1, v2, bias), x2); - Matrix RH5e = numericalDerivative11( - boost::bind(&evaluateRotationError, factor, x1, v1, x2, v2, _1), bias); - - // Actual Jacobians - Matrix H1a, H2a, H3a, H4a, H5a; - (void) factor.evaluateError(x1, v1, x2, v2, bias, H1a, H2a, H3a, H4a, H5a); - - EXPECT(assert_equal(H1e, H1a)); - EXPECT(assert_equal(H2e, H2a)); - EXPECT(assert_equal(H3e, H3a)); - EXPECT(assert_equal(H4e, H4a)); - EXPECT(assert_equal(H5e, H5a)); + // Make sure linearization is correct + double diffDelta = 1e-7; + EXPECT_CORRECT_FACTOR_JACOBIANS(factor, values, diffDelta, 1e-3); } /* ************************************************************************* */ -TEST( ImuFactor, ErrorAndJacobianWith2ndOrderCoriolis ) { - imuBias::ConstantBias bias(Vector3(0.2, 0, 0), Vector3(0.1, 0, 0.3)); // Biases (acc, rot) - Pose3 x1(Rot3::RzRyRx(M_PI / 12.0, M_PI / 6.0, M_PI / 10.0), - Point3(5.0, 1.0, -50.0)); - Vector3 v1(Vector3(0.5, 0.0, 0.0)); +TEST(ImuFactor, ErrorAndJacobianWith2ndOrderCoriolis) { + using common::x1; + using common::v1; + using common::v2; + Bias bias(Vector3(0.2, 0, 0), Vector3(0.1, 0, 0.3)); // Biases (acc, rot) Pose3 x2(Rot3::Expmap(Vector3(0, 0, M_PI / 10.0 + M_PI / 10.0)), Point3(5.5, 1.0, -50.0)); - Vector3 v2(Vector3(0.5, 0.0, 0.0)); // Measurements - Vector3 gravity; - gravity << 0, 0, 9.81; - Vector3 omegaCoriolis; - omegaCoriolis << 0, 0.1, 0.1; Vector3 measuredOmega; measuredOmega << 0, 0, M_PI / 10.0 + 0.3; - Vector3 measuredAcc = x1.rotation().unrotate(-Point3(gravity)).vector() + Vector3 measuredAcc = x1.rotation().unrotate(-kGravityAlongNavZDown) + Vector3(0.2, 0.0, 0.0); double deltaT = 1.0; - ImuFactor::PreintegratedMeasurements pre_int_data( - imuBias::ConstantBias(Vector3(0.2, 0.0, 0.0), Vector3(0.0, 0.0, 0.1)), kMeasuredAccCovariance, - kMeasuredOmegaCovariance, kIntegrationErrorCovariance); - pre_int_data.integrateMeasurement(measuredAcc, measuredOmega, deltaT); + auto p = testing::Params(); + p->omegaCoriolis = kNonZeroOmegaCoriolis; + p->use2ndOrderCoriolis = true; + + PreintegratedImuMeasurements pim(p, + Bias(Vector3(0.2, 0.0, 0.0), Vector3(0.0, 0.0, 0.1))); + pim.integrateMeasurement(measuredAcc, measuredOmega, deltaT); // Create factor - Pose3 bodyPsensor = Pose3(); - bool use2ndOrderCoriolis = true; - ImuFactor factor(X(1), V(1), X(2), V(2), B(1), pre_int_data, gravity, - omegaCoriolis, bodyPsensor, use2ndOrderCoriolis); + ImuFactor factor(X(1), V(1), X(2), V(2), B(1), pim); - SETDEBUG("ImuFactor evaluateError", false); - Vector errorActual = factor.evaluateError(x1, v1, x2, v2, bias); - SETDEBUG("ImuFactor evaluateError", false); + Values values; + values.insert(X(1), x1); + values.insert(V(1), v1); + values.insert(X(2), x2); + values.insert(V(2), v2); + values.insert(B(1), bias); - // Expected error (should not be zero in this test, as we want to evaluate Jacobians - // at a nontrivial linearization point) - // Vector errorExpected(9); errorExpected << 0, 0, 0, 0, 0, 0, 0, 0, 0; - // EXPECT(assert_equal(errorExpected, errorActual, 1e-6)); - - // Expected Jacobians - Matrix H1e = numericalDerivative11( - boost::bind(&callEvaluateError, factor, _1, v1, x2, v2, bias), x1); - Matrix H2e = numericalDerivative11( - boost::bind(&callEvaluateError, factor, x1, _1, x2, v2, bias), v1); - Matrix H3e = numericalDerivative11( - boost::bind(&callEvaluateError, factor, x1, v1, _1, v2, bias), x2); - Matrix H4e = numericalDerivative11( - boost::bind(&callEvaluateError, factor, x1, v1, x2, _1, bias), v2); - Matrix H5e = numericalDerivative11( - boost::bind(&callEvaluateError, factor, x1, v1, x2, v2, _1), bias); - - // Check rotation Jacobians - Matrix RH1e = numericalDerivative11( - boost::bind(&evaluateRotationError, factor, _1, v1, x2, v2, bias), x1); - Matrix RH3e = numericalDerivative11( - boost::bind(&evaluateRotationError, factor, x1, v1, _1, v2, bias), x2); - Matrix RH5e = numericalDerivative11( - boost::bind(&evaluateRotationError, factor, x1, v1, x2, v2, _1), bias); - - // Actual Jacobians - Matrix H1a, H2a, H3a, H4a, H5a; - (void) factor.evaluateError(x1, v1, x2, v2, bias, H1a, H2a, H3a, H4a, H5a); - - EXPECT(assert_equal(H1e, H1a)); - EXPECT(assert_equal(H2e, H2a)); - EXPECT(assert_equal(H3e, H3a)); - EXPECT(assert_equal(H4e, H4a)); - EXPECT(assert_equal(H5e, H5a)); + // Make sure linearization is correct + double diffDelta = 1e-7; + EXPECT_CORRECT_FACTOR_JACOBIANS(factor, values, diffDelta, 1e-3); } /* ************************************************************************* */ -TEST( ImuFactor, PartialDerivative_wrt_Bias ) { +TEST(ImuFactor, PartialDerivative_wrt_Bias) { // Linearization point - Vector3 biasOmega; - biasOmega << 0, 0, 0; ///< Current estimate of rotation rate bias + Vector3 biasOmega(0, 0, 0); // Current estimate of rotation rate bias // Measurements - Vector3 measuredOmega; - measuredOmega << 0.1, 0, 0; + Vector3 measuredOmega(0.1, 0, 0); double deltaT = 0.5; - // Compute numerical derivatives - Matrix expectedDelRdelBiasOmega = numericalDerivative11( - boost::bind(&evaluateRotation, measuredOmega, _1, deltaT), - Vector3(biasOmega)); + auto evaluateRotation = [=](const Vector3 biasOmega) { + return Rot3::Expmap((measuredOmega - biasOmega) * deltaT); + }; - const Matrix3 Jr = Rot3::ExpmapDerivative( - (measuredOmega - biasOmega) * deltaT); + // Compute numerical derivatives + Matrix expectedDelRdelBiasOmega = + numericalDerivative11(evaluateRotation, biasOmega); + + const Matrix3 Jr = + Rot3::ExpmapDerivative((measuredOmega - biasOmega) * deltaT); Matrix3 actualdelRdelBiasOmega = -Jr * deltaT; // the delta bias appears with the minus sign // Compare Jacobians - EXPECT(assert_equal(expectedDelRdelBiasOmega, actualdelRdelBiasOmega, 1e-3)); // 1e-3 needs to be added only when using quaternions for rotations + EXPECT(assert_equal(expectedDelRdelBiasOmega, actualdelRdelBiasOmega, 1e-9)); } /* ************************************************************************* */ -TEST( ImuFactor, PartialDerivativeLogmap ) { +TEST(ImuFactor, PartialDerivativeLogmap) { // Linearization point - Vector3 thetahat; - thetahat << 0.1, 0.1, 0; ///< Current estimate of rotation rate bias + Vector3 thetahat(0.1, 0.1, 0); // Current estimate of rotation rate bias // Measurements - Vector3 deltatheta; - deltatheta << 0, 0, 0; + Vector3 deltatheta(0, 0, 0); + + auto evaluateLogRotation = [=](const Vector3 deltatheta) { + return Rot3::Logmap( + Rot3::Expmap(thetahat).compose(Rot3::Expmap(deltatheta))); + }; // Compute numerical derivatives - Matrix expectedDelFdeltheta = numericalDerivative11( - boost::bind(&evaluateLogRotation, thetahat, _1), Vector3(deltatheta)); + Matrix expectedDelFdeltheta = + numericalDerivative11(evaluateLogRotation, deltatheta); Matrix3 actualDelFdeltheta = Rot3::LogmapDerivative(thetahat); @@ -499,14 +390,12 @@ TEST( ImuFactor, PartialDerivativeLogmap ) { } /* ************************************************************************* */ -TEST( ImuFactor, fistOrderExponential ) { +TEST(ImuFactor, fistOrderExponential) { // Linearization point - Vector3 biasOmega; - biasOmega << 0, 0, 0; ///< Current estimate of rotation rate bias + Vector3 biasOmega(0, 0, 0); // Current estimate of rotation rate bias // Measurements - Vector3 measuredOmega; - measuredOmega << 0.1, 0, 0; + Vector3 measuredOmega(0.1, 0, 0); double deltaT = 1.0; // change w.r.t. linearization point @@ -526,524 +415,456 @@ TEST( ImuFactor, fistOrderExponential ) { Rot3::Expmap((measuredOmega - biasOmega) * deltaT).matrix(); const Matrix3 actualRot = hatRot * Rot3::Expmap(delRdelBiasOmega * deltabiasOmega).matrix(); - //hatRot * (Matrix3::Identity() + skewSymmetric(delRdelBiasOmega * deltabiasOmega)); + // hatRot * (I_3x3 + skewSymmetric(delRdelBiasOmega * deltabiasOmega)); // This is a first order expansion so the equality is only an approximation EXPECT(assert_equal(expectedRot, actualRot)); } /* ************************************************************************* */ -TEST( ImuFactor, FirstOrderPreIntegratedMeasurements ) { - // Linearization point - imuBias::ConstantBias bias; ///< Current estimate of acceleration and rotation rate biases +TEST(ImuFactor, FirstOrderPreIntegratedMeasurements) { + testing::SomeMeasurements measurements; - Pose3 body_P_sensor(Rot3::Expmap(Vector3(0, 0.1, 0.1)), Point3(1, 0, 1)); + boost::function preintegrated = + [=](const Vector3& a, const Vector3& w) { + PreintegratedImuMeasurements pim(testing::Params(), Bias(a, w)); + testing::integrateMeasurements(measurements, &pim); + return pim.preintegrated(); + }; - // Measurements - list measuredAccs, measuredOmegas; - list deltaTs; - measuredAccs.push_back(Vector3(0.1, 0.0, 0.0)); - measuredOmegas.push_back(Vector3(M_PI / 100.0, 0.0, 0.0)); - deltaTs.push_back(0.01); - measuredAccs.push_back(Vector3(0.1, 0.0, 0.0)); - measuredOmegas.push_back(Vector3(M_PI / 100.0, 0.0, 0.0)); - deltaTs.push_back(0.01); - for (int i = 1; i < 100; i++) { - measuredAccs.push_back(Vector3(0.05, 0.09, 0.01)); - measuredOmegas.push_back( - Vector3(M_PI / 100.0, M_PI / 300.0, 2 * M_PI / 100.0)); - deltaTs.push_back(0.01); - } + // Actual pre-integrated values + PreintegratedImuMeasurements pim(testing::Params()); + testing::integrateMeasurements(measurements, &pim); - // Actual preintegrated values - ImuFactor::PreintegratedMeasurements preintegrated = - evaluatePreintegratedMeasurements(bias, measuredAccs, measuredOmegas, - deltaTs); - - // Compute numerical derivatives - Matrix expectedDelPdelBias = numericalDerivative11( - boost::bind(&evaluatePreintegratedMeasurementsPosition, _1, measuredAccs, - measuredOmegas, deltaTs), bias); - Matrix expectedDelPdelBiasAcc = expectedDelPdelBias.leftCols(3); - Matrix expectedDelPdelBiasOmega = expectedDelPdelBias.rightCols(3); - - Matrix expectedDelVdelBias = numericalDerivative11( - boost::bind(&evaluatePreintegratedMeasurementsVelocity, _1, measuredAccs, - measuredOmegas, deltaTs), bias); - Matrix expectedDelVdelBiasAcc = expectedDelVdelBias.leftCols(3); - Matrix expectedDelVdelBiasOmega = expectedDelVdelBias.rightCols(3); - - Matrix expectedDelRdelBias = - numericalDerivative11( - boost::bind(&evaluatePreintegratedMeasurementsRotation, _1, - measuredAccs, measuredOmegas, deltaTs), bias); - Matrix expectedDelRdelBiasAcc = expectedDelRdelBias.leftCols(3); - Matrix expectedDelRdelBiasOmega = expectedDelRdelBias.rightCols(3); - - // Compare Jacobians - EXPECT(assert_equal(expectedDelPdelBiasAcc, preintegrated.delPdelBiasAcc())); - EXPECT( - assert_equal(expectedDelPdelBiasOmega, preintegrated.delPdelBiasOmega())); - EXPECT(assert_equal(expectedDelVdelBiasAcc, preintegrated.delVdelBiasAcc())); - EXPECT( - assert_equal(expectedDelVdelBiasOmega, preintegrated.delVdelBiasOmega())); - EXPECT(assert_equal(expectedDelRdelBiasAcc, Matrix::Zero(3, 3))); - EXPECT( - assert_equal(expectedDelRdelBiasOmega, preintegrated.delRdelBiasOmega(), - 1e-3)); // 1e-3 needs to be added only when using quaternions for rotations + EXPECT(assert_equal(numericalDerivative21(preintegrated, Z_3x1, Z_3x1), + pim.preintegrated_H_biasAcc())); + EXPECT(assert_equal(numericalDerivative22(preintegrated, Z_3x1, Z_3x1), + pim.preintegrated_H_biasOmega(), 1e-3)); } /* ************************************************************************* */ -TEST( ImuFactor, JacobianPreintegratedCovariancePropagation ) { - // Linearization point - imuBias::ConstantBias bias; ///< Current estimate of acceleration and rotation rate biases - Pose3 body_P_sensor = Pose3(); // (Rot3::Expmap(Vector3(0,0.1,0.1)), Point3(1, 0, 1)); - - // Measurements - list measuredAccs, measuredOmegas; - list deltaTs; - measuredAccs.push_back(Vector3(0.1, 0.0, 0.0)); - measuredOmegas.push_back(Vector3(M_PI / 100.0, 0.0, 0.0)); - deltaTs.push_back(0.01); - measuredAccs.push_back(Vector3(0.1, 0.0, 0.0)); - measuredOmegas.push_back(Vector3(M_PI / 100.0, 0.0, 0.0)); - deltaTs.push_back(0.01); - for (int i = 1; i < 100; i++) { - measuredAccs.push_back(Vector3(0.05, 0.09, 0.01)); - measuredOmegas.push_back( - Vector3(M_PI / 100.0, M_PI / 300.0, 2 * M_PI / 100.0)); - deltaTs.push_back(0.01); - } - bool use2ndOrderIntegration = false; - // Actual preintegrated values - ImuFactor::PreintegratedMeasurements preintegrated = - evaluatePreintegratedMeasurements(bias, measuredAccs, measuredOmegas, - deltaTs, use2ndOrderIntegration); - - // so far we only created a nontrivial linearization point for the preintegrated measurements - // Now we add a new measurement and ask for Jacobians - const Vector3 newMeasuredAcc = Vector3(0.1, 0.0, 0.0); - const Vector3 newMeasuredOmega = Vector3(M_PI / 100.0, 0.0, 0.0); - const double newDeltaT = 0.01; - const Rot3 deltaRij_old = preintegrated.deltaRij(); // before adding new measurement - const Vector3 deltaVij_old = preintegrated.deltaVij(); // before adding new measurement - const Vector3 deltaPij_old = preintegrated.deltaPij(); // before adding new measurement - - Matrix oldPreintCovariance = preintegrated.preintMeasCov(); - - Matrix Factual, Gactual; - preintegrated.integrateMeasurement(newMeasuredAcc, newMeasuredOmega, - newDeltaT, body_P_sensor, Factual, Gactual); - - ////////////////////////////////////////////////////////////////////////////////////////////// - // COMPUTE NUMERICAL DERIVATIVES FOR F - ////////////////////////////////////////////////////////////////////////////////////////////// - // Compute expected f_pos_vel wrt positions - Matrix dfpv_dpos = numericalDerivative11( - boost::bind(&updatePreintegratedPosVel, _1, deltaVij_old, deltaRij_old, - newMeasuredAcc, newMeasuredOmega, newDeltaT, use2ndOrderIntegration), - deltaPij_old); - - // Compute expected f_pos_vel wrt velocities - Matrix dfpv_dvel = numericalDerivative11( - boost::bind(&updatePreintegratedPosVel, deltaPij_old, _1, deltaRij_old, - newMeasuredAcc, newMeasuredOmega, newDeltaT, use2ndOrderIntegration), - deltaVij_old); - - // Compute expected f_pos_vel wrt angles - Matrix dfpv_dangle = numericalDerivative11( - boost::bind(&updatePreintegratedPosVel, deltaPij_old, deltaVij_old, _1, - newMeasuredAcc, newMeasuredOmega, newDeltaT, use2ndOrderIntegration), - deltaRij_old); - - Matrix FexpectedTop6(6, 9); - FexpectedTop6 << dfpv_dpos, dfpv_dvel, dfpv_dangle; - - // Compute expected f_rot wrt angles - Matrix dfr_dangle = numericalDerivative11( - boost::bind(&updatePreintegratedRot, _1, newMeasuredOmega, newDeltaT), - deltaRij_old); - - Matrix FexpectedBottom3(3, 9); - FexpectedBottom3 << Z_3x3, Z_3x3, dfr_dangle; - Matrix Fexpected(9, 9); - Fexpected << FexpectedTop6, FexpectedBottom3; - - EXPECT(assert_equal(Fexpected, Factual)); - - ////////////////////////////////////////////////////////////////////////////////////////////// - // COMPUTE NUMERICAL DERIVATIVES FOR G - ////////////////////////////////////////////////////////////////////////////////////////////// - // Compute jacobian wrt integration noise - Matrix dgpv_dintNoise(6, 3); - dgpv_dintNoise << I_3x3 * newDeltaT, Z_3x3; - - // Compute jacobian wrt acc noise - Matrix dgpv_daccNoise = numericalDerivative11( - boost::bind(&updatePreintegratedPosVel, deltaPij_old, deltaVij_old, - deltaRij_old, _1, newMeasuredOmega, newDeltaT, - use2ndOrderIntegration), newMeasuredAcc); - - // Compute expected F wrt gyro noise - Matrix dgpv_domegaNoise = numericalDerivative11( - boost::bind(&updatePreintegratedPosVel, deltaPij_old, deltaVij_old, - deltaRij_old, newMeasuredAcc, _1, newDeltaT, use2ndOrderIntegration), - newMeasuredOmega); - Matrix GexpectedTop6(6, 9); - GexpectedTop6 << dgpv_dintNoise, dgpv_daccNoise, dgpv_domegaNoise; - - // Compute expected f_rot wrt gyro noise - Matrix dgr_dangle = numericalDerivative11( - boost::bind(&updatePreintegratedRot, deltaRij_old, _1, newDeltaT), - newMeasuredOmega); - - Matrix GexpectedBottom3(3, 9); - GexpectedBottom3 << Z_3x3, Z_3x3, dgr_dangle; - Matrix Gexpected(9, 9); - Gexpected << GexpectedTop6, GexpectedBottom3; - - EXPECT(assert_equal(Gexpected, Gactual)); - - // Check covariance propagation - Matrix9 measurementCovariance; - measurementCovariance << intNoiseVar * I_3x3, Z_3x3, Z_3x3, Z_3x3, accNoiseVar - * I_3x3, Z_3x3, Z_3x3, Z_3x3, omegaNoiseVar * I_3x3; - - Matrix newPreintCovarianceExpected = Factual * oldPreintCovariance - * Factual.transpose() - + (1 / newDeltaT) * Gactual * measurementCovariance * Gactual.transpose(); - - Matrix newPreintCovarianceActual = preintegrated.preintMeasCov(); - EXPECT(assert_equal(newPreintCovarianceExpected, newPreintCovarianceActual)); +Vector3 correctedAcc(const PreintegratedImuMeasurements& pim, + const Vector3& measuredAcc, const Vector3& measuredOmega) { + Vector3 correctedAcc = pim.biasHat().correctAccelerometer(measuredAcc); + Vector3 correctedOmega = pim.biasHat().correctGyroscope(measuredOmega); + return pim.correctMeasurementsBySensorPose(correctedAcc, correctedOmega).first; } -/* ************************************************************************* */ -TEST( ImuFactor, JacobianPreintegratedCovariancePropagation_2ndOrderInt ) { - // Linearization point - imuBias::ConstantBias bias; ///< Current estimate of acceleration and rotation rate biases - Pose3 body_P_sensor = Pose3(); // (Rot3::Expmap(Vector3(0,0.1,0.1)), Point3(1, 0, 1)); +TEST(ImuFactor, ErrorWithBiasesAndSensorBodyDisplacement) { + const Rot3 nRb = Rot3::Expmap(Vector3(0, 0, M_PI / 4.0)); + const Point3 p1(5.0, 1.0, -50.0); + const Vector3 v1(0.5, 0.0, 0.0); + + const Vector3 a = nRb * Vector3(0.2, 0.0, 0.0); + const AcceleratingScenario scenario(nRb, p1, v1, a, + Vector3(0, 0, M_PI / 10.0 + 0.3)); + + auto p = testing::Params(); + p->body_P_sensor = Pose3(Rot3::Expmap(Vector3(0, M_PI / 2, 0)), + Point3(0.1, 0.05, 0.01)); + p->omegaCoriolis = kNonZeroOmegaCoriolis; + + Bias biasHat(Vector3(0.2, 0.0, 0.0), Vector3(0.0, 0.0, 0.0)); + + const double T = 3.0; // seconds + ScenarioRunner runner(&scenario, p, T / 10); + + // PreintegratedImuMeasurements pim = runner.integrate(T); + // EXPECT(assert_equal(scenario.pose(T), runner.predict(pim).pose, 1e-9)); + // + // Matrix6 estimatedCov = runner.estimatePoseCovariance(T); + // EXPECT(assert_equal(estimatedCov, runner.poseCovariance(pim), 0.1)); + // + /////////////////////////////////////////////////////////////////////////////////////////// + Pose3 x1(nRb, p1); // Measurements - list measuredAccs, measuredOmegas; - list deltaTs; - measuredAccs.push_back(Vector3(0.1, 0.0, 0.0)); - measuredOmegas.push_back(Vector3(M_PI / 100.0, 0.0, 0.0)); - deltaTs.push_back(0.01); - measuredAccs.push_back(Vector3(0.1, 0.0, 0.0)); - measuredOmegas.push_back(Vector3(M_PI / 100.0, 0.0, 0.0)); - deltaTs.push_back(0.01); - for (int i = 1; i < 100; i++) { - measuredAccs.push_back(Vector3(0.05, 0.09, 0.01)); - measuredOmegas.push_back( - Vector3(M_PI / 100.0, M_PI / 300.0, 2 * M_PI / 100.0)); - deltaTs.push_back(0.01); - } - bool use2ndOrderIntegration = true; - // Actual preintegrated values - ImuFactor::PreintegratedMeasurements preintegrated = - evaluatePreintegratedMeasurements(bias, measuredAccs, measuredOmegas, - deltaTs, use2ndOrderIntegration); + Vector3 measuredOmega = runner.actualAngularVelocity(0); + Vector3 measuredAcc = runner.actualSpecificForce(0); - // so far we only created a nontrivial linearization point for the preintegrated measurements - // Now we add a new measurement and ask for Jacobians - const Vector3 newMeasuredAcc = Vector3(0.1, 0.0, 0.0); - const Vector3 newMeasuredOmega = Vector3(M_PI / 100.0, 0.0, 0.0); - const double newDeltaT = 0.01; - const Rot3 deltaRij_old = preintegrated.deltaRij(); // before adding new measurement - const Vector3 deltaVij_old = preintegrated.deltaVij(); // before adding new measurement - const Vector3 deltaPij_old = preintegrated.deltaPij(); // before adding new measurement + // Get mean prediction from "ground truth" measurements + const Vector3 accNoiseVar2(0.01, 0.02, 0.03); + const Vector3 omegaNoiseVar2(0.03, 0.01, 0.02); + PreintegratedImuMeasurements pim(p, biasHat); - Matrix oldPreintCovariance = preintegrated.preintMeasCov(); + // Check updatedDeltaXij derivatives + Matrix3 D_correctedAcc_measuredOmega = Z_3x3; + pim.correctMeasurementsBySensorPose(measuredAcc, measuredOmega, + boost::none, D_correctedAcc_measuredOmega, boost::none); + Matrix3 expectedD = numericalDerivative11( + boost::bind(correctedAcc, pim, measuredAcc, _1), measuredOmega, 1e-6); + EXPECT(assert_equal(expectedD, D_correctedAcc_measuredOmega, 1e-5)); - Matrix Factual, Gactual; - preintegrated.integrateMeasurement(newMeasuredAcc, newMeasuredOmega, - newDeltaT, body_P_sensor, Factual, Gactual); + double dt = 0.1; - ////////////////////////////////////////////////////////////////////////////////////////////// - // COMPUTE NUMERICAL DERIVATIVES FOR F - ////////////////////////////////////////////////////////////////////////////////////////////// - // Compute expected f_pos_vel wrt positions - Matrix dfpv_dpos = numericalDerivative11( - boost::bind(&updatePreintegratedPosVel, _1, deltaVij_old, deltaRij_old, - newMeasuredAcc, newMeasuredOmega, newDeltaT, use2ndOrderIntegration), - deltaPij_old); - - // Compute expected f_pos_vel wrt velocities - Matrix dfpv_dvel = numericalDerivative11( - boost::bind(&updatePreintegratedPosVel, deltaPij_old, _1, deltaRij_old, - newMeasuredAcc, newMeasuredOmega, newDeltaT, use2ndOrderIntegration), - deltaVij_old); - - // Compute expected f_pos_vel wrt angles - Matrix dfpv_dangle = numericalDerivative11( - boost::bind(&updatePreintegratedPosVel, deltaPij_old, deltaVij_old, _1, - newMeasuredAcc, newMeasuredOmega, newDeltaT, use2ndOrderIntegration), - deltaRij_old); - - Matrix FexpectedTop6(6, 9); - FexpectedTop6 << dfpv_dpos, dfpv_dvel, dfpv_dangle; - - // Compute expected f_rot wrt angles - Matrix dfr_dangle = numericalDerivative11( - boost::bind(&updatePreintegratedRot, _1, newMeasuredOmega, newDeltaT), - deltaRij_old); - - Matrix FexpectedBottom3(3, 9); - FexpectedBottom3 << Z_3x3, Z_3x3, dfr_dangle; - Matrix Fexpected(9, 9); - Fexpected << FexpectedTop6, FexpectedBottom3; - - EXPECT(assert_equal(Fexpected, Factual)); - - ////////////////////////////////////////////////////////////////////////////////////////////// - // COMPUTE NUMERICAL DERIVATIVES FOR G - ////////////////////////////////////////////////////////////////////////////////////////////// - // Compute jacobian wrt integration noise - Matrix dgpv_dintNoise(6, 3); - dgpv_dintNoise << I_3x3 * newDeltaT, Z_3x3; - - // Compute jacobian wrt acc noise - Matrix dgpv_daccNoise = numericalDerivative11( - boost::bind(&updatePreintegratedPosVel, deltaPij_old, deltaVij_old, - deltaRij_old, _1, newMeasuredOmega, newDeltaT, - use2ndOrderIntegration), newMeasuredAcc); - - // Compute expected F wrt gyro noise - Matrix dgpv_domegaNoise = numericalDerivative11( - boost::bind(&updatePreintegratedPosVel, deltaPij_old, deltaVij_old, - deltaRij_old, newMeasuredAcc, _1, newDeltaT, use2ndOrderIntegration), - newMeasuredOmega); - Matrix GexpectedTop6(6, 9); - GexpectedTop6 << dgpv_dintNoise, dgpv_daccNoise, dgpv_domegaNoise; - - // Compute expected f_rot wrt gyro noise - Matrix dgr_dangle = numericalDerivative11( - boost::bind(&updatePreintegratedRot, deltaRij_old, _1, newDeltaT), - newMeasuredOmega); - - Matrix GexpectedBottom3(3, 9); - GexpectedBottom3 << Z_3x3, Z_3x3, dgr_dangle; - Matrix Gexpected(9, 9); - Gexpected << GexpectedTop6, GexpectedBottom3; - - EXPECT(assert_equal(Gexpected, Gactual)); - - // Check covariance propagation - Matrix9 measurementCovariance; - measurementCovariance << intNoiseVar * I_3x3, Z_3x3, Z_3x3, Z_3x3, accNoiseVar - * I_3x3, Z_3x3, Z_3x3, Z_3x3, omegaNoiseVar * I_3x3; - - Matrix newPreintCovarianceExpected = Factual * oldPreintCovariance - * Factual.transpose() - + (1 / newDeltaT) * Gactual * measurementCovariance * Gactual.transpose(); - - Matrix newPreintCovarianceActual = preintegrated.preintMeasCov(); - EXPECT(assert_equal(newPreintCovarianceExpected, newPreintCovarianceActual)); -} - -//#include -///* ************************************************************************* */ -//TEST( ImuFactor, LinearizeTiming) -//{ -// // Linearization point -// Pose3 x1(Rot3::RzRyRx(M_PI/12.0, M_PI/6.0, M_PI/4.0), Point3(5.0, 1.0, -50.0)); -// Vector3 v1(Vector3(0.5, 0.0, 0.0)); -// Pose3 x2(Rot3::RzRyRx(M_PI/12.0 + M_PI/100.0, M_PI/6.0, M_PI/4.0), Point3(5.5, 1.0, -50.0)); -// Vector3 v2(Vector3(0.5, 0.0, 0.0)); -// imuBias::ConstantBias bias(Vector3(0.001, 0.002, 0.008), Vector3(0.002, 0.004, 0.012)); +// TODO(frank): revive derivative tests +// Matrix93 G1, G2; +// Vector9 preint = +// pim.updatedDeltaXij(measuredAcc, measuredOmega, dt, boost::none, G1, G2); // -// // Pre-integrator -// imuBias::ConstantBias biasHat(Vector3(0, 0, 0.10), Vector3(0, 0, 0.10)); -// Vector3 gravity; gravity << 0, 0, 9.81; -// Vector3 omegaCoriolis; omegaCoriolis << 0.0001, 0, 0.01; -// ImuFactor::PreintegratedMeasurements pre_int_data(biasHat, Matrix3::Identity(), Matrix3::Identity(), Matrix3::Identity()); +// Matrix93 expectedG1 = numericalDerivative21( +// boost::bind(&PreintegratedImuMeasurements::updatedDeltaXij, pim, _1, _2, +// dt, boost::none, boost::none, boost::none), measuredAcc, +// measuredOmega, 1e-6); +// EXPECT(assert_equal(expectedG1, G1, 1e-5)); // -// // Pre-integrate Measurements -// Vector3 measuredAcc(0.1, 0.0, 0.0); -// Vector3 measuredOmega(M_PI/100.0, 0.0, 0.0); -// double deltaT = 0.5; -// for(size_t i = 0; i < 50; ++i) { -// pre_int_data.integrateMeasurement(measuredAcc, measuredOmega, deltaT); -// } -// -// // Create factor -// noiseModel::Base::shared_ptr model = noiseModel::Gaussian::Covariance(pre_int_data.MeasurementCovariance()); -// ImuFactor factor(X(1), V(1), X(2), V(2), B(1), pre_int_data, gravity, omegaCoriolis); -// -// Values values; -// values.insert(X(1), x1); -// values.insert(X(2), x2); -// values.insert(V(1), v1); -// values.insert(V(2), v2); -// values.insert(B(1), bias); -// -// Ordering ordering; -// ordering.push_back(X(1)); -// ordering.push_back(V(1)); -// ordering.push_back(X(2)); -// ordering.push_back(V(2)); -// ordering.push_back(B(1)); -// -// GaussianFactorGraph graph; -// gttic_(LinearizeTiming); -// for(size_t i = 0; i < 100000; ++i) { -// GaussianFactor::shared_ptr g = factor.linearize(values, ordering); -// graph.push_back(g); -// } -// gttoc_(LinearizeTiming); -// tictoc_finishedIteration_(); -// std::cout << "Linear Error: " << graph.error(values.zeroVectors(ordering)) << std::endl; -// tictoc_print_(); -//} +// Matrix93 expectedG2 = numericalDerivative22( +// boost::bind(&PreintegratedImuMeasurements::updatedDeltaXij, pim, _1, _2, +// dt, boost::none, boost::none, boost::none), measuredAcc, +// measuredOmega, 1e-6); +// EXPECT(assert_equal(expectedG2, G2, 1e-5)); -/* ************************************************************************* */ -TEST( ImuFactor, ErrorWithBiasesAndSensorBodyDisplacement ) { + Bias bias(Vector3(0.2, 0, 0), Vector3(0, 0, 0.3)); // Biases (acc, rot) + + // integrate at least twice to get position information + // otherwise factor cov noise from preint_cov is not positive definite + pim.integrateMeasurement(measuredAcc, measuredOmega, dt); + pim.integrateMeasurement(measuredAcc, measuredOmega, dt); + + // Create factor + ImuFactor factor(X(1), V(1), X(2), V(2), B(1), pim); - imuBias::ConstantBias bias(Vector3(0.2, 0, 0), Vector3(0, 0, 0.3)); // Biases (acc, rot) - Pose3 x1(Rot3::Expmap(Vector3(0, 0, M_PI / 4.0)), Point3(5.0, 1.0, -50.0)); - Vector3 v1(Vector3(0.5, 0.0, 0.0)); Pose3 x2(Rot3::Expmap(Vector3(0, 0, M_PI / 4.0 + M_PI / 10.0)), Point3(5.5, 1.0, -50.0)); Vector3 v2(Vector3(0.5, 0.0, 0.0)); - // Measurements - Vector3 gravity; - gravity << 0, 0, 9.81; - Vector3 omegaCoriolis; - omegaCoriolis << 0, 0.1, 0.1; - Vector3 measuredOmega; - measuredOmega << 0, 0, M_PI / 10.0 + 0.3; - Vector3 measuredAcc = x1.rotation().unrotate(-Point3(gravity)).vector() - + Vector3(0.2, 0.0, 0.0); - double deltaT = 1.0; + Values values; + values.insert(X(1), x1); + values.insert(V(1), v1); + values.insert(X(2), x2); + values.insert(V(2), v2); + values.insert(B(1), bias); - const Pose3 body_P_sensor(Rot3::Expmap(Vector3(0, 0.10, 0.10)), - Point3(1, 0, 0)); - - ImuFactor::PreintegratedMeasurements pre_int_data( - imuBias::ConstantBias(Vector3(0.2, 0.0, 0.0), Vector3(0.0, 0.0, 0.0)), kMeasuredAccCovariance, - kMeasuredOmegaCovariance, kIntegrationErrorCovariance); - - pre_int_data.integrateMeasurement(measuredAcc, measuredOmega, deltaT); - - // Create factor - ImuFactor factor(X(1), V(1), X(2), V(2), B(1), pre_int_data, gravity, - omegaCoriolis); - - // Expected Jacobians - Matrix H1e = numericalDerivative11( - boost::bind(&callEvaluateError, factor, _1, v1, x2, v2, bias), x1); - Matrix H2e = numericalDerivative11( - boost::bind(&callEvaluateError, factor, x1, _1, x2, v2, bias), v1); - Matrix H3e = numericalDerivative11( - boost::bind(&callEvaluateError, factor, x1, v1, _1, v2, bias), x2); - Matrix H4e = numericalDerivative11( - boost::bind(&callEvaluateError, factor, x1, v1, x2, _1, bias), v2); - Matrix H5e = numericalDerivative11( - boost::bind(&callEvaluateError, factor, x1, v1, x2, v2, _1), bias); - - // Check rotation Jacobians - Matrix RH1e = numericalDerivative11( - boost::bind(&evaluateRotationError, factor, _1, v1, x2, v2, bias), x1); - Matrix RH3e = numericalDerivative11( - boost::bind(&evaluateRotationError, factor, x1, v1, _1, v2, bias), x2); - Matrix RH5e = numericalDerivative11( - boost::bind(&evaluateRotationError, factor, x1, v1, x2, v2, _1), bias); - - // Actual Jacobians - Matrix H1a, H2a, H3a, H4a, H5a; - (void) factor.evaluateError(x1, v1, x2, v2, bias, H1a, H2a, H3a, H4a, H5a); - - EXPECT(assert_equal(H1e, H1a)); - EXPECT(assert_equal(H2e, H2a)); - EXPECT(assert_equal(H3e, H3a)); - EXPECT(assert_equal(H4e, H4a)); - EXPECT(assert_equal(H5e, H5a)); + // Make sure linearization is correct + double diffDelta = 1e-8; + EXPECT_CORRECT_FACTOR_JACOBIANS(factor, values, diffDelta, 1e-3); } /* ************************************************************************* */ TEST(ImuFactor, PredictPositionAndVelocity) { - imuBias::ConstantBias bias(Vector3(0, 0, 0), Vector3(0, 0, 0)); // Biases (acc, rot) + Bias bias(Vector3(0, 0, 0), Vector3(0, 0, 0)); // Biases (acc, rot) // Measurements - Vector3 gravity; - gravity << 0, 0, 9.81; - Vector3 omegaCoriolis; - omegaCoriolis << 0, 0, 0; Vector3 measuredOmega; - measuredOmega << 0, 0, 0; //M_PI/10.0+0.3; + measuredOmega << 0, 0, 0; // M_PI/10.0+0.3; Vector3 measuredAcc; - measuredAcc << 0, 1, -9.81; + measuredAcc << 0, 1, -kGravity; double deltaT = 0.001; - Matrix I6x6(6, 6); - I6x6 = Matrix::Identity(6, 6); - - ImuFactor::PreintegratedMeasurements pre_int_data( - imuBias::ConstantBias(Vector3(0.2, 0.0, 0.0), Vector3(0.0, 0.0, 0.0)), kMeasuredAccCovariance, - kMeasuredOmegaCovariance, kIntegrationErrorCovariance, true); + PreintegratedImuMeasurements pim(testing::Params(), + Bias(Vector3(0.2, 0.0, 0.0), Vector3(0.0, 0.0, 0.0))); for (int i = 0; i < 1000; ++i) - pre_int_data.integrateMeasurement(measuredAcc, measuredOmega, deltaT); + pim.integrateMeasurement(measuredAcc, measuredOmega, deltaT); // Create factor - ImuFactor factor(X(1), V(1), X(2), V(2), B(1), pre_int_data, gravity, - omegaCoriolis); + ImuFactor factor(X(1), V(1), X(2), V(2), B(1), pim); // Predict Pose3 x1; Vector3 v1(0, 0.0, 0.0); - PoseVelocityBias poseVelocity = pre_int_data.predict(x1, v1, bias, gravity, - omegaCoriolis); - Pose3 expectedPose(Rot3(), Point3(0, 0.5, 0)); - Vector3 expectedVelocity; - expectedVelocity << 0, 1, 0; - EXPECT(assert_equal(expectedPose, poseVelocity.pose)); - EXPECT(assert_equal(Vector(expectedVelocity), Vector(poseVelocity.velocity))); + NavState actual = pim.predict(NavState(x1, v1), bias); + NavState expected(Rot3(), Point3(0, 0.5, 0), Vector3(0, 1, 0)); + EXPECT(assert_equal(expected, actual)); } /* ************************************************************************* */ TEST(ImuFactor, PredictRotation) { - imuBias::ConstantBias bias(Vector3(0, 0, 0), Vector3(0, 0, 0)); // Biases (acc, rot) + Bias bias(Vector3(0, 0, 0), Vector3(0, 0, 0)); // Biases (acc, rot) // Measurements - Vector3 gravity; - gravity << 0, 0, 9.81; - Vector3 omegaCoriolis; - omegaCoriolis << 0, 0, 0; Vector3 measuredOmega; - measuredOmega << 0, 0, M_PI / 10; //M_PI/10.0+0.3; + measuredOmega << 0, 0, M_PI / 10; // M_PI/10.0+0.3; Vector3 measuredAcc; - measuredAcc << 0, 0, -9.81; + measuredAcc << 0, 0, -kGravity; double deltaT = 0.001; - Matrix I6x6(6, 6); - I6x6 = Matrix::Identity(6, 6); - - ImuFactor::PreintegratedMeasurements pre_int_data( - imuBias::ConstantBias(Vector3(0.2, 0.0, 0.0), Vector3(0.0, 0.0, 0.0)), kMeasuredAccCovariance, - kMeasuredOmegaCovariance, kIntegrationErrorCovariance, true); + PreintegratedImuMeasurements pim(testing::Params(), + Bias(Vector3(0.2, 0.0, 0.0), Vector3(0.0, 0.0, 0.0))); for (int i = 0; i < 1000; ++i) - pre_int_data.integrateMeasurement(measuredAcc, measuredOmega, deltaT); + pim.integrateMeasurement(measuredAcc, measuredOmega, deltaT); // Create factor - ImuFactor factor(X(1), V(1), X(2), V(2), B(1), pre_int_data, gravity, - omegaCoriolis); + ImuFactor factor(X(1), V(1), X(2), V(2), B(1), pim); // Predict - Pose3 x1, x2; - Vector3 v1 = Vector3(0, 0.0, 0.0); - Vector3 v2; - ImuFactor::Predict(x1, v1, x2, v2, bias, factor.preintegratedMeasurements(), - gravity, omegaCoriolis); - Pose3 expectedPose(Rot3().ypr(M_PI / 10, 0, 0), Point3(0, 0, 0)); - Vector3 expectedVelocity; - expectedVelocity << 0, 0, 0; - EXPECT(assert_equal(expectedPose, x2)); - EXPECT(assert_equal(Vector(expectedVelocity), Vector(v2))); + NavState actual = pim.predict(NavState(), bias); + NavState expected(Rot3::Ypr(M_PI / 10, 0, 0), Point3(), Z_3x1); + EXPECT(assert_equal(expected, actual)); +} + +/* ************************************************************************* */ +TEST(ImuFactor, PredictArbitrary) { + Pose3 x1; + const Vector3 v1(0, 0, 0); + + const AcceleratingScenario scenario(x1.rotation(), x1.translation(), v1, + Vector3(0.1, 0.2, 0), Vector3(M_PI / 10, M_PI / 10, M_PI / 10)); + + const double T = 3.0; // seconds + ScenarioRunner runner(&scenario, testing::Params(), T / 10); + // + // PreintegratedImuMeasurements pim = runner.integrate(T); + // EXPECT(assert_equal(scenario.pose(T), runner.predict(pim).pose, 1e-9)); + // + // Matrix6 estimatedCov = runner.estimatePoseCovariance(T); + // EXPECT(assert_equal(estimatedCov, runner.poseCovariance(pim), 0.1)); + ////////////////////////////////////////////////////////////////////////////////// + + Bias biasHat(Vector3(0.2, 0.0, 0.0), Vector3(0.0, 0.0, 0.0)); + + // Measurements + Vector3 measuredOmega = runner.actualAngularVelocity(0); + Vector3 measuredAcc = runner.actualSpecificForce(0); + + auto p = testing::Params(); + p->integrationCovariance = Z_3x3; // MonteCarlo does not sample integration noise + PreintegratedImuMeasurements pim(p, biasHat); + Bias bias(Vector3(0, 0, 0), Vector3(0, 0, 0)); +// EXPECT(MonteCarlo(pim, NavState(x1, v1), bias, 0.1, boost::none, measuredAcc, measuredOmega, +// Vector3::Constant(accNoiseVar), Vector3::Constant(omegaNoiseVar), 100000)); + + double dt = 0.001; + for (int i = 0; i < 1000; ++i) + pim.integrateMeasurement(measuredAcc, measuredOmega, dt); + + // Create factor + ImuFactor factor(X(1), V(1), X(2), V(2), B(1), pim); + + // Predict + NavState actual = pim.predict(NavState(x1, v1), bias); + + // Regression test for Imu Refactor + Rot3 expectedR( // + +0.903715275, -0.250741668, 0.347026393, // + +0.347026393, 0.903715275, -0.250741668, // + -0.250741668, 0.347026393, 0.903715275); + Point3 expectedT(-0.516077031, 0.57842919, 0.0876478403); + Vector3 expectedV(-1.62337767, 1.57954409, 0.343833571); + NavState expected(expectedR, expectedT, expectedV); + EXPECT(assert_equal(expected, actual, 1e-7)); +} + +/* ************************************************************************* */ +TEST(ImuFactor, bodyPSensorNoBias) { + Bias bias(Vector3(0, 0, 0), Vector3(0, 0.1, 0)); // Biases (acc, rot) + + // Rotate sensor (z-down) to body (same as navigation) i.e. z-up + auto p = testing::Params(); + p->n_gravity = Vector3(0, 0, -kGravity); // z-up nav frame + p->body_P_sensor = Pose3(Rot3::Ypr(0, 0, M_PI), Point3(0, 0, 0)); + + // Measurements + // Gyroscope measurement is the angular velocity of sensor w.r.t nav frame in sensor frame + Vector3 s_omegaMeas_ns(0, 0.1, M_PI / 10); + // Acc measurement is acceleration of sensor in the sensor frame, when stationary, + // table exerts an equal and opposite force w.r.t gravity + Vector3 s_accMeas(0, 0, -kGravity); + double dt = 0.001; + + PreintegratedImuMeasurements pim(p, bias); + + for (int i = 0; i < 1000; ++i) + pim.integrateMeasurement(s_accMeas, s_omegaMeas_ns, dt); + + // Create factor + ImuFactor factor(X(1), V(1), X(2), V(2), B(1), pim); + + // Predict + NavState actual = pim.predict(NavState(), bias); + + Pose3 expectedPose(Rot3::Ypr(-M_PI / 10, 0, 0), Point3(0, 0, 0)); + EXPECT(assert_equal(expectedPose, actual.pose())); + + Vector3 expectedVelocity(0, 0, 0); + EXPECT(assert_equal(Vector(expectedVelocity), Vector(actual.velocity()))); +} + +/* ************************************************************************* */ +#include +#include +#include +#include +#include + +TEST(ImuFactor, bodyPSensorWithBias) { + using noiseModel::Diagonal; + typedef Bias Bias; + + int numFactors = 80; + Vector6 noiseBetweenBiasSigma; + noiseBetweenBiasSigma << Vector3(2.0e-5, 2.0e-5, 2.0e-5), Vector3(3.0e-6, + 3.0e-6, 3.0e-6); + SharedDiagonal biasNoiseModel = Diagonal::Sigmas(noiseBetweenBiasSigma); + + // Measurements + // Sensor frame is z-down + // Gyroscope measurement is the angular velocity of sensor w.r.t nav frame in sensor frame + Vector3 measuredOmega(0, 0.01, 0); + // Acc measurement is acceleration of sensor in the sensor frame, when stationary, + // table exerts an equal and opposite force w.r.t gravity + Vector3 measuredAcc(0, 0, -kGravity); + + auto p = testing::Params(); + p->n_gravity = Vector3(0, 0, -kGravity); + p->body_P_sensor = Pose3(Rot3::Ypr(0, 0, M_PI), Point3()); + p->accelerometerCovariance = 1e-7 * I_3x3; + p->gyroscopeCovariance = 1e-8 * I_3x3; + p->integrationCovariance = 1e-9 * I_3x3; + double deltaT = 0.005; + + // Specify noise values on priors + Vector6 priorNoisePoseSigmas( + (Vector(6) << 0.001, 0.001, 0.001, 0.01, 0.01, 0.01).finished()); + Vector3 priorNoiseVelSigmas((Vector(3) << 0.1, 0.1, 0.1).finished()); + Vector6 priorNoiseBiasSigmas( + (Vector(6) << 0.1, 0.1, 0.1, 0.5e-1, 0.5e-1, 0.5e-1).finished()); + SharedDiagonal priorNoisePose = Diagonal::Sigmas(priorNoisePoseSigmas); + SharedDiagonal priorNoiseVel = Diagonal::Sigmas(priorNoiseVelSigmas); + SharedDiagonal priorNoiseBias = Diagonal::Sigmas(priorNoiseBiasSigmas); + Vector3 zeroVel(0, 0, 0); + + // Create a factor graph with priors on initial pose, vlocity and bias + NonlinearFactorGraph graph; + Values values; + + PriorFactor priorPose(X(0), Pose3(), priorNoisePose); + graph.add(priorPose); + values.insert(X(0), Pose3()); + + PriorFactor priorVel(V(0), zeroVel, priorNoiseVel); + graph.add(priorVel); + values.insert(V(0), zeroVel); + + // The key to this test is that we specify the bias, in the sensor frame, as known a priori + // We also create factors below that encode our assumption that this bias is constant over time + // In theory, after optimization, we should recover that same bias estimate + Bias priorBias(Vector3(0, 0, 0), Vector3(0, 0.01, 0)); // Biases (acc, rot) + PriorFactor priorBiasFactor(B(0), priorBias, priorNoiseBias); + graph.add(priorBiasFactor); + values.insert(B(0), priorBias); + + // Now add IMU factors and bias noise models + Bias zeroBias(Vector3(0, 0, 0), Vector3(0, 0, 0)); + for (int i = 1; i < numFactors; i++) { + PreintegratedImuMeasurements pim = PreintegratedImuMeasurements(p, + priorBias); + for (int j = 0; j < 200; ++j) + pim.integrateMeasurement(measuredAcc, measuredOmega, deltaT); + + // Create factors + graph.add(ImuFactor(X(i - 1), V(i - 1), X(i), V(i), B(i - 1), pim)); + graph.add(BetweenFactor(B(i - 1), B(i), zeroBias, biasNoiseModel)); + + values.insert(X(i), Pose3()); + values.insert(V(i), zeroVel); + values.insert(B(i), priorBias); + } + + // Finally, optimize, and get bias at last time step + Values results = LevenbergMarquardtOptimizer(graph, values).optimize(); + Bias biasActual = results.at(B(numFactors - 1)); + + // And compare it with expected value (our prior) + Bias biasExpected(Vector3(0, 0, 0), Vector3(0, 0.01, 0)); + EXPECT(assert_equal(biasExpected, biasActual, 1e-3)); +} + +/* ************************************************************************* */ +static const double kVelocity = 2.0, kAngularVelocity = M_PI / 6; + +struct ImuFactorMergeTest { + boost::shared_ptr p_; + const ConstantTwistScenario forward_, loop_; + + ImuFactorMergeTest() + : p_(PreintegratedImuMeasurements::Params::MakeSharedU(kGravity)), + forward_(Z_3x1, Vector3(kVelocity, 0, 0)), + loop_(Vector3(0, -kAngularVelocity, 0), Vector3(kVelocity, 0, 0)) { + // arbitrary noise values + p_->gyroscopeCovariance = I_3x3 * 0.01; + p_->accelerometerCovariance = I_3x3 * 0.02; + p_->accelerometerCovariance = I_3x3 * 0.03; + } + + int TestScenario(TestResult& result_, const std::string& name_, + const Scenario& scenario, + const Bias& bias01, + const Bias& bias12, double tol) { + // Test merge by creating a 01, 12, and 02 PreintegratedRotation, + // then checking the merge of 01-12 matches 02. + PreintegratedImuMeasurements pim01(p_, bias01); + PreintegratedImuMeasurements pim12(p_, bias12); + PreintegratedImuMeasurements pim02_expected(p_, bias01); + + double deltaT = 0.01; + ScenarioRunner runner(&scenario, p_, deltaT); + // TODO(frank) can this loop just go into runner ? + for (int i = 0; i < 100; i++) { + double t = i * deltaT; + // integrate the measurements appropriately + Vector3 accel_meas = runner.actualSpecificForce(t); + Vector3 omega_meas = runner.actualAngularVelocity(t); + pim02_expected.integrateMeasurement(accel_meas, omega_meas, deltaT); + if (i < 50) { + pim01.integrateMeasurement(accel_meas, omega_meas, deltaT); + } else { + pim12.integrateMeasurement(accel_meas, omega_meas, deltaT); + } + } + auto actual_pim02 = ImuFactor::Merge(pim01, pim12); + EXPECT(assert_equal(pim02_expected.preintegrated(), + actual_pim02.preintegrated(), tol)); + EXPECT(assert_equal(pim02_expected, actual_pim02, tol)); + + ImuFactor::shared_ptr factor01 = + boost::make_shared(X(0), V(0), X(1), V(1), B(0), pim01); + ImuFactor::shared_ptr factor12 = + boost::make_shared(X(1), V(1), X(2), V(2), B(0), pim12); + ImuFactor::shared_ptr factor02_expected = boost::make_shared( + X(0), V(0), X(2), V(2), B(0), pim02_expected); + + ImuFactor::shared_ptr factor02_merged = ImuFactor::Merge(factor01, factor12); + EXPECT(assert_equal(*factor02_expected, *factor02_merged, tol)); + return result_.getFailureCount(); + } + + void TestScenarios(TestResult& result_, const std::string& name_, + const Bias& bias01, + const Bias& bias12, double tol) { + for (auto scenario : {forward_, loop_}) + TestScenario(result_, name_, scenario, bias01, bias12, tol); + } +}; + +/* ************************************************************************* */ +// Test case with zero biases +TEST(ImuFactor, MergeZeroBias) { + ImuFactorMergeTest mergeTest; + mergeTest.TestScenarios(result_, name_, kZeroBias, kZeroBias, 1e-4); +} + +// Test case with identical biases: we expect an exact answer. +TEST(ImuFactor, MergeConstantBias) { + ImuFactorMergeTest mergeTest; + Bias bias(Vector3(0.03, -0.02, 0.01), Vector3(-0.01, 0.02, -0.03)); + mergeTest.TestScenarios(result_, name_, bias, bias, 1e-4); +} + +// Test case with different biases where we expect there to be some variation. +TEST(ImuFactor, MergeChangingBias) { + ImuFactorMergeTest mergeTest; + mergeTest.TestScenarios(result_, name_, + Bias(Vector3(0.03, -0.02, 0.01), Vector3(-0.01, 0.02, -0.03)), + Bias(Vector3(0.01, 0.02, 0.03), Vector3(0.03, -0.02, 0.01)), 1e-1); +} + +// Test case with non-zero coriolis +TEST(ImuFactor, MergeWithCoriolis) { + ImuFactorMergeTest mergeTest; + mergeTest.p_->omegaCoriolis = Vector3(0.1, 0.2, -0.1); + mergeTest.TestScenarios(result_, name_, kZeroBias, kZeroBias, 1e-4); } /* ************************************************************************* */ diff --git a/gtsam/navigation/tests/testImuFactorSerialization.cpp b/gtsam/navigation/tests/testImuFactorSerialization.cpp new file mode 100644 index 000000000..a7796d1b2 --- /dev/null +++ b/gtsam/navigation/tests/testImuFactorSerialization.cpp @@ -0,0 +1,77 @@ +/* ---------------------------------------------------------------------------- + + * 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 testImuFactor.cpp + * @brief Unit test for ImuFactor + * @author Luca Carlone + * @author Frank Dellaert + * @author Richard Roberts + * @author Stephen Williams + */ + +#include +#include +#include +#include + +using namespace std; +using namespace gtsam; + +BOOST_CLASS_EXPORT_GUID(gtsam::noiseModel::Constrained, + "gtsam_noiseModel_Constrained"); +BOOST_CLASS_EXPORT_GUID(gtsam::noiseModel::Diagonal, + "gtsam_noiseModel_Diagonal"); +BOOST_CLASS_EXPORT_GUID(gtsam::noiseModel::Gaussian, + "gtsam_noiseModel_Gaussian"); +BOOST_CLASS_EXPORT_GUID(gtsam::noiseModel::Unit, "gtsam_noiseModel_Unit"); +BOOST_CLASS_EXPORT_GUID(gtsam::noiseModel::Isotropic, + "gtsam_noiseModel_Isotropic"); +BOOST_CLASS_EXPORT_GUID(gtsam::SharedNoiseModel, "gtsam_SharedNoiseModel"); +BOOST_CLASS_EXPORT_GUID(gtsam::SharedDiagonal, "gtsam_SharedDiagonal"); + +TEST(ImuFactor, serialization) { + using namespace gtsam::serializationTestHelpers; + + // Create default parameters with Z-down and above noise paramaters + auto p = PreintegrationParams::MakeSharedD(9.81); + p->body_P_sensor = Pose3(Rot3::Ypr(0, 0, M_PI), Point3()); + p->accelerometerCovariance = 1e-7 * I_3x3; + p->gyroscopeCovariance = 1e-8 * I_3x3; + p->integrationCovariance = 1e-9 * I_3x3; + + const double deltaT = 0.005; + const imuBias::ConstantBias priorBias( + Vector3(0, 0, 0), Vector3(0, 0.01, 0)); // Biases (acc, rot) + + PreintegratedImuMeasurements pim(p, priorBias); + + // measurements are needed for non-inf noise model, otherwise will throw err + // when deserialize + const Vector3 measuredOmega(0, 0.01, 0); + const Vector3 measuredAcc(0, 0, -9.81); + + for (int j = 0; j < 200; ++j) + pim.integrateMeasurement(measuredAcc, measuredOmega, deltaT); + + ImuFactor factor(1, 2, 3, 4, 5, pim); + + EXPECT(equalsObj(factor)); + EXPECT(equalsXML(factor)); + EXPECT(equalsBinary(factor)); +} + +/* ************************************************************************* */ +int main() { + TestResult tr; + return TestRegistry::runAllTests(tr); +} +/* ************************************************************************* */ diff --git a/gtsam/navigation/tests/testMagFactor.cpp b/gtsam/navigation/tests/testMagFactor.cpp index 950c6ce63..38aecfcbc 100644 --- a/gtsam/navigation/tests/testMagFactor.cpp +++ b/gtsam/navigation/tests/testMagFactor.cpp @@ -40,7 +40,7 @@ Point3 nM(22653.29982, -1956.83010, 44202.47862); // Let's assume scale factor, double scale = 255.0 / 50000.0; // ...ground truth orientation, -Rot3 nRb = Rot3::yaw(-0.1); +Rot3 nRb = Rot3::Yaw(-0.1); Rot2 theta = nRb.yaw(); // ...and bias Point3 bias(10, -10, 50); diff --git a/gtsam/navigation/tests/testNavState.cpp b/gtsam/navigation/tests/testNavState.cpp new file mode 100644 index 000000000..a62ca06a8 --- /dev/null +++ b/gtsam/navigation/tests/testNavState.cpp @@ -0,0 +1,272 @@ +/* ---------------------------------------------------------------------------- + + * 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 testNavState.cpp + * @brief Unit tests for NavState + * @author Frank Dellaert + * @date July 2015 + */ + +#include +#include +#include +#include + +using namespace std; +using namespace gtsam; + +static const Rot3 kAttitude = Rot3::RzRyRx(0.1, 0.2, 0.3); +static const Point3 kPosition(1.0, 2.0, 3.0); +static const Pose3 kPose(kAttitude, kPosition); +static const Velocity3 kVelocity(0.4, 0.5, 0.6); +static const NavState kIdentity; +static const NavState kState1(kAttitude, kPosition, kVelocity); +static const Vector3 kOmegaCoriolis(0.02, 0.03, 0.04); +static const Vector3 kGravity(0, 0, 9.81); +static const Vector9 kZeroXi = Vector9::Zero(); + +/* ************************************************************************* */ +TEST(NavState, Constructor) { + boost::function construct = + boost::bind(&NavState::FromPoseVelocity, _1, _2, boost::none, + boost::none); + Matrix aH1, aH2; + EXPECT( + assert_equal(kState1, + NavState::FromPoseVelocity(kPose, kVelocity, aH1, aH2))); + EXPECT(assert_equal(numericalDerivative21(construct, kPose, kVelocity), aH1)); + EXPECT(assert_equal(numericalDerivative22(construct, kPose, kVelocity), aH2)); +} + +/* ************************************************************************* */ +TEST( NavState, Attitude) { + Matrix39 aH, eH; + Rot3 actual = kState1.attitude(aH); + EXPECT(assert_equal(actual, kAttitude)); + eH = numericalDerivative11( + boost::bind(&NavState::attitude, _1, boost::none), kState1); + EXPECT(assert_equal((Matrix )eH, aH)); +} + +/* ************************************************************************* */ +TEST( NavState, Position) { + Matrix39 aH, eH; + Point3 actual = kState1.position(aH); + EXPECT(assert_equal(actual, kPosition)); + eH = numericalDerivative11( + boost::bind(&NavState::position, _1, boost::none), kState1); + EXPECT(assert_equal((Matrix )eH, aH)); +} + +/* ************************************************************************* */ +TEST( NavState, Velocity) { + Matrix39 aH, eH; + Velocity3 actual = kState1.velocity(aH); + EXPECT(assert_equal(actual, kVelocity)); + eH = numericalDerivative11( + boost::bind(&NavState::velocity, _1, boost::none), kState1); + EXPECT(assert_equal((Matrix )eH, aH)); +} + +/* ************************************************************************* */ +TEST( NavState, BodyVelocity) { + Matrix39 aH, eH; + Velocity3 actual = kState1.bodyVelocity(aH); + EXPECT(assert_equal(actual, kAttitude.unrotate(kVelocity))); + eH = numericalDerivative11( + boost::bind(&NavState::bodyVelocity, _1, boost::none), kState1); + EXPECT(assert_equal((Matrix )eH, aH)); +} + +/* ************************************************************************* */ +TEST( NavState, MatrixGroup ) { + // check roundtrip conversion to 7*7 matrix representation + Matrix7 T = kState1.matrix(); + EXPECT(assert_equal(kState1, NavState(T))); + + // check group product agrees with matrix product + NavState state2 = kState1 * kState1; + Matrix T2 = T * T; + EXPECT(assert_equal(state2, NavState(T2))); + EXPECT(assert_equal(T2, state2.matrix())); +} + +/* ************************************************************************* */ +TEST( NavState, Manifold ) { + // Check zero xi + EXPECT(assert_equal(kIdentity, kIdentity.retract(kZeroXi))); + EXPECT(assert_equal(kZeroXi, kIdentity.localCoordinates(kIdentity))); + EXPECT(assert_equal(kState1, kState1.retract(kZeroXi))); + EXPECT(assert_equal(kZeroXi, kState1.localCoordinates(kState1))); + + // Check definition of retract as operating on components separately + Vector9 xi; + xi << 0.1, 0.1, 0.1, 0.2, 0.3, 0.4, -0.1, -0.2, -0.3; + Rot3 drot = Rot3::Expmap(xi.head<3>()); + Point3 dt = Point3(xi.segment<3>(3)); + Velocity3 dvel = Velocity3(-0.1, -0.2, -0.3); + NavState state2 = kState1 * NavState(drot, dt, dvel); + EXPECT(assert_equal(state2, kState1.retract(xi))); + EXPECT(assert_equal(xi, kState1.localCoordinates(state2))); + + // roundtrip from state2 to state3 and back + NavState state3 = state2.retract(xi); + EXPECT(assert_equal(xi, state2.localCoordinates(state3))); + + // Check derivatives for ChartAtOrigin::Retract + Matrix9 aH; + // For zero xi + boost::function Retract = boost::bind( + NavState::ChartAtOrigin::Retract, _1, boost::none); + NavState::ChartAtOrigin::Retract(kZeroXi, aH); + EXPECT(assert_equal(numericalDerivative11(Retract, kZeroXi), aH)); + // For non-zero xi + NavState::ChartAtOrigin::Retract(xi, aH); + EXPECT(assert_equal(numericalDerivative11(Retract, xi), aH)); + + // Check derivatives for ChartAtOrigin::Local + // For zero xi + boost::function Local = boost::bind( + NavState::ChartAtOrigin::Local, _1, boost::none); + NavState::ChartAtOrigin::Local(kIdentity, aH); + EXPECT(assert_equal(numericalDerivative11(Local, kIdentity), aH)); + // For non-zero xi + NavState::ChartAtOrigin::Local(kState1, aH); + EXPECT(assert_equal(numericalDerivative11(Local, kState1), aH)); + + // Check retract derivatives + Matrix9 aH1, aH2; + kState1.retract(xi, aH1, aH2); + boost::function retract = + boost::bind(&NavState::retract, _1, _2, boost::none, boost::none); + EXPECT(assert_equal(numericalDerivative21(retract, kState1, xi), aH1)); + EXPECT(assert_equal(numericalDerivative22(retract, kState1, xi), aH2)); + + // Check localCoordinates derivatives + boost::function local = + boost::bind(&NavState::localCoordinates, _1, _2, boost::none, + boost::none); + // from state1 to state2 + kState1.localCoordinates(state2, aH1, aH2); + EXPECT(assert_equal(numericalDerivative21(local, kState1, state2), aH1)); + EXPECT(assert_equal(numericalDerivative22(local, kState1, state2), aH2)); + // from identity to state2 + kIdentity.localCoordinates(state2, aH1, aH2); + EXPECT(assert_equal(numericalDerivative21(local, kIdentity, state2), aH1)); + EXPECT(assert_equal(numericalDerivative22(local, kIdentity, state2), aH2)); + // from state2 to identity + state2.localCoordinates(kIdentity, aH1, aH2); + EXPECT(assert_equal(numericalDerivative21(local, state2, kIdentity), aH1)); + EXPECT(assert_equal(numericalDerivative22(local, state2, kIdentity), aH2)); +} + +/* ************************************************************************* */ +TEST( NavState, Lie ) { + // Check zero xi + EXPECT(assert_equal(kIdentity, kIdentity.expmap(kZeroXi))); + EXPECT(assert_equal(kZeroXi, kIdentity.logmap(kIdentity))); + EXPECT(assert_equal(kState1, kState1.expmap(kZeroXi))); + EXPECT(assert_equal(kZeroXi, kState1.logmap(kState1))); + + // Expmap/Logmap roundtrip + Vector xi(9); + xi << 0.1, 0.1, 0.1, 0.2, 0.3, 0.4, -0.1, -0.2, -0.3; + NavState state2 = NavState::Expmap(xi); + EXPECT(assert_equal(xi, NavState::Logmap(state2))); + + // roundtrip from state2 to state3 and back + NavState state3 = state2.expmap(xi); + EXPECT(assert_equal(xi, state2.logmap(state3))); + + // For the expmap/logmap (not necessarily expmap/local) -xi goes other way + EXPECT(assert_equal(state2, state3.expmap(-xi))); + EXPECT(assert_equal(xi, -state3.logmap(state2))); +} + +/* ************************************************************************* */ +TEST(NavState, Update) { + Vector3 omega(M_PI / 100.0, 0.0, 0.0); + Vector3 acc(0.1, 0.0, 0.0); + double dt = 10; + Matrix9 aF; + Matrix93 aG1, aG2; + boost::function update = + boost::bind(&NavState::update, _1, _2, _3, dt, boost::none, + boost::none, boost::none); + Vector3 b_acc = kAttitude * acc; + NavState expected(kAttitude.expmap(dt * omega), + kPosition + Point3((kVelocity + b_acc * dt / 2) * dt), + kVelocity + b_acc * dt); + NavState actual = kState1.update(acc, omega, dt, aF, aG1, aG2); + EXPECT(assert_equal(expected, actual)); + EXPECT(assert_equal(numericalDerivative31(update, kState1, acc, omega, 1e-7), aF, 1e-7)); + EXPECT(assert_equal(numericalDerivative32(update, kState1, acc, omega, 1e-7), aG1, 1e-7)); + EXPECT(assert_equal(numericalDerivative33(update, kState1, acc, omega, 1e-7), aG2, 1e-7)); + + // Try different values + omega = Vector3(0.1, 0.2, 0.3); + acc = Vector3(0.4, 0.5, 0.6); + kState1.update(acc, omega, dt, aF, aG1, aG2); + EXPECT(assert_equal(numericalDerivative31(update, kState1, acc, omega, 1e-7), aF, 1e-7)); + EXPECT(assert_equal(numericalDerivative32(update, kState1, acc, omega, 1e-7), aG1, 1e-7)); + EXPECT(assert_equal(numericalDerivative33(update, kState1, acc, omega, 1e-7), aG2, 1e-7)); +} + +/* ************************************************************************* */ +static const double dt = 2.0; +boost::function coriolis = boost::bind( + &NavState::coriolis, _1, dt, kOmegaCoriolis, _2, boost::none); + +TEST(NavState, Coriolis) { + Matrix9 aH; + + // first-order + kState1.coriolis(dt, kOmegaCoriolis, false, aH); + EXPECT(assert_equal(numericalDerivative21(coriolis, kState1, false), aH)); + // second-order + kState1.coriolis(dt, kOmegaCoriolis, true, aH); + EXPECT(assert_equal(numericalDerivative21(coriolis, kState1, true), aH)); +} + +TEST(NavState, Coriolis2) { + Matrix9 aH; + NavState state2(Rot3::RzRyRx(M_PI / 12.0, M_PI / 6.0, M_PI / 4.0), + Point3(5.0, 1.0, -50.0), Vector3(0.5, 0.0, 0.0)); + + // first-order + state2.coriolis(dt, kOmegaCoriolis, false, aH); + EXPECT(assert_equal(numericalDerivative21(coriolis, state2, false), aH)); + // second-order + state2.coriolis(dt, kOmegaCoriolis, true, aH); + EXPECT(assert_equal(numericalDerivative21(coriolis, state2, true), aH)); +} + +/* ************************************************************************* */ +TEST(NavState, CorrectPIM) { + Vector9 xi; + xi << 0.1, 0.1, 0.1, 0.2, 0.3, 0.4, -0.1, -0.2, -0.3; + double dt = 0.5; + Matrix9 aH1, aH2; + boost::function correctPIM = + boost::bind(&NavState::correctPIM, _1, _2, dt, kGravity, kOmegaCoriolis, + false, boost::none, boost::none); + kState1.correctPIM(xi, dt, kGravity, kOmegaCoriolis, false, aH1, aH2); + EXPECT(assert_equal(numericalDerivative21(correctPIM, kState1, xi), aH1)); + EXPECT(assert_equal(numericalDerivative22(correctPIM, kState1, xi), aH2)); +} + +/* ************************************************************************* */ +int main() { + TestResult tr; + return TestRegistry::runAllTests(tr); +} +/* ************************************************************************* */ diff --git a/gtsam/navigation/tests/testPoseVelocityBias.cpp b/gtsam/navigation/tests/testPoseVelocityBias.cpp new file mode 100644 index 000000000..cc2a47498 --- /dev/null +++ b/gtsam/navigation/tests/testPoseVelocityBias.cpp @@ -0,0 +1,67 @@ +/* ---------------------------------------------------------------------------- + + * 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 testPoseVelocityBias.cpp + * @brief Unit test for PoseVelocityBias + * @author Frank Dellaert + */ + +#include +#include +#include +#include +#include +#include + +using namespace std; +using namespace gtsam; + +#ifdef GTSAM_ALLOW_DEPRECATED_SINCE_V4 + +// Should be seen as between(pvb1,pvb2), i.e., written as pvb2 \omin pvb1 +Vector9 error(const PoseVelocityBias& pvb1, const PoseVelocityBias& pvb2) { + Matrix3 R1 = pvb1.pose.rotation().matrix(); + // Ri.transpose() translate the error from the global frame into pose1's frame + const Vector3 fp = R1.transpose() * (pvb2.pose.translation() - pvb1.pose.translation()).vector(); + const Vector3 fv = R1.transpose() * (pvb2.velocity - pvb1.velocity); + const Rot3 R1BetweenR2 = pvb1.pose.rotation().between(pvb2.pose.rotation()); + const Vector3 fR = Rot3::Logmap(R1BetweenR2); + Vector9 r; + r << fp, fv, fR; + return r; +} + +/* ************************************************************************************************/ +TEST(PoseVelocityBias, error) { + Point3 i1(0, 1, 0), j1(-1, 0, 0), k1(0, 0, 1); + Pose3 x1(Rot3(i1, j1, k1), Point3(5.0, 1.0, 0.0)); + Vector3 v1(Vector3(0.5, 0.0, 0.0)); + imuBias::ConstantBias bias1(Vector3(0.2, 0, 0), Vector3(0.1, 0, 0.3)); + + Pose3 x2(Rot3(i1, j1, k1).expmap(Vector3(0.1, 0.2, 0.3)), Point3(5.5, 1.0, 6.0)); + Vector3 v2(Vector3(0.5, 4.0, 3.0)); + imuBias::ConstantBias bias2(Vector3(0.1, 0.2, -0.3), Vector3(0.2, 0.3, 0.1)); + + PoseVelocityBias pvb1(x1, v1, bias1), pvb2(x2, v2, bias2); + + Vector9 expected, actual = error(pvb1, pvb2); + expected << 0.0, -0.5, 6.0, 4.0, 0.0, 3.0, 0.1, 0.2, 0.3; + EXPECT(assert_equal(expected, actual, 1e-9)); +} +#endif + +/* ************************************************************************************************/ +int main() { + TestResult tr; + return TestRegistry::runAllTests(tr); +} +/* ************************************************************************************************/ diff --git a/gtsam/navigation/tests/testPreintegrationBase.cpp b/gtsam/navigation/tests/testPreintegrationBase.cpp new file mode 100644 index 000000000..b733181ac --- /dev/null +++ b/gtsam/navigation/tests/testPreintegrationBase.cpp @@ -0,0 +1,150 @@ +/* ---------------------------------------------------------------------------- + + * 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 testPreintegrationBase.cpp + * @brief Unit test for the InertialNavFactor + * @author Frank Dellaert + */ + +#include +#include +#include +#include +#include + +#include +#include + +#include "imuFactorTesting.h" + +static const double kDt = 0.1; + +Vector9 f(const Vector9& zeta, const Vector3& a, const Vector3& w) { + return PreintegrationBase::UpdatePreintegrated(a, w, kDt, zeta); +} + +namespace testing { +// Create default parameters with Z-down and above noise parameters +static boost::shared_ptr Params() { + auto p = PreintegrationParams::MakeSharedD(kGravity); + p->gyroscopeCovariance = kGyroSigma * kGyroSigma * I_3x3; + p->accelerometerCovariance = kAccelSigma * kAccelSigma * I_3x3; + p->integrationCovariance = 0.0001 * I_3x3; + return p; +} +} + +/* ************************************************************************* */ +TEST(PreintegrationBase, UpdateEstimate1) { + PreintegrationBase pim(testing::Params()); + const Vector3 acc(0.1, 0.2, 10), omega(0.1, 0.2, 0.3); + Vector9 zeta; + zeta.setZero(); + Matrix9 aH1; + Matrix93 aH2, aH3; + pim.UpdatePreintegrated(acc, omega, kDt, zeta, aH1, aH2, aH3); + EXPECT(assert_equal(numericalDerivative31(f, zeta, acc, omega), aH1, 1e-9)); + EXPECT(assert_equal(numericalDerivative32(f, zeta, acc, omega), aH2, 1e-9)); + EXPECT(assert_equal(numericalDerivative33(f, zeta, acc, omega), aH3, 1e-9)); +} + +/* ************************************************************************* */ +TEST(PreintegrationBase, UpdateEstimate2) { + PreintegrationBase pim(testing::Params()); + const Vector3 acc(0.1, 0.2, 10), omega(0.1, 0.2, 0.3); + Vector9 zeta; + zeta << 0.01, 0.02, 0.03, 100, 200, 300, 10, 5, 3; + Matrix9 aH1; + Matrix93 aH2, aH3; + pim.UpdatePreintegrated(acc, omega, kDt, zeta, aH1, aH2, aH3); + // NOTE(frank): tolerance of 1e-3 on H1 because approximate away from 0 + EXPECT(assert_equal(numericalDerivative31(f, zeta, acc, omega), aH1, 1e-3)); + EXPECT(assert_equal(numericalDerivative32(f, zeta, acc, omega), aH2, 1e-8)); + EXPECT(assert_equal(numericalDerivative33(f, zeta, acc, omega), aH3, 1e-9)); +} + +/* ************************************************************************* */ +TEST(PreintegrationBase, computeError) { + PreintegrationBase pim(testing::Params()); + NavState x1, x2; + imuBias::ConstantBias bias; + Matrix9 aH1, aH2; + Matrix96 aH3; + pim.computeError(x1, x2, bias, aH1, aH2, aH3); + boost::function f = + boost::bind(&PreintegrationBase::computeError, pim, _1, _2, _3, + boost::none, boost::none, boost::none); + // NOTE(frank): tolerance of 1e-3 on H1 because approximate away from 0 + EXPECT(assert_equal(numericalDerivative31(f, x1, x2, bias), aH1, 1e-9)); + EXPECT(assert_equal(numericalDerivative32(f, x1, x2, bias), aH2, 1e-9)); + EXPECT(assert_equal(numericalDerivative33(f, x1, x2, bias), aH3, 1e-9)); +} + +/* ************************************************************************* */ +TEST(PreintegrationBase, Compose) { + testing::SomeMeasurements measurements; + PreintegrationBase pim(testing::Params()); + testing::integrateMeasurements(measurements, &pim); + + boost::function f = + [pim](const Vector9& zeta01, const Vector9& zeta12) { + return PreintegrationBase::Compose(zeta01, zeta12, pim.deltaTij()); + }; + + // Expected merge result + PreintegrationBase expected_pim02(testing::Params()); + testing::integrateMeasurements(measurements, &expected_pim02); + testing::integrateMeasurements(measurements, &expected_pim02); + + // Actual result + Matrix9 H1, H2; + PreintegrationBase actual_pim02 = pim; + actual_pim02.mergeWith(pim, &H1, &H2); + + const Vector9 zeta = pim.preintegrated(); + const Vector9 actual_zeta = + PreintegrationBase::Compose(zeta, zeta, pim.deltaTij()); + EXPECT(assert_equal(expected_pim02.preintegrated(), actual_zeta, 1e-7)); + EXPECT(assert_equal(numericalDerivative21(f, zeta, zeta), H1, 1e-7)); + EXPECT(assert_equal(numericalDerivative22(f, zeta, zeta), H2, 1e-7)); +} + +/* ************************************************************************* */ + TEST(PreintegrationBase, MergedBiasDerivatives) { + testing::SomeMeasurements measurements; + + boost::function f = + [=](const Vector3& a, const Vector3& w) { + PreintegrationBase pim02(testing::Params(), Bias(a, w)); + testing::integrateMeasurements(measurements, &pim02); + testing::integrateMeasurements(measurements, &pim02); + return pim02.preintegrated(); + }; + + // Expected merge result + PreintegrationBase expected_pim02(testing::Params()); + testing::integrateMeasurements(measurements, &expected_pim02); + testing::integrateMeasurements(measurements, &expected_pim02); + + EXPECT(assert_equal(numericalDerivative21(f, Z_3x1, Z_3x1), + expected_pim02.preintegrated_H_biasAcc())); + EXPECT(assert_equal(numericalDerivative22(f, Z_3x1, Z_3x1), + expected_pim02.preintegrated_H_biasOmega(), 1e-7)); +} + +/* ************************************************************************* */ +int main() { + TestResult tr; + return TestRegistry::runAllTests(tr); +} +/* ************************************************************************* */ diff --git a/gtsam/navigation/tests/testScenario.cpp b/gtsam/navigation/tests/testScenario.cpp new file mode 100644 index 000000000..bc965b058 --- /dev/null +++ b/gtsam/navigation/tests/testScenario.cpp @@ -0,0 +1,137 @@ +/* ---------------------------------------------------------------------------- + + * 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 testScenario.cpp + * @brief Unit test Scenario class + * @author Frank Dellaert + */ + +#include +#include + +#include +#include +#include + +using namespace std; +using namespace gtsam; + +static const double kDegree = M_PI / 180.0; + +/* ************************************************************************* */ +TEST(Scenario, Spin) { + // angular velocity 6 kDegree/sec + const double w = 6 * kDegree; + const Vector3 W(0, 0, w), V(0, 0, 0); + const ConstantTwistScenario scenario(W, V); + + const double T = 10; + EXPECT(assert_equal(W, scenario.omega_b(T), 1e-9)); + EXPECT(assert_equal(V, scenario.velocity_b(T), 1e-9)); + EXPECT(assert_equal(W.cross(V), scenario.acceleration_b(T), 1e-9)); + + const Pose3 T10 = scenario.pose(T); + EXPECT(assert_equal(Vector3(0, 0, 60 * kDegree), T10.rotation().xyz(), 1e-9)); + EXPECT(assert_equal(Point3(0, 0, 0), T10.translation(), 1e-9)); +} + +/* ************************************************************************* */ +TEST(Scenario, Forward) { + const double v = 2; // m/s + const Vector3 W(0, 0, 0), V(v, 0, 0); + const ConstantTwistScenario scenario(W, V); + + const double T = 15; + EXPECT(assert_equal(W, scenario.omega_b(T), 1e-9)); + EXPECT(assert_equal(V, scenario.velocity_b(T), 1e-9)); + EXPECT(assert_equal(W.cross(V), scenario.acceleration_b(T), 1e-9)); + + const Pose3 T15 = scenario.pose(T); + EXPECT(assert_equal(Vector3(0, 0, 0), T15.rotation().xyz(), 1e-9)); + EXPECT(assert_equal(Point3(30, 0, 0), T15.translation(), 1e-9)); +} + +/* ************************************************************************* */ +TEST(Scenario, Circle) { + // Forward velocity 2m/s, angular velocity 6 kDegree/sec around Z + const double v = 2, w = 6 * kDegree; + const Vector3 W(0, 0, w), V(v, 0, 0); + const ConstantTwistScenario scenario(W, V); + + const double T = 15; + EXPECT(assert_equal(W, scenario.omega_b(T), 1e-9)); + EXPECT(assert_equal(V, scenario.velocity_b(T), 1e-9)); + EXPECT(assert_equal(W.cross(V), scenario.acceleration_b(T), 1e-9)); + + // R = v/w, so test if circle is of right size + const double R = v / w; + const Pose3 T15 = scenario.pose(T); + EXPECT(assert_equal(Vector3(0, 0, 90 * kDegree), T15.rotation().xyz(), 1e-9)); + EXPECT(assert_equal(Point3(R, R, 0), T15.translation(), 1e-9)); +} + +/* ************************************************************************* */ +TEST(Scenario, Loop) { + // Forward velocity 2m/s + // Pitch up with angular velocity 6 kDegree/sec (negative in FLU) + const double v = 2, w = 6 * kDegree; + const Vector3 W(0, -w, 0), V(v, 0, 0); + const ConstantTwistScenario scenario(W, V); + + const double T = 30; + EXPECT(assert_equal(W, scenario.omega_b(T), 1e-9)); + EXPECT(assert_equal(V, scenario.velocity_b(T), 1e-9)); + EXPECT(assert_equal(W.cross(V), scenario.acceleration_b(T), 1e-9)); + + // R = v/w, so test if loop crests at 2*R + const double R = v / w; + const Pose3 T30 = scenario.pose(30); + EXPECT(assert_equal(Rot3::Rodrigues(0, M_PI, 0), T30.rotation(), 1e-9)); + EXPECT(assert_equal(Point3(0, 0, 2 * R), T30.translation(), 1e-9)); +} + +/* ************************************************************************* */ +TEST(Scenario, Accelerating) { + // Set up body pointing towards y axis, and start at 10,20,0 with velocity + // going in X. The body itself has Z axis pointing down + const Rot3 nRb(Point3(0, 1, 0), Point3(1, 0, 0), Point3(0, 0, -1)); + const Point3 P0(10, 20, 0); + const Vector3 V0(50, 0, 0); + + const double a = 0.2; // m/s^2 + const Vector3 A(0, a, 0), W(0.1, 0.2, 0.3); + const AcceleratingScenario scenario(nRb, P0, V0, A, W); + + const double T = 3; + EXPECT(assert_equal(W, scenario.omega_b(T), 1e-9)); + EXPECT(assert_equal(Vector3(V0 + T * A), scenario.velocity_n(T), 1e-9)); + EXPECT(assert_equal(A, scenario.acceleration_n(T), 1e-9)); + + { + // Check acceleration in nav + Matrix expected = numericalDerivative11( + boost::bind(&Scenario::velocity_n, scenario, _1), T); + EXPECT(assert_equal(Vector3(expected), scenario.acceleration_n(T), 1e-9)); + } + + const Pose3 T3 = scenario.pose(3); + EXPECT(assert_equal(nRb.expmap(T * W), T3.rotation(), 1e-9)); + EXPECT(assert_equal(Point3(10 + T * 50, 20 + a * T * T / 2, 0), + T3.translation(), 1e-9)); +} + +/* ************************************************************************* */ +int main() { + TestResult tr; + return TestRegistry::runAllTests(tr); +} +/* ************************************************************************* */ diff --git a/gtsam/navigation/tests/testScenarios.cpp b/gtsam/navigation/tests/testScenarios.cpp new file mode 100644 index 000000000..c2fdb963d --- /dev/null +++ b/gtsam/navigation/tests/testScenarios.cpp @@ -0,0 +1,385 @@ +/* ---------------------------------------------------------------------------- + + * 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 testScenarioRunner.cpp + * @brief test ImuFacor with ScenarioRunner class + * @author Frank Dellaert + */ + +#include +#include +#include +#include + +using namespace std; +using namespace gtsam; + +static const double kDegree = M_PI / 180.0; +static const double kDt = 1e-2; + +// realistic white noise strengths are 0.5 deg/sqrt(hr) and 0.1 (m/s)/sqrt(h) +static const double kGyroSigma = 0.5 * kDegree / 60; +static const double kAccelSigma = 0.1 / 60.0; + +static const Vector3 kAccBias(0.2, 0, 0), kRotBias(0.1, 0, 0.3); +static const imuBias::ConstantBias kNonZeroBias(kAccBias, kRotBias); + +// Create default parameters with Z-up and above noise parameters +static boost::shared_ptr defaultParams() { + auto p = PreintegrationParams::MakeSharedU(10); + p->gyroscopeCovariance = kGyroSigma * kGyroSigma * I_3x3; + p->accelerometerCovariance = kAccelSigma * kAccelSigma * I_3x3; + p->integrationCovariance = 0.0000001 * I_3x3; + return p; +} + +#define EXPECT_NEAR(a, b, c) EXPECT(assert_equal(Vector(a), Vector(b), c)); + +/* ************************************************************************* */ +TEST(ScenarioRunner, Spin) { + // angular velocity 6 degree/sec + const double w = 6 * kDegree; + const Vector3 W(0, 0, w), V(0, 0, 0); + const ConstantTwistScenario scenario(W, V); + + auto p = defaultParams(); + ScenarioRunner runner(&scenario, p, kDt); + const double T = 2 * kDt; // seconds + + auto pim = runner.integrate(T); + EXPECT(assert_equal(scenario.pose(T), runner.predict(pim).pose(), 1e-9)); + +#if 0 + // Check sampled noise is kosher + Matrix6 expected; + expected << p->accelerometerCovariance / kDt, Z_3x3, // + Z_3x3, p->gyroscopeCovariance / kDt; + Matrix6 actual = runner.estimateNoiseCovariance(10000); + EXPECT(assert_equal(expected, actual, 1e-2)); +#endif + + // Check calculated covariance against Monte Carlo estimate + Matrix9 estimatedCov = runner.estimateCovariance(T); + EXPECT(assert_equal(estimatedCov, pim.preintMeasCov(), 1e-5)); +} + +/* ************************************************************************* */ +namespace forward { +const double v = 2; // m/s +ConstantTwistScenario scenario(Vector3::Zero(), Vector3(v, 0, 0)); +} +/* ************************************************************************* */ +TEST(ScenarioRunner, Forward) { + using namespace forward; + ScenarioRunner runner(&scenario, defaultParams(), kDt); + const double T = 0.1; // seconds + + auto pim = runner.integrate(T); + EXPECT(assert_equal(scenario.pose(T), runner.predict(pim).pose(), 1e-9)); + + Matrix9 estimatedCov = runner.estimateCovariance(T); + EXPECT_NEAR(estimatedCov.diagonal(), pim.preintMeasCov().diagonal(), 0.1); + EXPECT(assert_equal(estimatedCov, pim.preintMeasCov(), 1e-5)); +} + +/* ************************************************************************* */ +TEST(ScenarioRunner, ForwardWithBias) { + using namespace forward; + ScenarioRunner runner(&scenario, defaultParams(), kDt); + const double T = 0.1; // seconds + + auto pim = runner.integrate(T, kNonZeroBias); + Matrix9 estimatedCov = runner.estimateCovariance(T, 1000, kNonZeroBias); + EXPECT(assert_equal(estimatedCov, pim.preintMeasCov(), 0.1)); +} + +/* ************************************************************************* */ +TEST(ScenarioRunner, Circle) { + // Forward velocity 2m/s, angular velocity 6 degree/sec + const double v = 2, w = 6 * kDegree; + ConstantTwistScenario scenario(Vector3(0, 0, w), Vector3(v, 0, 0)); + + ScenarioRunner runner(&scenario, defaultParams(), kDt); + const double T = 0.1; // seconds + + auto pim = runner.integrate(T); + EXPECT(assert_equal(scenario.pose(T), runner.predict(pim).pose(), 0.1)); + + Matrix9 estimatedCov = runner.estimateCovariance(T); + EXPECT_NEAR(estimatedCov.diagonal(), pim.preintMeasCov().diagonal(), 0.1); + EXPECT(assert_equal(estimatedCov, pim.preintMeasCov(), 1e-5)); +} + +/* ************************************************************************* */ +TEST(ScenarioRunner, Loop) { + // Forward velocity 2m/s + // Pitch up with angular velocity 6 degree/sec (negative in FLU) + const double v = 2, w = 6 * kDegree; + ConstantTwistScenario scenario(Vector3(0, -w, 0), Vector3(v, 0, 0)); + + ScenarioRunner runner(&scenario, defaultParams(), kDt); + const double T = 0.1; // seconds + + auto pim = runner.integrate(T); + EXPECT(assert_equal(scenario.pose(T), runner.predict(pim).pose(), 0.1)); + + Matrix9 estimatedCov = runner.estimateCovariance(T); + EXPECT_NEAR(estimatedCov.diagonal(), pim.preintMeasCov().diagonal(), 0.1); + EXPECT(assert_equal(estimatedCov, pim.preintMeasCov(), 1e-5)); +} + +/* ************************************************************************* */ +namespace initial { +const Rot3 nRb; +const Point3 P0; +const Vector3 V0(0, 0, 0); +} + +/* ************************************************************************* */ +namespace accelerating { +using namespace initial; +const double a = 0.2; // m/s^2 +const Vector3 A(0, a, 0); +const AcceleratingScenario scenario(nRb, P0, V0, A); + +const double T = 3; // seconds +} + +/* ************************************************************************* */ +TEST(ScenarioRunner, Accelerating) { + using namespace accelerating; + ScenarioRunner runner(&scenario, defaultParams(), T / 10); + + auto pim = runner.integrate(T); + EXPECT(assert_equal(scenario.pose(T), runner.predict(pim).pose(), 1e-9)); + + Matrix9 estimatedCov = runner.estimateCovariance(T); + EXPECT_NEAR(estimatedCov.diagonal(), pim.preintMeasCov().diagonal(), 0.1); + EXPECT(assert_equal(estimatedCov, pim.preintMeasCov(), 0.1)); +} + +/* ************************************************************************* */ +TEST(ScenarioRunner, AcceleratingWithBias) { + using namespace accelerating; + ScenarioRunner runner(&scenario, defaultParams(), T / 10, kNonZeroBias); + + auto pim = runner.integrate(T, kNonZeroBias); + Matrix9 estimatedCov = runner.estimateCovariance(T, 10000, kNonZeroBias); + EXPECT(assert_equal(estimatedCov, pim.preintMeasCov(), 0.1)); +} + +/* ************************************************************************* */ +TEST(ScenarioRunner, AcceleratingAndRotating) { + using namespace initial; + const double a = 0.2; // m/s^2 + const Vector3 A(0, a, 0), W(0, 0.1, 0); + const AcceleratingScenario scenario(nRb, P0, V0, A, W); + + const double T = 10; // seconds + ScenarioRunner runner(&scenario, defaultParams(), T / 10); + + auto pim = runner.integrate(T); + EXPECT(assert_equal(scenario.pose(T), runner.predict(pim).pose(), 1e-9)); + + Matrix9 estimatedCov = runner.estimateCovariance(T); + EXPECT_NEAR(estimatedCov.diagonal(), pim.preintMeasCov().diagonal(), 0.1); + EXPECT(assert_equal(estimatedCov, pim.preintMeasCov(), 0.1)); +} + +/* ************************************************************************* */ +namespace initial2 { +// No rotation, but non-zero position and velocities +const Rot3 nRb; +const Point3 P0(10, 20, 0); +const Vector3 V0(50, 0, 0); +} + +/* ************************************************************************* */ +namespace accelerating2 { +using namespace initial2; +const double a = 0.2; // m/s^2 +const Vector3 A(0, a, 0); +const AcceleratingScenario scenario(nRb, P0, V0, A); + +const double T = 3; // seconds +} + +/* ************************************************************************* */ +TEST(ScenarioRunner, Accelerating2) { + using namespace accelerating2; + ScenarioRunner runner(&scenario, defaultParams(), T / 10); + + auto pim = runner.integrate(T); + EXPECT(assert_equal(scenario.pose(T), runner.predict(pim).pose(), 1e-9)); + + Matrix9 estimatedCov = runner.estimateCovariance(T); + EXPECT_NEAR(estimatedCov.diagonal(), pim.preintMeasCov().diagonal(), 0.1); + EXPECT(assert_equal(estimatedCov, pim.preintMeasCov(), 0.1)); +} + +/* ************************************************************************* */ +TEST(ScenarioRunner, AcceleratingWithBias2) { + using namespace accelerating2; + ScenarioRunner runner(&scenario, defaultParams(), T / 10, kNonZeroBias); + + auto pim = runner.integrate(T, kNonZeroBias); + Matrix9 estimatedCov = runner.estimateCovariance(T, 10000, kNonZeroBias); + EXPECT(assert_equal(estimatedCov, pim.preintMeasCov(), 0.1)); +} + +/* ************************************************************************* */ +TEST(ScenarioRunner, AcceleratingAndRotating2) { + using namespace initial2; + const double a = 0.2; // m/s^2 + const Vector3 A(0, a, 0), W(0, 0.1, 0); + const AcceleratingScenario scenario(nRb, P0, V0, A, W); + + const double T = 10; // seconds + ScenarioRunner runner(&scenario, defaultParams(), T / 10); + + auto pim = runner.integrate(T); + EXPECT(assert_equal(scenario.pose(T), runner.predict(pim).pose(), 1e-9)); + + Matrix9 estimatedCov = runner.estimateCovariance(T); + EXPECT_NEAR(estimatedCov.diagonal(), pim.preintMeasCov().diagonal(), 0.1); + EXPECT(assert_equal(estimatedCov, pim.preintMeasCov(), 0.1)); +} + +/* ************************************************************************* */ +namespace initial3 { +// Rotation only +// Set up body pointing towards y axis. The body itself has Z axis pointing down +const Rot3 nRb(Point3(0, 1, 0), Point3(1, 0, 0), Point3(0, 0, -1)); +const Point3 P0; +const Vector3 V0(0, 0, 0); +} + +/* ************************************************************************* */ +namespace accelerating3 { +using namespace initial3; +const double a = 0.2; // m/s^2 +const Vector3 A(0, a, 0); +const AcceleratingScenario scenario(nRb, P0, V0, A); + +const double T = 3; // seconds +} + +/* ************************************************************************* */ +TEST(ScenarioRunner, Accelerating3) { + using namespace accelerating3; + ScenarioRunner runner(&scenario, defaultParams(), T / 10); + + auto pim = runner.integrate(T); + EXPECT(assert_equal(scenario.pose(T), runner.predict(pim).pose(), 1e-9)); + + Matrix9 estimatedCov = runner.estimateCovariance(T); + EXPECT_NEAR(estimatedCov.diagonal(), pim.preintMeasCov().diagonal(), 0.1); + EXPECT(assert_equal(estimatedCov, pim.preintMeasCov(), 0.1)); +} + +/* ************************************************************************* */ +TEST(ScenarioRunner, AcceleratingWithBias3) { + using namespace accelerating3; + ScenarioRunner runner(&scenario, defaultParams(), T / 10, kNonZeroBias); + + auto pim = runner.integrate(T, kNonZeroBias); + Matrix9 estimatedCov = runner.estimateCovariance(T, 10000, kNonZeroBias); + EXPECT(assert_equal(estimatedCov, pim.preintMeasCov(), 0.1)); +} + +/* ************************************************************************* */ +TEST(ScenarioRunner, AcceleratingAndRotating3) { + using namespace initial3; + const double a = 0.2; // m/s^2 + const Vector3 A(0, a, 0), W(0, 0.1, 0); + const AcceleratingScenario scenario(nRb, P0, V0, A, W); + + const double T = 10; // seconds + ScenarioRunner runner(&scenario, defaultParams(), T / 10); + + auto pim = runner.integrate(T); + EXPECT(assert_equal(scenario.pose(T), runner.predict(pim).pose(), 1e-9)); + + Matrix9 estimatedCov = runner.estimateCovariance(T); + EXPECT_NEAR(estimatedCov.diagonal(), pim.preintMeasCov().diagonal(), 0.1); + EXPECT(assert_equal(estimatedCov, pim.preintMeasCov(), 0.1)); +} + +/* ************************************************************************* */ +namespace initial4 { +// Both rotation and translation +// Set up body pointing towards y axis, and start at 10,20,0 with velocity +// going in X. The body itself has Z axis pointing down +const Rot3 nRb(Point3(0, 1, 0), Point3(1, 0, 0), Point3(0, 0, -1)); +const Point3 P0(10, 20, 0); +const Vector3 V0(50, 0, 0); +} + +/* ************************************************************************* */ +namespace accelerating4 { +using namespace initial4; +const double a = 0.2; // m/s^2 +const Vector3 A(0, a, 0); +const AcceleratingScenario scenario(nRb, P0, V0, A); + +const double T = 3; // seconds +} + +/* ************************************************************************* */ +TEST(ScenarioRunner, Accelerating4) { + using namespace accelerating4; + ScenarioRunner runner(&scenario, defaultParams(), T / 10); + + auto pim = runner.integrate(T); + EXPECT(assert_equal(scenario.pose(T), runner.predict(pim).pose(), 1e-9)); + + Matrix9 estimatedCov = runner.estimateCovariance(T); + EXPECT_NEAR(estimatedCov.diagonal(), pim.preintMeasCov().diagonal(), 0.1); + EXPECT(assert_equal(estimatedCov, pim.preintMeasCov(), 0.1)); +} + +/* ************************************************************************* */ +TEST(ScenarioRunner, AcceleratingWithBias4) { + using namespace accelerating4; + ScenarioRunner runner(&scenario, defaultParams(), T / 10, kNonZeroBias); + + auto pim = runner.integrate(T, kNonZeroBias); + Matrix9 estimatedCov = runner.estimateCovariance(T, 10000, kNonZeroBias); + EXPECT(assert_equal(estimatedCov, pim.preintMeasCov(), 0.1)); +} + +/* ************************************************************************* */ +TEST(ScenarioRunner, AcceleratingAndRotating4) { + using namespace initial4; + const double a = 0.2; // m/s^2 + const Vector3 A(0, a, 0), W(0, 0.1, 0); + const AcceleratingScenario scenario(nRb, P0, V0, A, W); + + const double T = 10; // seconds + ScenarioRunner runner(&scenario, defaultParams(), T / 10); + + auto pim = runner.integrate(T); + EXPECT(assert_equal(scenario.pose(T), runner.predict(pim).pose(), 1e-9)); + + Matrix9 estimatedCov = runner.estimateCovariance(T); + EXPECT_NEAR(estimatedCov.diagonal(), pim.preintMeasCov().diagonal(), 0.1); + EXPECT(assert_equal(estimatedCov, pim.preintMeasCov(), 0.1)); +} + +/* ************************************************************************* */ +int main() { + TestResult tr; + auto result = TestRegistry::runAllTests(tr); + tictoc_print_(); + return result; +} +/* ************************************************************************* */ diff --git a/gtsam/nonlinear/AdaptAutoDiff.h b/gtsam/nonlinear/AdaptAutoDiff.h index 7295f3160..ff059ef78 100644 --- a/gtsam/nonlinear/AdaptAutoDiff.h +++ b/gtsam/nonlinear/AdaptAutoDiff.h @@ -1,6 +1,6 @@ /* ---------------------------------------------------------------------------- - * GTSAM Copyright 2010, Georgia Tech Research Corporation, + * 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) @@ -27,92 +27,46 @@ namespace gtsam { -namespace detail { - -// By default, we assume an Identity element -template -struct Origin { T operator()() { return traits::Identity();} }; - -// but dimple manifolds don't have one, so we just use the default constructor -template -struct Origin { T operator()() { return T();} }; - -} // \ detail - /** - * Canonical is a template that creates canonical coordinates for a given type. - * A simple manifold type (i.e., not a Lie Group) has no concept of identity, - * hence in that case we use the value given by the default constructor T() as - * the origin of a "canonical coordinate" parameterization. + * The AdaptAutoDiff class uses ceres-style autodiff to adapt a ceres-style + * Function evaluation, i.e., a function FUNCTOR that defines an operator + * template bool operator()(const T* const, const T* const, T* + * predicted) const; + * For now only binary operators are supported. */ -template -struct Canonical { - - GTSAM_CONCEPT_MANIFOLD_TYPE(T) - - typedef traits Traits; - enum { dimension = Traits::dimension }; - typedef typename Traits::TangentVector TangentVector; - typedef typename Traits::structure_category Category; - typedef detail::Origin Origin; - - static TangentVector Local(const T& other) { - return Traits::Local(Origin()(), other); - } - - static T Retract(const TangentVector& v) { - return Traits::Retract(Origin()(), v); - } -}; - -/// Adapt ceres-style autodiff -template +template class AdaptAutoDiff { + typedef Eigen::Matrix RowMajor1; + typedef Eigen::Matrix RowMajor2; - static const int N = traits::dimension; - static const int M1 = traits::dimension; - static const int M2 = traits::dimension; + typedef Eigen::Matrix VectorT; + typedef Eigen::Matrix Vector1; + typedef Eigen::Matrix Vector2; - typedef Eigen::Matrix RowMajor1; - typedef Eigen::Matrix RowMajor2; - - typedef Canonical CanonicalT; - typedef Canonical Canonical1; - typedef Canonical Canonical2; - - typedef typename CanonicalT::TangentVector VectorT; - typedef typename Canonical1::TangentVector Vector1; - typedef typename Canonical2::TangentVector Vector2; - - F f; - -public: - - T operator()(const A1& a1, const A2& a2, OptionalJacobian H1 = boost::none, - OptionalJacobian H2 = boost::none) { + FUNCTOR f; + public: + VectorT operator()(const Vector1& v1, const Vector2& v2, + OptionalJacobian H1 = boost::none, + OptionalJacobian H2 = boost::none) { using ceres::internal::AutoDiff; - // Make arguments - Vector1 v1 = Canonical1::Local(a1); - Vector2 v2 = Canonical2::Local(a2); - bool success; VectorT result; if (H1 || H2) { - // Get derivatives with AutoDiff - double *parameters[] = { v1.data(), v2.data() }; - double rowMajor1[N * M1], rowMajor2[N * M2]; // om the stack - double *jacobians[] = { rowMajor1, rowMajor2 }; - success = AutoDiff::Differentiate(f, parameters, 2, - result.data(), jacobians); + const double* parameters[] = {v1.data(), v2.data()}; + double rowMajor1[M * N1], rowMajor2[M * N2]; // on the stack + double* jacobians[] = {rowMajor1, rowMajor2}; + success = AutoDiff::Differentiate( + f, parameters, M, result.data(), jacobians); // Convert from row-major to columnn-major - // TODO: if this is a bottleneck (probably not!) fix Autodiff to be Column-Major - *H1 = Eigen::Map(rowMajor1); - *H2 = Eigen::Map(rowMajor2); + // TODO: if this is a bottleneck (probably not!) fix Autodiff to be + // Column-Major + if (H1) *H1 = Eigen::Map(rowMajor1); + if (H2) *H2 = Eigen::Map(rowMajor2); } else { // Apply the mapping, to get result @@ -121,9 +75,8 @@ public: if (!success) throw std::runtime_error( "AdaptAutoDiff: function call resulted in failure"); - return CanonicalT::Retract(result); + return result; } - }; -} +} // namespace gtsam diff --git a/gtsam/nonlinear/DoglegOptimizer.cpp b/gtsam/nonlinear/DoglegOptimizer.cpp index e148bd65d..a91515e9c 100644 --- a/gtsam/nonlinear/DoglegOptimizer.cpp +++ b/gtsam/nonlinear/DoglegOptimizer.cpp @@ -95,8 +95,8 @@ void DoglegOptimizer::iterate(void) { /* ************************************************************************* */ DoglegParams DoglegOptimizer::ensureHasOrdering(DoglegParams params, const NonlinearFactorGraph& graph) const { - if(!params.ordering) - params.ordering = Ordering::colamd(graph); + if (!params.ordering) + params.ordering = Ordering::Create(params.orderingType, graph); return params; } diff --git a/gtsam/nonlinear/Expression-inl.h b/gtsam/nonlinear/Expression-inl.h index 6c6c155c7..70a872d15 100644 --- a/gtsam/nonlinear/Expression-inl.h +++ b/gtsam/nonlinear/Expression-inl.h @@ -29,7 +29,7 @@ namespace gtsam { template void Expression::print(const std::string& s) const { - std::cout << s << *root_ << std::endl; + root_->print(s); } template @@ -155,7 +155,7 @@ size_t Expression::traceSize() const { template T Expression::valueAndDerivatives(const Values& values, - const FastVector& keys, const FastVector& dims, + const KeyVector& keys, const FastVector& dims, std::vector& H) const { // H should be pre-allocated @@ -219,7 +219,7 @@ typename Expression::KeysAndDims Expression::keysAndDims() const { std::map map; dims(map); size_t n = map.size(); - KeysAndDims pair = std::make_pair(FastVector(n), FastVector(n)); + KeysAndDims pair = std::make_pair(KeyVector(n), FastVector(n)); boost::copy(map | boost::adaptors::map_keys, pair.first.begin()); boost::copy(map | boost::adaptors::map_values, pair.second.begin()); return pair; diff --git a/gtsam/nonlinear/Expression.h b/gtsam/nonlinear/Expression.h index d24a568f5..0b348ece9 100644 --- a/gtsam/nonlinear/Expression.h +++ b/gtsam/nonlinear/Expression.h @@ -172,12 +172,15 @@ public: private: + /// Default constructor, for serialization + Expression() {} + /// Keys and dimensions in same order - typedef std::pair, FastVector > KeysAndDims; + typedef std::pair > KeysAndDims; KeysAndDims keysAndDims() const; /// private version that takes keys and dimensions, returns derivatives - T valueAndDerivatives(const Values& values, const FastVector& keys, + T valueAndDerivatives(const Values& values, const KeyVector& keys, const FastVector& dims, std::vector& H) const; /// trace execution, very unsafe diff --git a/gtsam/nonlinear/ExpressionFactor.h b/gtsam/nonlinear/ExpressionFactor.h index b32b84df3..21e17a648 100644 --- a/gtsam/nonlinear/ExpressionFactor.h +++ b/gtsam/nonlinear/ExpressionFactor.h @@ -1,6 +1,6 @@ /* ---------------------------------------------------------------------------- - * GTSAM Copyright 2010, Georgia Tech Research Corporation, + * 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) @@ -27,43 +27,55 @@ namespace gtsam { /** + * Factor that supports arbitrary expressions via AD */ -template +template class ExpressionFactor: public NoiseModelFactor { + BOOST_CONCEPT_ASSERT((IsTestable)); - protected: +protected: typedef ExpressionFactor This; - - T measurement_; ///< the measurement to be compared with the expression - Expression expression_; ///< the expression that is AD enabled - FastVector dims_; ///< dimensions of the Jacobian matrices - static const int Dim = traits::dimension; - public: + T measured_; ///< the measurement to be compared with the expression + Expression expression_; ///< the expression that is AD enabled + FastVector dims_; ///< dimensions of the Jacobian matrices + +public: typedef boost::shared_ptr > shared_ptr; /// Constructor - ExpressionFactor(const SharedNoiseModel& noiseModel, // - const T& measurement, const Expression& expression) : - measurement_(measurement), expression_(expression) { - if (!noiseModel) - throw std::invalid_argument("ExpressionFactor: no NoiseModel."); - if (noiseModel->dim() != Dim) - throw std::invalid_argument( - "ExpressionFactor was created with a NoiseModel of incorrect dimension."); - noiseModel_ = noiseModel; + ExpressionFactor(const SharedNoiseModel& noiseModel, // + const T& measurement, const Expression& expression) + : NoiseModelFactor(noiseModel), measured_(measurement) { + initialize(expression); + } - // Get keys and dimensions for Jacobian matrices - // An Expression is assumed unmutable, so we do this now - boost::tie(keys_, dims_) = expression_.keysAndDims(); + /// Destructor + virtual ~ExpressionFactor() {} + + /** return the measurement */ + const T& measured() const { return measured_; } + + /// print relies on Testable traits being defined for T + void print(const std::string& s, const KeyFormatter& keyFormatter) const { + NoiseModelFactor::print(s, keyFormatter); + traits::Print(measured_, s + ".measured_"); + } + + /// equals relies on Testable traits being defined for T + bool equals(const NonlinearFactor& f, double tol) const { + const ExpressionFactor* p = dynamic_cast(&f); + return p && NoiseModelFactor::equals(f, tol) && + traits::Equals(measured_, p->measured_, tol) && + dims_ == p->dims_; } /** - * Error function *without* the NoiseModel, \f$ h(x)-z \f$. + * Error function *without* the NoiseModel, \f$ z-h(x) -> Local(h(x),z) \f$. * We override this method to provide * both the function evaluation and its derivative(s) in H. */ @@ -71,10 +83,12 @@ class ExpressionFactor: public NoiseModelFactor { boost::optional&> H = boost::none) const { if (H) { const T value = expression_.valueAndDerivatives(x, keys_, dims_, *H); - return traits::Local(measurement_, value); + // NOTE(hayk): Doing the reverse, AKA Local(measured_, value) is not correct here + // because it would use the tangent space of the measurement instead of the value. + return -traits::Local(value, measured_); } else { const T value = expression_.value(x); - return traits::Local(measurement_, value); + return -traits::Local(value, measured_); } } @@ -83,13 +97,16 @@ class ExpressionFactor: public NoiseModelFactor { if (!active(x)) return boost::shared_ptr(); - // Create a writeable JacobianFactor in advance // In case noise model is constrained, we need to provide a noise model - bool constrained = noiseModel_->isConstrained(); + SharedDiagonal noiseModel; + if (noiseModel_ && noiseModel_->isConstrained()) { + noiseModel = boost::static_pointer_cast( + noiseModel_)->unit(); + } + + // Create a writeable JacobianFactor in advance boost::shared_ptr factor( - constrained ? new JacobianFactor(keys_, dims_, Dim, - boost::static_pointer_cast(noiseModel_)->unit()) : - new JacobianFactor(keys_, dims_, Dim)); + new JacobianFactor(keys_, dims_, Dim, noiseModel)); // Wrap keys and VerticalBlockMatrix into structure passed to expression_ VerticalBlockMatrix& Ab = factor->matrixObject(); @@ -102,11 +119,13 @@ class ExpressionFactor: public NoiseModelFactor { T value = expression_.valueAndJacobianMap(x, jacobianMap); // <<< Reverse AD happens here ! // Evaluate error and set RHS vector b - Ab(size()).col(0) = -traits::Local(measurement_, value); + Ab(size()).col(0) = traits::Local(value, measured_); // Whiten the corresponding system, Ab already contains RHS - Vector b = Ab(size()).col(0); // need b to be valid for Robust noise models - noiseModel_->WhitenSystem(Ab.matrix(), b); + if (noiseModel_) { + Vector b = Ab(size()).col(0); // need b to be valid for Robust noise models + noiseModel_->WhitenSystem(Ab.matrix(), b); + } return factor; } @@ -114,9 +133,118 @@ class ExpressionFactor: public NoiseModelFactor { /// @return a deep copy of this factor virtual gtsam::NonlinearFactor::shared_ptr clone() const { return boost::static_pointer_cast( - gtsam::NonlinearFactor::shared_ptr(new This(*this))); } + gtsam::NonlinearFactor::shared_ptr(new This(*this))); + } + +protected: + ExpressionFactor() {} + /// Default constructor, for serialization + + /// Constructor for serializable derived classes + ExpressionFactor(const SharedNoiseModel& noiseModel, const T& measurement) + : NoiseModelFactor(noiseModel), measured_(measurement) { + // Not properly initialized yet, need to call initialize + } + + /// Initialize with constructor arguments + void initialize(const Expression& expression) { + if (!noiseModel_) + throw std::invalid_argument("ExpressionFactor: no NoiseModel."); + if (noiseModel_->dim() != Dim) + throw std::invalid_argument( + "ExpressionFactor was created with a NoiseModel of incorrect dimension."); + expression_ = expression; + + // Get keys and dimensions for Jacobian matrices + // An Expression is assumed unmutable, so we do this now + boost::tie(keys_, dims_) = expression_.keysAndDims(); + } + + /// Recreate expression from keys_ and measured_, used in load below. + /// Needed to deserialize a derived factor + virtual Expression expression() const { + throw std::runtime_error("ExpressionFactor::expression not provided: cannot deserialize."); + } + +private: + /// Save to an archive: just saves the base class + template + void save(Archive& ar, const unsigned int /*version*/) const { + ar << BOOST_SERIALIZATION_BASE_OBJECT_NVP(NoiseModelFactor); + ar << boost::serialization::make_nvp("measured_", this->measured_); + } + + /// Load from an archive, creating a valid expression using the overloaded + /// [expression] method + template + void load(Archive& ar, const unsigned int /*version*/) { + ar >> BOOST_SERIALIZATION_BASE_OBJECT_NVP(NoiseModelFactor); + ar >> boost::serialization::make_nvp("measured_", this->measured_); + this->initialize(expression()); + } + + // Indicate that we implement save/load separately, and be friendly to boost + BOOST_SERIALIZATION_SPLIT_MEMBER() + + friend class boost::serialization::access; }; // ExpressionFactor +/// traits +template +struct traits > : public Testable > {}; + +/** + * Binary specialization of ExpressionFactor meant as a base class for binary factors + * Enforces expression method with two keys, and provides evaluateError + * Derived needs to call initialize. + */ +template +class ExpressionFactor2 : public ExpressionFactor { + public: + /// Destructor + virtual ~ExpressionFactor2() {} + + /// Backwards compatible evaluateError, to make existing tests compile + Vector evaluateError(const A1& a1, const A2& a2, + boost::optional H1 = boost::none, + boost::optional H2 = boost::none) const { + Values values; + values.insert(this->keys_[0], a1); + values.insert(this->keys_[1], a2); + std::vector H(2); + Vector error = this->unwhitenedError(values, H); + if (H1) (*H1) = H[0]; + if (H2) (*H2) = H[1]; + return error; + } + + /// Recreate expression from given keys_ and measured_, used in load + /// Needed to deserialize a derived factor + virtual Expression expression(Key key1, Key key2) const { + throw std::runtime_error("ExpressionFactor2::expression not provided: cannot deserialize."); + } + + protected: + /// Default constructor, for serialization + ExpressionFactor2() {} + + /// Constructor takes care of keys, but still need to call initialize + ExpressionFactor2(Key key1, Key key2, + const SharedNoiseModel& noiseModel, + const T& measurement) + : ExpressionFactor(noiseModel, measurement) { + this->keys_.push_back(key1); + this->keys_.push_back(key2); + } + + private: + /// Return an expression that predicts the measurement given Values + virtual Expression expression() const { + return expression(this->keys_[0], this->keys_[1]); + } +}; +// ExpressionFactor2 + }// \ namespace gtsam diff --git a/gtsam/nonlinear/GaussNewtonOptimizer.cpp b/gtsam/nonlinear/GaussNewtonOptimizer.cpp index 7a115e1c4..e420567ec 100644 --- a/gtsam/nonlinear/GaussNewtonOptimizer.cpp +++ b/gtsam/nonlinear/GaussNewtonOptimizer.cpp @@ -46,10 +46,9 @@ void GaussNewtonOptimizer::iterate() { /* ************************************************************************* */ GaussNewtonParams GaussNewtonOptimizer::ensureHasOrdering( - GaussNewtonParams params, const NonlinearFactorGraph& graph) const -{ - if(!params.ordering) - params.ordering = Ordering::colamd(graph); + GaussNewtonParams params, const NonlinearFactorGraph& graph) const { + if (!params.ordering) + params.ordering = Ordering::Create(params.orderingType, graph); return params; } diff --git a/gtsam/nonlinear/ISAM2-impl.cpp b/gtsam/nonlinear/ISAM2-impl.cpp index 41ee52b3a..4e8c0e303 100644 --- a/gtsam/nonlinear/ISAM2-impl.cpp +++ b/gtsam/nonlinear/ISAM2-impl.cpp @@ -19,6 +19,8 @@ #include #include // for selective linearization thresholds #include +#include // for GTSAM_USE_TBB + #include #include @@ -84,11 +86,11 @@ void ISAM2::Impl::AddFactorsStep1(const NonlinearFactorGraph& newFactors, bool u } /* ************************************************************************* */ -void ISAM2::Impl::RemoveVariables(const FastSet& unusedKeys, const FastVector& roots, +void ISAM2::Impl::RemoveVariables(const KeySet& unusedKeys, const FastVector& roots, Values& theta, VariableIndex& variableIndex, VectorValues& delta, VectorValues& deltaNewton, VectorValues& RgProd, - FastSet& replacedKeys, Base::Nodes& nodes, - FastSet& fixedVariables) + KeySet& replacedKeys, Base::Nodes& nodes, + KeySet& fixedVariables) { variableIndex.removeUnusedVariables(unusedKeys.begin(), unusedKeys.end()); BOOST_FOREACH(Key key, unusedKeys) { @@ -103,10 +105,10 @@ void ISAM2::Impl::RemoveVariables(const FastSet& unusedKeys, const FastVect } /* ************************************************************************* */ -FastSet ISAM2::Impl::CheckRelinearizationFull(const VectorValues& delta, +KeySet ISAM2::Impl::CheckRelinearizationFull(const VectorValues& delta, const ISAM2Params::RelinearizationThreshold& relinearizeThreshold) { - FastSet relinKeys; + KeySet relinKeys; if(const double* threshold = boost::get(&relinearizeThreshold)) { @@ -131,7 +133,7 @@ FastSet ISAM2::Impl::CheckRelinearizationFull(const VectorValues& delta, } /* ************************************************************************* */ -void CheckRelinearizationRecursiveDouble(FastSet& relinKeys, double threshold, +void CheckRelinearizationRecursiveDouble(KeySet& relinKeys, double threshold, const VectorValues& delta, const ISAM2Clique::shared_ptr& clique) { // Check the current clique for relinearization @@ -153,7 +155,7 @@ void CheckRelinearizationRecursiveDouble(FastSet& relinKeys, double thresho } /* ************************************************************************* */ -void CheckRelinearizationRecursiveMap(FastSet& relinKeys, const FastMap& thresholds, +void CheckRelinearizationRecursiveMap(KeySet& relinKeys, const FastMap& thresholds, const VectorValues& delta, const ISAM2Clique::shared_ptr& clique) { @@ -185,11 +187,11 @@ void CheckRelinearizationRecursiveMap(FastSet& relinKeys, const FastMap ISAM2::Impl::CheckRelinearizationPartial(const FastVector& roots, +KeySet ISAM2::Impl::CheckRelinearizationPartial(const FastVector& roots, const VectorValues& delta, const ISAM2Params::RelinearizationThreshold& relinearizeThreshold) { - FastSet relinKeys; + KeySet relinKeys; BOOST_FOREACH(const ISAM2::sharedClique& root, roots) { if(relinearizeThreshold.type() == typeid(double)) CheckRelinearizationRecursiveDouble(relinKeys, boost::get(relinearizeThreshold), delta, root); @@ -200,7 +202,7 @@ FastSet ISAM2::Impl::CheckRelinearizationPartial(const FastVector& keys, const FastSet& markedMask) +void ISAM2::Impl::FindAll(ISAM2Clique::shared_ptr clique, KeySet& keys, const KeySet& markedMask) { static const bool debug = false; // does the separator contain any of the variables? @@ -224,7 +226,7 @@ void ISAM2::Impl::FindAll(ISAM2Clique::shared_ptr clique, FastSet& keys, co /* ************************************************************************* */ void ISAM2::Impl::ExpmapMasked(Values& values, const VectorValues& delta, - const FastSet& mask, boost::optional invalidateIfDebug, const KeyFormatter& keyFormatter) + const KeySet& mask, boost::optional invalidateIfDebug, const KeyFormatter& keyFormatter) { // If debugging, invalidate if requested, otherwise do not invalidate. // Invalidating means setting expmapped entries to Inf, to trigger assertions @@ -272,7 +274,7 @@ inline static void optimizeInPlace(const boost::shared_ptr& clique, /* ************************************************************************* */ size_t ISAM2::Impl::UpdateGaussNewtonDelta(const FastVector& roots, - const FastSet& replacedKeys, VectorValues& delta, double wildfireThreshold) { + const KeySet& replacedKeys, VectorValues& delta, double wildfireThreshold) { size_t lastBacksubVariableCount; @@ -300,7 +302,7 @@ size_t ISAM2::Impl::UpdateGaussNewtonDelta(const FastVector /* ************************************************************************* */ namespace internal { -void updateRgProd(const boost::shared_ptr& clique, const FastSet& replacedKeys, +void updateRgProd(const boost::shared_ptr& clique, const KeySet& replacedKeys, const VectorValues& grad, VectorValues& RgProd, size_t& varsUpdated) { // Check if any frontal or separator keys were recalculated, if so, we need @@ -344,7 +346,7 @@ void updateRgProd(const boost::shared_ptr& clique, const FastSet& replacedKeys, +size_t ISAM2::Impl::UpdateRgProd(const ISAM2::Roots& roots, const KeySet& replacedKeys, const VectorValues& gradAtZero, VectorValues& RgProd) { // Update variables diff --git a/gtsam/nonlinear/ISAM2-impl.h b/gtsam/nonlinear/ISAM2-impl.h index a8d03df13..d34480144 100644 --- a/gtsam/nonlinear/ISAM2-impl.h +++ b/gtsam/nonlinear/ISAM2-impl.h @@ -57,10 +57,10 @@ struct GTSAM_EXPORT ISAM2::Impl { /** * Remove variables from the ISAM2 system. */ - static void RemoveVariables(const FastSet& unusedKeys, const FastVector& roots, + static void RemoveVariables(const KeySet& unusedKeys, const FastVector& roots, Values& theta, VariableIndex& variableIndex, VectorValues& delta, VectorValues& deltaNewton, - VectorValues& RgProd, FastSet& replacedKeys, Base::Nodes& nodes, - FastSet& fixedVariables); + VectorValues& RgProd, KeySet& replacedKeys, Base::Nodes& nodes, + KeySet& fixedVariables); /** * Find the set of variables to be relinearized according to relinearizeThreshold. @@ -71,7 +71,7 @@ struct GTSAM_EXPORT ISAM2::Impl { * @return The set of variable indices in delta whose magnitude is greater than or * equal to relinearizeThreshold */ - static FastSet CheckRelinearizationFull(const VectorValues& delta, + static KeySet CheckRelinearizationFull(const VectorValues& delta, const ISAM2Params::RelinearizationThreshold& relinearizeThreshold); /** @@ -85,7 +85,7 @@ struct GTSAM_EXPORT ISAM2::Impl { * @return The set of variable indices in delta whose magnitude is greater than or * equal to relinearizeThreshold */ - static FastSet CheckRelinearizationPartial(const FastVector& roots, + static KeySet CheckRelinearizationPartial(const FastVector& roots, const VectorValues& delta, const ISAM2Params::RelinearizationThreshold& relinearizeThreshold); /** @@ -103,7 +103,7 @@ struct GTSAM_EXPORT ISAM2::Impl { * * Alternatively could we trace up towards the root for each variable here? */ - static void FindAll(ISAM2Clique::shared_ptr clique, FastSet& keys, const FastSet& markedMask); + static void FindAll(ISAM2Clique::shared_ptr clique, KeySet& keys, const KeySet& markedMask); /** * Apply expmap to the given values, but only for indices appearing in @@ -119,7 +119,7 @@ struct GTSAM_EXPORT ISAM2::Impl { * @param keyFormatter Formatter for printing nonlinear keys during debugging */ static void ExpmapMasked(Values& values, const VectorValues& delta, - const FastSet& mask, + const KeySet& mask, boost::optional invalidateIfDebug = boost::none, const KeyFormatter& keyFormatter = DefaultKeyFormatter); @@ -127,13 +127,13 @@ struct GTSAM_EXPORT ISAM2::Impl { * Update the Newton's method step point, using wildfire */ static size_t UpdateGaussNewtonDelta(const FastVector& roots, - const FastSet& replacedKeys, VectorValues& delta, double wildfireThreshold); + const KeySet& replacedKeys, VectorValues& delta, double wildfireThreshold); /** * Update the RgProd (R*g) incrementally taking into account which variables * have been recalculated in \c replacedKeys. Only used in Dogleg. */ - static size_t UpdateRgProd(const ISAM2::Roots& roots, const FastSet& replacedKeys, + static size_t UpdateRgProd(const ISAM2::Roots& roots, const KeySet& replacedKeys, const VectorValues& gradAtZero, VectorValues& RgProd); /** diff --git a/gtsam/nonlinear/ISAM2-inl.h b/gtsam/nonlinear/ISAM2-inl.h index f7c6d0345..538c66068 100644 --- a/gtsam/nonlinear/ISAM2-inl.h +++ b/gtsam/nonlinear/ISAM2-inl.h @@ -36,7 +36,7 @@ VALUE ISAM2::calculateEstimate(Key key) const { namespace internal { template void optimizeWildfire(const boost::shared_ptr& clique, double threshold, - FastSet& changed, const FastSet& replaced, VectorValues& delta, size_t& count) + KeySet& changed, const KeySet& replaced, VectorValues& delta, size_t& count) { // if none of the variables in this clique (frontal and separator!) changed // significantly, then by the running intersection property, none of the @@ -113,7 +113,7 @@ void optimizeWildfire(const boost::shared_ptr& clique, double threshold, template bool optimizeWildfireNode(const boost::shared_ptr& clique, double threshold, - FastSet& changed, const FastSet& replaced, VectorValues& delta, size_t& count) + KeySet& changed, const KeySet& replaced, VectorValues& delta, size_t& count) { // if none of the variables in this clique (frontal and separator!) changed // significantly, then by the running intersection property, none of the @@ -245,8 +245,8 @@ bool optimizeWildfireNode(const boost::shared_ptr& clique, double thresh /* ************************************************************************* */ template -size_t optimizeWildfire(const boost::shared_ptr& root, double threshold, const FastSet& keys, VectorValues& delta) { - FastSet changed; +size_t optimizeWildfire(const boost::shared_ptr& root, double threshold, const KeySet& keys, VectorValues& delta) { + KeySet changed; int count = 0; // starting from the root, call optimize on each conditional if(root) @@ -256,9 +256,9 @@ size_t optimizeWildfire(const boost::shared_ptr& root, double threshold, /* ************************************************************************* */ template -size_t optimizeWildfireNonRecursive(const boost::shared_ptr& root, double threshold, const FastSet& keys, VectorValues& delta) +size_t optimizeWildfireNonRecursive(const boost::shared_ptr& root, double threshold, const KeySet& keys, VectorValues& delta) { - FastSet changed; + KeySet changed; size_t count = 0; if (root) { diff --git a/gtsam/nonlinear/ISAM2.cpp b/gtsam/nonlinear/ISAM2.cpp index 00ffdccef..52af4fee3 100644 --- a/gtsam/nonlinear/ISAM2.cpp +++ b/gtsam/nonlinear/ISAM2.cpp @@ -194,7 +194,7 @@ FastSet ISAM2::getAffectedFactors(const FastList& keys) const { // (note that the remaining stuff is summarized in the cached factors) GaussianFactorGraph::shared_ptr -ISAM2::relinearizeAffectedFactors(const FastList& affectedKeys, const FastSet& relinKeys) const +ISAM2::relinearizeAffectedFactors(const FastList& affectedKeys, const KeySet& relinKeys) const { gttic(getAffectedFactors); FastSet candidates = getAffectedFactors(affectedKeys); @@ -204,7 +204,7 @@ ISAM2::relinearizeAffectedFactors(const FastList& affectedKeys, const FastS gttic(affectedKeysSet); // for fast lookup below - FastSet affectedKeysSet; + KeySet affectedKeysSet; affectedKeysSet.insert(affectedKeys.begin(), affectedKeys.end()); gttoc(affectedKeysSet); @@ -260,9 +260,9 @@ GaussianFactorGraph ISAM2::getCachedBoundaryFactors(Cliques& orphans) { } /* ************************************************************************* */ -boost::shared_ptr > ISAM2::recalculate(const FastSet& markedKeys, const FastSet& relinKeys, +boost::shared_ptr ISAM2::recalculate(const KeySet& markedKeys, const KeySet& relinKeys, const vector& observedKeys, - const FastSet& unusedIndices, + const KeySet& unusedIndices, const boost::optional >& constrainKeys, ISAM2Result& result) { @@ -326,7 +326,7 @@ boost::shared_ptr > ISAM2::recalculate(const FastSet& markedKe affectedKeys.insert(affectedKeys.end(), conditional->beginFrontals(), conditional->endFrontals()); gttoc(affectedKeys); - boost::shared_ptr > affectedKeysSet(new FastSet()); // Will return this result + boost::shared_ptr affectedKeysSet(new KeySet()); // Will return this result if(affectedKeys.size() >= theta_.size() * batchThreshold) { @@ -341,7 +341,7 @@ boost::shared_ptr > ISAM2::recalculate(const FastSet& markedKe Ordering order; if(constrainKeys) { - order = Ordering::colamdConstrained(variableIndex_, *constrainKeys); + order = Ordering::ColamdConstrained(variableIndex_, *constrainKeys); } else { @@ -351,11 +351,11 @@ boost::shared_ptr > ISAM2::recalculate(const FastSet& markedKe FastMap constraintGroups; BOOST_FOREACH(Key var, observedKeys) constraintGroups[var] = 1; - order = Ordering::colamdConstrained(variableIndex_, constraintGroups); + order = Ordering::ColamdConstrained(variableIndex_, constraintGroups); } else { - order = Ordering::colamd(variableIndex_); + order = Ordering::Colamd(variableIndex_); } } gttoc(ordering); @@ -481,7 +481,7 @@ boost::shared_ptr > ISAM2::recalculate(const FastSet& markedKe // Generate ordering gttic(Ordering); - Ordering ordering = Ordering::colamdConstrained(affectedFactorsVarIndex, constraintGroups); + Ordering ordering = Ordering::ColamdConstrained(affectedFactorsVarIndex, constraintGroups); gttoc(Ordering); ISAM2BayesTree::shared_ptr bayesTree = ISAM2JunctionTree(GaussianEliminationTree( @@ -566,17 +566,17 @@ ISAM2Result ISAM2::update( variableIndex_.remove(removeFactorIndices.begin(), removeFactorIndices.end(), removeFactors); // Compute unused keys and indices - FastSet unusedKeys; - FastSet unusedIndices; + KeySet unusedKeys; + KeySet unusedIndices; { // Get keys from removed factors and new factors, and compute unused keys, // i.e., keys that are empty now and do not appear in the new factors. - FastSet removedAndEmpty; + KeySet removedAndEmpty; BOOST_FOREACH(Key key, removeFactors.keys()) { if(variableIndex_[key].empty()) removedAndEmpty.insert(removedAndEmpty.end(), key); } - FastSet newFactorSymbKeys = newFactors.keys(); + KeySet newFactorSymbKeys = newFactors.keys(); std::set_difference(removedAndEmpty.begin(), removedAndEmpty.end(), newFactorSymbKeys.begin(), newFactorSymbKeys.end(), std::inserter(unusedKeys, unusedKeys.end())); @@ -602,10 +602,10 @@ ISAM2Result ISAM2::update( gttic(gather_involved_keys); // 3. Mark linear update - FastSet markedKeys = newFactors.keys(); // Get keys from new factors + KeySet markedKeys = newFactors.keys(); // Get keys from new factors // Also mark keys involved in removed factors { - FastSet markedRemoveKeys = removeFactors.keys(); // Get keys involved in removed factors + KeySet markedRemoveKeys = removeFactors.keys(); // Get keys involved in removed factors markedKeys.insert(markedRemoveKeys.begin(), markedRemoveKeys.end()); // Add to the overall set of marked keys } // Also mark any provided extra re-eliminate keys @@ -632,7 +632,7 @@ ISAM2Result ISAM2::update( gttoc(gather_involved_keys); // Check relinearization if we're at the nth step, or we are using a looser loop relin threshold - FastSet relinKeys; + KeySet relinKeys; if (relinearizeThisStep) { gttic(gather_relinearize_keys); // 4. Mark keys in \Delta above threshold \beta: J=\{\Delta_{j}\in\Delta|\Delta_{j}\geq\beta\}. @@ -659,7 +659,7 @@ ISAM2Result ISAM2::update( result.detail->variableStatus[key].isRelinearized = true; } } // Add the variables being relinearized to the marked keys - FastSet markedRelinMask; + KeySet markedRelinMask; BOOST_FOREACH(const Key key, relinKeys) markedRelinMask.insert(key); markedKeys.insert(relinKeys.begin(), relinKeys.end()); @@ -674,7 +674,7 @@ ISAM2Result ISAM2::update( // Relin involved keys for detailed results if(params_.enableDetailedResults) { - FastSet involvedRelinKeys; + KeySet involvedRelinKeys; BOOST_FOREACH(const sharedClique& root, roots_) Impl::FindAll(root, involvedRelinKeys, markedRelinMask); BOOST_FOREACH(Key key, involvedRelinKeys) { @@ -726,7 +726,7 @@ ISAM2Result ISAM2::update( gttic(recalculate); // 8. Redo top of Bayes tree - boost::shared_ptr > replacedKeys; + boost::shared_ptr replacedKeys; if(!markedKeys.empty() || !observedKeys.empty()) replacedKeys = recalculate(markedKeys, relinKeys, observedKeys, unusedIndices, constrainedKeys, result); @@ -758,7 +758,7 @@ void ISAM2::marginalizeLeaves(const FastList& leafKeysList, boost::optional&> deletedFactorsIndices) { // Convert to ordered set - FastSet leafKeys(leafKeysList.begin(), leafKeysList.end()); + KeySet leafKeys(leafKeysList.begin(), leafKeysList.end()); // Keep track of marginal factors - map from clique to the marginal factors // that should be incorporated into it, passed up from it's children. @@ -769,7 +769,7 @@ void ISAM2::marginalizeLeaves(const FastList& leafKeysList, FastSet factorIndicesToRemove; // Keep track of variables removed in subtrees - FastSet leafKeysRemoved; + KeySet leafKeysRemoved; // Remove each variable and its subtrees BOOST_FOREACH(Key j, leafKeys) { @@ -881,7 +881,7 @@ void ISAM2::marginalizeLeaves(const FastList& leafKeysList, graph.push_back(nonlinearFactors_[i]->linearize(theta_)); } // Reeliminate the linear graph to get the marginal and discard the conditional - const FastSet cliqueFrontals(clique->conditional()->beginFrontals(), clique->conditional()->endFrontals()); + const KeySet cliqueFrontals(clique->conditional()->beginFrontals(), clique->conditional()->endFrontals()); FastVector cliqueFrontalsToEliminate; std::set_intersection(cliqueFrontals.begin(), cliqueFrontals.end(), leafKeys.begin(), leafKeys.end(), std::back_inserter(cliqueFrontalsToEliminate)); @@ -957,7 +957,7 @@ void ISAM2::marginalizeLeaves(const FastList& leafKeysList, deletedFactorsIndices->assign(factorIndicesToRemove.begin(), factorIndicesToRemove.end()); // Remove the marginalized variables - Impl::RemoveVariables(FastSet(leafKeys.begin(), leafKeys.end()), roots_, theta_, variableIndex_, delta_, deltaNewton_, RgProd_, + Impl::RemoveVariables(KeySet(leafKeys.begin(), leafKeys.end()), roots_, theta_, variableIndex_, delta_, deltaNewton_, RgProd_, deltaReplacedMask_, nodes_, fixedVariables_); } diff --git a/gtsam/nonlinear/ISAM2.h b/gtsam/nonlinear/ISAM2.h index 5f5554e91..fdc0021e5 100644 --- a/gtsam/nonlinear/ISAM2.h +++ b/gtsam/nonlinear/ISAM2.h @@ -460,7 +460,7 @@ protected: * This is \c mutable because it is used internally to not update delta_ * until it is needed. */ - mutable FastSet deltaReplacedMask_; // TODO: Make sure accessed in the right way + mutable KeySet deltaReplacedMask_; // TODO: Make sure accessed in the right way /** All original nonlinear factors are stored here to use during relinearization */ NonlinearFactorGraph nonlinearFactors_; @@ -476,7 +476,7 @@ protected: /** Set of variables that are involved with linear factors from marginalized * variables and thus cannot have their linearization points changed. */ - FastSet fixedVariables_; + KeySet fixedVariables_; int update_count_; ///< Counter incremented every update(), used to determine periodic relinearization @@ -614,7 +614,7 @@ public: const VariableIndex& getVariableIndex() const { return variableIndex_; } /** Access the nonlinear variable index */ - const FastSet& getFixedVariables() const { return fixedVariables_; } + const KeySet& getFixedVariables() const { return fixedVariables_; } size_t lastAffectedVariableCount; size_t lastAffectedFactorCount; @@ -641,11 +641,11 @@ public: protected: FastSet getAffectedFactors(const FastList& keys) const; - GaussianFactorGraph::shared_ptr relinearizeAffectedFactors(const FastList& affectedKeys, const FastSet& relinKeys) const; + GaussianFactorGraph::shared_ptr relinearizeAffectedFactors(const FastList& affectedKeys, const KeySet& relinKeys) const; GaussianFactorGraph getCachedBoundaryFactors(Cliques& orphans); - virtual boost::shared_ptr > recalculate(const FastSet& markedKeys, const FastSet& relinKeys, - const std::vector& observedKeys, const FastSet& unusedIndices, const boost::optional >& constrainKeys, ISAM2Result& result); + virtual boost::shared_ptr recalculate(const KeySet& markedKeys, const KeySet& relinKeys, + const std::vector& observedKeys, const KeySet& unusedIndices, const boost::optional >& constrainKeys, ISAM2Result& result); void updateDelta(bool forceFullSolve = false) const; }; // ISAM2 @@ -666,11 +666,11 @@ template<> struct traits : public Testable {}; /// @return The number of variables that were solved for template size_t optimizeWildfire(const boost::shared_ptr& root, - double threshold, const FastSet& replaced, VectorValues& delta); + double threshold, const KeySet& replaced, VectorValues& delta); template size_t optimizeWildfireNonRecursive(const boost::shared_ptr& root, - double threshold, const FastSet& replaced, VectorValues& delta); + double threshold, const KeySet& replaced, VectorValues& delta); /// calculate the number of non-zero entries for the tree starting at clique (use root for complete matrix) template diff --git a/gtsam/nonlinear/LevenbergMarquardtOptimizer.cpp b/gtsam/nonlinear/LevenbergMarquardtOptimizer.cpp index 5fb51a243..9e42afa33 100644 --- a/gtsam/nonlinear/LevenbergMarquardtOptimizer.cpp +++ b/gtsam/nonlinear/LevenbergMarquardtOptimizer.cpp @@ -22,9 +22,12 @@ #include #include #include +#include #include #include +#include + #include #include #include @@ -105,8 +108,8 @@ void LevenbergMarquardtParams::print(const std::string& str) const { std::cout << " lambdaLowerBound: " << lambdaLowerBound << "\n"; std::cout << " minModelFidelity: " << minModelFidelity << "\n"; std::cout << " diagonalDamping: " << diagonalDamping << "\n"; - std::cout << " min_diagonal: " << min_diagonal_ << "\n"; - std::cout << " max_diagonal: " << max_diagonal_ << "\n"; + std::cout << " minDiagonal: " << minDiagonal << "\n"; + std::cout << " maxDiagonal: " << maxDiagonal << "\n"; std::cout << " verbosityLM: " << verbosityLMTranslator(verbosityLM) << "\n"; std::cout.flush(); @@ -119,19 +122,19 @@ GaussianFactorGraph::shared_ptr LevenbergMarquardtOptimizer::linearize() const { /* ************************************************************************* */ void LevenbergMarquardtOptimizer::increaseLambda() { - if (params_.useFixedLambdaFactor_) { + if (params_.useFixedLambdaFactor) { state_.lambda *= params_.lambdaFactor; } else { state_.lambda *= params_.lambdaFactor; params_.lambdaFactor *= 2.0; } - params_.reuse_diagonal_ = true; + state_.reuseDiagonal = true; } /* ************************************************************************* */ void LevenbergMarquardtOptimizer::decreaseLambda(double stepQuality) { - if (params_.useFixedLambdaFactor_) { + if (params_.useFixedLambdaFactor) { state_.lambda /= params_.lambdaFactor; } else { // CHECK_GT(step_quality, 0.0); @@ -139,7 +142,7 @@ void LevenbergMarquardtOptimizer::decreaseLambda(double stepQuality) { params_.lambdaFactor = 2.0; } state_.lambda = std::max(params_.lambdaLowerBound, state_.lambda); - params_.reuse_diagonal_ = false; + state_.reuseDiagonal = false; } @@ -152,12 +155,12 @@ GaussianFactorGraph::shared_ptr LevenbergMarquardtOptimizer::buildDampedSystem( cout << "building damped system with lambda " << state_.lambda << endl; // Only retrieve diagonal vector when reuse_diagonal = false - if (params_.diagonalDamping && params_.reuse_diagonal_ == false) { + if (params_.diagonalDamping && state_.reuseDiagonal == false) { state_.hessianDiagonal = linear.hessianDiagonal(); BOOST_FOREACH(Vector& v, state_.hessianDiagonal | map_values) { for (int aa = 0; aa < v.size(); aa++) { - v(aa) = std::min(std::max(v(aa), params_.min_diagonal_), - params_.max_diagonal_); + v(aa) = std::min(std::max(v(aa), params_.minDiagonal), + params_.maxDiagonal); v(aa) = sqrt(v(aa)); } } @@ -186,12 +189,24 @@ GaussianFactorGraph::shared_ptr LevenbergMarquardtOptimizer::buildDampedSystem( } } else { // Straightforward damping: + + // initialize noise model cache to a reasonable default size + NoiseCacheVector noises(6); BOOST_FOREACH(const Values::KeyValuePair& key_value, state_.values) { size_t dim = key_value.value.dim(); - Matrix A = Matrix::Identity(dim, dim); - Vector b = Vector::Zero(dim); - SharedDiagonal model = noiseModel::Isotropic::Sigma(dim, sigma); - damped += boost::make_shared(key_value.key, A, b, model); + + if (dim > noises.size()) + noises.resize(dim); + + NoiseCacheItem& item = noises[dim-1]; + + // Initialize noise model, A and b if we haven't done so already + if(!item.model) { + item.A = Matrix::Identity(dim, dim); + item.b = Vector::Zero(dim); + item.model = noiseModel::Isotropic::Sigma(dim, sigma); + } + damped += boost::make_shared(key_value.key, item.A, item.b, item.model); } } gttoc(damp); @@ -237,6 +252,14 @@ void LevenbergMarquardtOptimizer::iterate() { // Keep increasing lambda until we make make progress while (true) { +#ifdef GTSAM_USING_NEW_BOOST_TIMERS + boost::timer::cpu_timer lamda_iteration_timer; + lamda_iteration_timer.start(); +#else + boost::timer lamda_iteration_timer; + lamda_iteration_timer.restart(); +#endif + if (lmVerbosity >= LevenbergMarquardtParams::TRYLAMBDA) cout << "trying lambda = " << state_.lambda << endl; @@ -248,22 +271,21 @@ void LevenbergMarquardtOptimizer::iterate() { double modelFidelity = 0.0; bool step_is_successful = false; bool stopSearchingLambda = false; - double newError = numeric_limits::infinity(); + double newError = numeric_limits::infinity(), costChange; Values newValues; VectorValues delta; bool systemSolvedSuccessfully; try { + // ============ Solve is where most computation happens !! ================= delta = solve(dampedSystem, state_.values, params_); systemSolvedSuccessfully = true; } catch (const IndeterminantLinearSystemException& e) { systemSolvedSuccessfully = false; } - double linearizedCostChange = 0, - newlinearizedError = 0; if (systemSolvedSuccessfully) { - params_.reuse_diagonal_ = true; + state_.reuseDiagonal = true; if (lmVerbosity >= LevenbergMarquardtParams::TRYLAMBDA) cout << "linear delta norm = " << delta.norm() << endl; @@ -271,9 +293,9 @@ void LevenbergMarquardtOptimizer::iterate() { delta.print("delta"); // cost change in the linearized system (old - new) - newlinearizedError = linear->error(delta); + double newlinearizedError = linear->error(delta); - linearizedCostChange = state_.error - newlinearizedError; + double linearizedCostChange = state_.error - newlinearizedError; if (lmVerbosity >= LevenbergMarquardtParams::TRYLAMBDA) cout << "newlinearizedError = " << newlinearizedError << " linearizedCostChange = " << linearizedCostChange << endl; @@ -281,7 +303,9 @@ void LevenbergMarquardtOptimizer::iterate() { if (linearizedCostChange >= 0) { // step is valid // update values gttic(retract); + // ============ This is where the solution is updated ==================== newValues = state_.values.retract(delta); + // ======================================================================= gttoc(retract); // compute new error @@ -296,7 +320,7 @@ void LevenbergMarquardtOptimizer::iterate() { << ") new (tentative) error (" << newError << ")" << endl; // cost change in the original, nonlinear system (old - new) - double costChange = state_.error - newError; + costChange = state_.error - newError; if (linearizedCostChange > 1e-20) { // the (linear) error has to decrease to satisfy this condition // fidelity of linearized model VS original system between @@ -319,9 +343,18 @@ void LevenbergMarquardtOptimizer::iterate() { } if (lmVerbosity == LevenbergMarquardtParams::SUMMARY) { - cout << "[" << state_.iterations << "]: " << "new error = " << newlinearizedError - << ", delta = " << linearizedCostChange << ", lambda = " << state_.lambda - << ", success = " << systemSolvedSuccessfully << std::endl; + // do timing +#ifdef GTSAM_USING_NEW_BOOST_TIMERS + double iterationTime = 1e-9 * lamda_iteration_timer.elapsed().wall; +#else + double iterationTime = lamda_iteration_timer.elapsed(); +#endif + if (state_.iterations == 0) + cout << "iter cost cost_change lambda success iter_time" << endl; + + cout << boost::format("% 4d % 8e % 3.2e % 3.2e % 4d % 3.2e") % + state_.iterations % newError % costChange % state_.lambda % + systemSolvedSuccessfully % iterationTime << endl; } ++state_.totalNumberInnerIterations; @@ -361,12 +394,8 @@ void LevenbergMarquardtOptimizer::iterate() { /* ************************************************************************* */ LevenbergMarquardtParams LevenbergMarquardtOptimizer::ensureHasOrdering( LevenbergMarquardtParams params, const NonlinearFactorGraph& graph) const { - if (!params.ordering){ - if (params.orderingType == Ordering::METIS) - params.ordering = Ordering::metis(graph); - else - params.ordering = Ordering::colamd(graph); - } + if (!params.ordering) + params.ordering = Ordering::Create(params.orderingType, graph); return params; } diff --git a/gtsam/nonlinear/LevenbergMarquardtOptimizer.h b/gtsam/nonlinear/LevenbergMarquardtOptimizer.h index 009b480f2..2be4a218e 100644 --- a/gtsam/nonlinear/LevenbergMarquardtOptimizer.h +++ b/gtsam/nonlinear/LevenbergMarquardtOptimizer.h @@ -52,70 +52,84 @@ public: double lambdaLowerBound; ///< The minimum lambda used in LM (default: 0) VerbosityLM verbosityLM; ///< The verbosity level for Levenberg-Marquardt (default: SILENT), see also NonlinearOptimizerParams::verbosity double minModelFidelity; ///< Lower bound for the modelFidelity to accept the result of an LM iteration - std::string logFile; ///< an optional CSV log file, with [iteration, time, error, labda] + std::string logFile; ///< an optional CSV log file, with [iteration, time, error, lambda] bool diagonalDamping; ///< if true, use diagonal of Hessian - bool reuse_diagonal_; ///< an additional option in Ceres for diagonalDamping (related to efficiency) - bool useFixedLambdaFactor_; ///< if true applies constant increase (or decrease) to lambda according to lambdaFactor - double min_diagonal_; ///< when using diagonal damping saturates the minimum diagonal entries (default: 1e-6) - double max_diagonal_; ///< when using diagonal damping saturates the maximum diagonal entries (default: 1e32) + bool useFixedLambdaFactor; ///< if true applies constant increase (or decrease) to lambda according to lambdaFactor + double minDiagonal; ///< when using diagonal damping saturates the minimum diagonal entries (default: 1e-6) + double maxDiagonal; ///< when using diagonal damping saturates the maximum diagonal entries (default: 1e32) - LevenbergMarquardtParams() : - lambdaInitial(1e-5), lambdaFactor(10.0), lambdaUpperBound(1e5), lambdaLowerBound( - 0.0), verbosityLM(SILENT), minModelFidelity(1e-3), - diagonalDamping(false), reuse_diagonal_(false), useFixedLambdaFactor_(true), - min_diagonal_(1e-6), max_diagonal_(1e32) { - } - virtual ~LevenbergMarquardtParams() { + LevenbergMarquardtParams() + : verbosityLM(SILENT), + diagonalDamping(false), + minDiagonal(1e-6), + maxDiagonal(1e32) { + SetLegacyDefaults(this); } + static void SetLegacyDefaults(LevenbergMarquardtParams* p) { + // Relevant NonlinearOptimizerParams: + p->maxIterations = 100; + p->relativeErrorTol = 1e-5; + p->absoluteErrorTol = 1e-5; + // LM-specific: + p->lambdaInitial = 1e-5; + p->lambdaFactor = 10.0; + p->lambdaUpperBound = 1e5; + p->lambdaLowerBound = 0.0; + p->minModelFidelity = 1e-3; + p->diagonalDamping = false; + p->useFixedLambdaFactor = true; + } + + // these do seem to work better for SFM + static void SetCeresDefaults(LevenbergMarquardtParams* p) { + // Relevant NonlinearOptimizerParams: + p->maxIterations = 50; + p->absoluteErrorTol = 0; // No corresponding option in CERES + p->relativeErrorTol = 1e-6; // This is function_tolerance + // LM-specific: + p->lambdaUpperBound = 1e32; + p->lambdaLowerBound = 1e-16; + p->lambdaInitial = 1e-04; + p->lambdaFactor = 2.0; + p->minModelFidelity = 1e-3; // options.min_relative_decrease in CERES + p->diagonalDamping = true; + p->useFixedLambdaFactor = false; // This is important + } + + static LevenbergMarquardtParams LegacyDefaults() { + LevenbergMarquardtParams p; + SetLegacyDefaults(&p); + return p; + } + + static LevenbergMarquardtParams CeresDefaults() { + LevenbergMarquardtParams p; + SetCeresDefaults(&p); + return p; + } + + virtual ~LevenbergMarquardtParams() {} virtual void print(const std::string& str = "") const; - inline double getlambdaInitial() const { - return lambdaInitial; - } - inline double getlambdaFactor() const { - return lambdaFactor; - } - inline double getlambdaUpperBound() const { - return lambdaUpperBound; - } - inline double getlambdaLowerBound() const { - return lambdaLowerBound; - } - inline std::string getVerbosityLM() const { - return verbosityLMTranslator(verbosityLM); - } - inline std::string getLogFile() const { - return logFile; - } - inline bool getDiagonalDamping() const { - return diagonalDamping; - } - - inline void setlambdaInitial(double value) { - lambdaInitial = value; - } - inline void setlambdaFactor(double value) { - lambdaFactor = value; - } - inline void setlambdaUpperBound(double value) { - lambdaUpperBound = value; - } - inline void setlambdaLowerBound(double value) { - lambdaLowerBound = value; - } - inline void setVerbosityLM(const std::string &s) { - verbosityLM = verbosityLMTranslator(s); - } - inline void setLogFile(const std::string &s) { - logFile = s; - } - inline void setDiagonalDamping(bool flag) { - diagonalDamping = flag; - } - inline void setUseFixedLambdaFactor(bool flag) { - useFixedLambdaFactor_ = flag; - } + /// @name Getters/Setters, mainly for MATLAB. Use fields above in C++. + /// @{ + bool getDiagonalDamping() const { return diagonalDamping; } + double getlambdaFactor() const { return lambdaFactor; } + double getlambdaInitial() const { return lambdaInitial; } + double getlambdaLowerBound() const { return lambdaLowerBound; } + double getlambdaUpperBound() const { return lambdaUpperBound; } + std::string getLogFile() const { return logFile; } + std::string getVerbosityLM() const { return verbosityLMTranslator(verbosityLM);} + void setDiagonalDamping(bool flag) { diagonalDamping = flag; } + void setlambdaFactor(double value) { lambdaFactor = value; } + void setlambdaInitial(double value) { lambdaInitial = value; } + void setlambdaLowerBound(double value) { lambdaLowerBound = value; } + void setlambdaUpperBound(double value) { lambdaUpperBound = value; } + void setLogFile(const std::string& s) { logFile = s; } + void setUseFixedLambdaFactor(bool flag) { useFixedLambdaFactor = flag;} + void setVerbosityLM(const std::string& s) { verbosityLM = verbosityLMTranslator(s);} + // @} }; /** @@ -125,13 +139,12 @@ class GTSAM_EXPORT LevenbergMarquardtState: public NonlinearOptimizerState { public: double lambda; - int totalNumberInnerIterations; // The total number of inner iterations in the optimization (for each iteration, LM may try multiple iterations with different lambdas) boost::posix_time::ptime startTime; - VectorValues hessianDiagonal; //only update hessianDiagonal when reuse_diagonal_ = false + int totalNumberInnerIterations; //< The total number of inner iterations in the optimization (for each iteration, LM may try multiple iterations with different lambdas) + VectorValues hessianDiagonal; //< we only update hessianDiagonal when reuseDiagonal = false + bool reuseDiagonal; ///< an additional option in Ceres for diagonalDamping - LevenbergMarquardtState() { - initTime(); - } + LevenbergMarquardtState() {} // used in LM constructor but immediately overwritten void initTime() { startTime = boost::posix_time::microsec_clock::universal_time(); @@ -145,7 +158,7 @@ protected: const Values& initialValues, const LevenbergMarquardtParams& params, unsigned int iterations = 0) : NonlinearOptimizerState(graph, initialValues, iterations), lambda( - params.lambdaInitial), totalNumberInnerIterations(0) { + params.lambdaInitial), totalNumberInnerIterations(0),reuseDiagonal(false) { initTime(); } @@ -175,12 +188,12 @@ public: * @param initialValues The initial variable assignments * @param params The optimization parameters */ - LevenbergMarquardtOptimizer(const NonlinearFactorGraph& graph, - const Values& initialValues, const LevenbergMarquardtParams& params = - LevenbergMarquardtParams()) : - NonlinearOptimizer(graph), params_(ensureHasOrdering(params, graph)), state_( - graph, initialValues, params_) { - } + LevenbergMarquardtOptimizer( + const NonlinearFactorGraph& graph, const Values& initialValues, + const LevenbergMarquardtParams& params = LevenbergMarquardtParams()) + : NonlinearOptimizer(graph), + params_(ensureHasOrdering(params, graph)), + state_(graph, initialValues, params_) {} /** Standard constructor, requires a nonlinear factor graph, initial * variable assignments, and optimization parameters. For convenience this @@ -189,9 +202,11 @@ public: * @param graph The nonlinear factor graph to optimize * @param initialValues The initial variable assignments */ - LevenbergMarquardtOptimizer(const NonlinearFactorGraph& graph, - const Values& initialValues, const Ordering& ordering) : - NonlinearOptimizer(graph) { + LevenbergMarquardtOptimizer( + const NonlinearFactorGraph& graph, const Values& initialValues, + const Ordering& ordering, + const LevenbergMarquardtParams& params = LevenbergMarquardtParams()) + : NonlinearOptimizer(graph), params_(params) { params_.ordering = ordering; state_ = LevenbergMarquardtState(graph, initialValues, params_); } @@ -257,6 +272,17 @@ public: GaussianFactorGraph::shared_ptr buildDampedSystem(const GaussianFactorGraph& linear); friend class ::NonlinearOptimizerMoreOptimizationTest; + /** Small struct to cache objects needed for damping. + * This is used in buildDampedSystem */ + struct NoiseCacheItem { + Matrix A; + Vector b; + SharedDiagonal model; + }; + + /// Noise model Cache + typedef std::vector NoiseCacheVector; + void writeLogFile(double currentError); /// @} diff --git a/gtsam/nonlinear/NonlinearFactorGraph.cpp b/gtsam/nonlinear/NonlinearFactorGraph.cpp index f23418d2a..b81332f5e 100644 --- a/gtsam/nonlinear/NonlinearFactorGraph.cpp +++ b/gtsam/nonlinear/NonlinearFactorGraph.cpp @@ -17,22 +17,24 @@ * @author Christian Potthast */ -#include -#include -#include #include #include -#include -#include #include -#include #include #include +#include +#include +#include +#include // for GTSAM_USE_TBB #ifdef GTSAM_USE_TBB # include #endif +#include +#include +#include + using namespace std; namespace gtsam { @@ -70,7 +72,7 @@ void NonlinearFactorGraph::saveGraph(std::ostream &stm, const Values& values, stm << " size=\"" << formatting.figureWidthInches << "," << formatting.figureHeightInches << "\";\n\n"; - FastSet keys = this->keys(); + KeySet keys = this->keys(); // Local utility function to extract x and y coordinates struct { boost::optional operator()( @@ -144,7 +146,7 @@ void NonlinearFactorGraph::saveGraph(std::ostream &stm, const Values& values, if (formatting.mergeSimilarFactors) { // Remove duplicate factors - FastSet > structure; + std::set > structure; BOOST_FOREACH(const sharedFactor& factor, *this){ if(factor) { vector factorKeys = factor->keys(); @@ -234,8 +236,8 @@ double NonlinearFactorGraph::error(const Values& c) const { } /* ************************************************************************* */ -FastSet NonlinearFactorGraph::keys() const { - FastSet keys; +KeySet NonlinearFactorGraph::keys() const { + KeySet keys; BOOST_FOREACH(const sharedFactor& factor, this->factors_) { if(factor) keys.insert(factor->begin(), factor->end()); @@ -246,13 +248,13 @@ FastSet NonlinearFactorGraph::keys() const { /* ************************************************************************* */ Ordering NonlinearFactorGraph::orderingCOLAMD() const { - return Ordering::colamd(*this); + return Ordering::Colamd(*this); } /* ************************************************************************* */ Ordering NonlinearFactorGraph::orderingCOLAMDConstrained(const FastMap& constraints) const { - return Ordering::colamdConstrained(*this, constraints); + return Ordering::ColamdConstrained(*this, constraints); } /* ************************************************************************* */ @@ -276,23 +278,26 @@ SymbolicFactorGraph::shared_ptr NonlinearFactorGraph::symbolic() const namespace { #ifdef GTSAM_USE_TBB - struct _LinearizeOneFactor { - const NonlinearFactorGraph& graph; - const Values& linearizationPoint; - GaussianFactorGraph& result; - _LinearizeOneFactor(const NonlinearFactorGraph& graph, const Values& linearizationPoint, GaussianFactorGraph& result) : - graph(graph), linearizationPoint(linearizationPoint), result(result) {} - void operator()(const tbb::blocked_range& r) const - { - for(size_t i = r.begin(); i != r.end(); ++i) - { - if(graph[i]) - result[i] = graph[i]->linearize(linearizationPoint); - else - result[i] = GaussianFactor::shared_ptr(); - } +class _LinearizeOneFactor { + const NonlinearFactorGraph& nonlinearGraph_; + const Values& linearizationPoint_; + GaussianFactorGraph& result_; +public: + // Create functor with constant parameters + _LinearizeOneFactor(const NonlinearFactorGraph& graph, + const Values& linearizationPoint, GaussianFactorGraph& result) : + nonlinearGraph_(graph), linearizationPoint_(linearizationPoint), result_(result) { + } + // Operator that linearizes a given range of the factors + void operator()(const tbb::blocked_range& blocked_range) const { + for (size_t i = blocked_range.begin(); i != blocked_range.end(); ++i) { + if (nonlinearGraph_[i]) + result_[i] = nonlinearGraph_[i]->linearize(linearizationPoint_); + else + result_[i] = GaussianFactor::shared_ptr(); } - }; + } +}; #endif } @@ -321,7 +326,7 @@ GaussianFactorGraph::shared_ptr NonlinearFactorGraph::linearize(const Values& li if(factor) { (*linearFG) += factor->linearize(linearizationPoint); } else - (*linearFG) += GaussianFactor::shared_ptr(); + (*linearFG) += GaussianFactor::shared_ptr(); } #endif diff --git a/gtsam/nonlinear/NonlinearFactorGraph.h b/gtsam/nonlinear/NonlinearFactorGraph.h index 169d12455..ecd3b9b56 100644 --- a/gtsam/nonlinear/NonlinearFactorGraph.h +++ b/gtsam/nonlinear/NonlinearFactorGraph.h @@ -106,7 +106,7 @@ namespace gtsam { const KeyFormatter& keyFormatter = DefaultKeyFormatter) const; /** return keys as an ordered set - ordering is by key value */ - FastSet keys() const; + KeySet keys() const; /** unnormalized error, \f$ 0.5 \sum_i (h_i(X_i)-z)^2/\sigma^2 \f$ in the most common case */ double error(const Values& c) const; diff --git a/gtsam/nonlinear/NonlinearOptimizer.cpp b/gtsam/nonlinear/NonlinearOptimizer.cpp index 00746d9b7..77d26d361 100644 --- a/gtsam/nonlinear/NonlinearOptimizer.cpp +++ b/gtsam/nonlinear/NonlinearOptimizer.cpp @@ -68,6 +68,7 @@ void NonlinearOptimizer::defaultOptimize() { // Do next iteration currentError = this->error(); this->iterate(); + tictoc_finishedIteration(); // Maybe show output if(params.verbosity >= NonlinearOptimizerParams::VALUES) this->values().print("newValues"); diff --git a/gtsam/nonlinear/Values-inl.h b/gtsam/nonlinear/Values-inl.h index fe2c3f3ca..05e58accb 100644 --- a/gtsam/nonlinear/Values-inl.h +++ b/gtsam/nonlinear/Values-inl.h @@ -49,8 +49,12 @@ namespace gtsam { const Key key; ///< The key const ValueType& value; ///< The value - _ValuesConstKeyValuePair(Key _key, const ValueType& _value) : key(_key), value(_value) {} - _ValuesConstKeyValuePair(const _ValuesKeyValuePair& rhs) : key(rhs.key), value(rhs.value) {} + _ValuesConstKeyValuePair(Key _key, const ValueType& _value) : + key(_key), value(_value) { + } + _ValuesConstKeyValuePair(const _ValuesKeyValuePair& rhs) : + key(rhs.key), value(rhs.value) { + } }; /* ************************************************************************* */ @@ -59,17 +63,20 @@ namespace gtsam { // need to use a struct here for later partial specialization template struct ValuesCastHelper { - static CastedKeyValuePairType cast(KeyValuePairType key_value) { - // Static cast because we already checked the type during filtering - return CastedKeyValuePairType(key_value.key, const_cast&>(static_cast&>(key_value.value)).value()); - } + static CastedKeyValuePairType cast(KeyValuePairType key_value) { + // Static cast because we already checked the type during filtering + return CastedKeyValuePairType(key_value.key, + const_cast&>(static_cast&>(key_value.value)).value()); + } }; // partial specialized version for ValueType == Value template struct ValuesCastHelper { static CastedKeyValuePairType cast(KeyValuePairType key_value) { // Static cast because we already checked the type during filtering - // in this case the casted and keyvalue pair are essentially the same type (key, Value&) so perhaps this could be done with just a cast of the key_value? + // in this case the casted and keyvalue pair are essentially the same type + // (key, Value&) so perhaps this could be done with just a cast of the key_value? return CastedKeyValuePairType(key_value.key, key_value.value); } }; @@ -78,7 +85,8 @@ namespace gtsam { struct ValuesCastHelper { static CastedKeyValuePairType cast(KeyValuePairType key_value) { // Static cast because we already checked the type during filtering - // in this case the casted and keyvalue pair are essentially the same type (key, Value&) so perhaps this could be done with just a cast of the key_value? + // in this case the casted and keyvalue pair are essentially the same type + // (key, Value&) so perhaps this could be done with just a cast of the key_value? return CastedKeyValuePairType(key_value.key, key_value.value); } }; @@ -126,23 +134,29 @@ namespace gtsam { } private: - Filtered(const boost::function& filter, Values& values) : - begin_(boost::make_transform_iterator( - boost::make_filter_iterator( - filter, values.begin(), values.end()), - &ValuesCastHelper::cast)), - end_(boost::make_transform_iterator( - boost::make_filter_iterator( - filter, values.end(), values.end()), - &ValuesCastHelper::cast)), - constBegin_(boost::make_transform_iterator( - boost::make_filter_iterator( - filter, ((const Values&)values).begin(), ((const Values&)values).end()), - &ValuesCastHelper::cast)), - constEnd_(boost::make_transform_iterator( - boost::make_filter_iterator( - filter, ((const Values&)values).end(), ((const Values&)values).end()), - &ValuesCastHelper::cast)) {} + Filtered( + const boost::function& filter, + Values& values) : + begin_( + boost::make_transform_iterator( + boost::make_filter_iterator(filter, values.begin(), values.end()), + &ValuesCastHelper::cast)), end_( + boost::make_transform_iterator( + boost::make_filter_iterator(filter, values.end(), values.end()), + &ValuesCastHelper::cast)), constBegin_( + boost::make_transform_iterator( + boost::make_filter_iterator(filter, + ((const Values&) values).begin(), + ((const Values&) values).end()), + &ValuesCastHelper::cast)), constEnd_( + boost::make_transform_iterator( + boost::make_filter_iterator(filter, + ((const Values&) values).end(), + ((const Values&) values).end()), + &ValuesCastHelper::cast)) { + } friend class Values; iterator begin_; @@ -191,7 +205,9 @@ namespace gtsam { friend class Values; const_iterator begin_; const_iterator end_; - ConstFiltered(const boost::function& filter, const Values& values) { + ConstFiltered( + const boost::function& filter, + const Values& values) { // We remove the const from values to create a non-const Filtered // view, then pull the const_iterators out of it. const Filtered filtered(filter, const_cast(values)); @@ -247,7 +263,8 @@ namespace gtsam { /* ************************************************************************* */ template<> - inline bool Values::filterHelper(const boost::function filter, const ConstKeyValuePair& key_value) { + inline bool Values::filterHelper(const boost::function filter, + const ConstKeyValuePair& key_value) { // Filter and check the type return filter(key_value.key); } @@ -263,10 +280,11 @@ namespace gtsam { throw ValuesKeyDoesNotExist("retrieve", j); // Check the type and throw exception if incorrect + const Value& value = *item->second; try { - return dynamic_cast&>(*item->second).value(); + return dynamic_cast&>(value).value(); } catch (std::bad_cast &) { - throw ValuesIncorrectType(j, typeid(*item->second), typeid(ValueType)); + throw ValuesIncorrectType(j, typeid(value), typeid(ValueType)); } } @@ -278,10 +296,11 @@ namespace gtsam { if(item != values_.end()) { // dynamic cast the type and throw exception if incorrect + const Value& value = *item->second; try { - return dynamic_cast&>(*item->second).value(); + return dynamic_cast&>(value).value(); } catch (std::bad_cast &) { - throw ValuesIncorrectType(j, typeid(*item->second), typeid(ValueType)); + throw ValuesIncorrectType(j, typeid(value), typeid(ValueType)); } } else { return boost::none; diff --git a/gtsam/nonlinear/Values.cpp b/gtsam/nonlinear/Values.cpp index 372bced8e..07757062c 100644 --- a/gtsam/nonlinear/Values.cpp +++ b/gtsam/nonlinear/Values.cpp @@ -58,18 +58,19 @@ namespace gtsam { /* ************************************************************************* */ bool Values::equals(const Values& other, double tol) const { - if(this->size() != other.size()) + if (this->size() != other.size()) return false; - for(const_iterator it1=this->begin(), it2=other.begin(); it1!=this->end(); ++it1, ++it2) { - if(typeid(it1->value) != typeid(it2->value)) - return false; - if(it1->key != it2->key) - return false; - if(!it1->value.equals_(it2->value, tol)) + for (const_iterator it1 = this->begin(), it2 = other.begin(); + it1 != this->end(); ++it1, ++it2) { + const Value& value1 = it1->value; + const Value& value2 = it2->value; + if (typeid(value1) != typeid(value2) || it1->key != it2->key + || !value1.equals_(value2, tol)) { return false; + } } return true; // We return false earlier if we find anything that does not match - } +} /* ************************************************************************* */ bool Values::exists(Key j) const { @@ -85,7 +86,6 @@ namespace gtsam { VectorValues::const_iterator vector_item = delta.find(key_value->key); Key key = key_value->key; // Non-const duplicate to deal with non-const insert argument if(vector_item != delta.end()) { -// const Vector& singleDelta = delta[key_value->key]; // Delta for this value const Vector& singleDelta = vector_item->second; Value* retractedValue(key_value->value.retract_(singleDelta)); // Retract result.values_.insert(key, retractedValue); // Add retracted result directly to result values @@ -184,12 +184,13 @@ namespace gtsam { void Values::update(Key j, const Value& val) { // Find the value to update KeyValueMap::iterator item = values_.find(j); - if(item == values_.end()) + if (item == values_.end()) throw ValuesKeyDoesNotExist("update", j); // Cast to the derived type - if(typeid(*item->second) != typeid(val)) - throw ValuesIncorrectType(j, typeid(*item->second), typeid(val)); + const Value& old_value = *item->second; + if (typeid(old_value) != typeid(val)) + throw ValuesIncorrectType(j, typeid(old_value), typeid(val)); values_.replace(item, val.clone_()); } @@ -210,8 +211,9 @@ namespace gtsam { } /* ************************************************************************* */ - FastList Values::keys() const { - FastList result; + KeyVector Values::keys() const { + KeyVector result; + result.reserve(size()); for(const_iterator key_value = begin(); key_value != end(); ++key_value) result.push_back(key_value->key); return result; diff --git a/gtsam/nonlinear/Values.h b/gtsam/nonlinear/Values.h index 4eb89b084..70aadfa06 100644 --- a/gtsam/nonlinear/Values.h +++ b/gtsam/nonlinear/Values.h @@ -32,6 +32,7 @@ #ifdef __GNUC__ #pragma GCC diagnostic push #pragma GCC diagnostic ignored "-Wunused-variable" +#pragma GCC diagnostic ignored "-Wunused-local-typedefs" #endif #include #ifdef __GNUC__ @@ -291,7 +292,7 @@ namespace gtsam { * Returns a set of keys in the config * Note: by construction, the list is ordered */ - KeyList keys() const; + KeyVector keys() const; /** Replace all keys and variables */ Values& operator=(const Values& rhs); diff --git a/gtsam/nonlinear/expressionTesting.h b/gtsam/nonlinear/expressionTesting.h index 47f61b8b1..b15592c00 100644 --- a/gtsam/nonlinear/expressionTesting.h +++ b/gtsam/nonlinear/expressionTesting.h @@ -20,56 +20,22 @@ #pragma once #include -#include #include -#include #include -#include - -#include -#include -#include namespace gtsam { -namespace internal { -// CPPUnitLite-style test for linearization of a factor -void testFactorJacobians(TestResult& result_, const std::string& name_, - const NoiseModelFactor& factor, const gtsam::Values& values, double delta, - double tolerance) { - - // Create expected value by numerical differentiation - JacobianFactor expected = linearizeNumerically(factor, values, delta); - - // Create actual value by linearize - boost::shared_ptr actual = // - boost::dynamic_pointer_cast(factor.linearize(values)); - - // Check cast result and then equality - CHECK(actual); - EXPECT(assert_equal(expected, *actual, tolerance)); -} -} - -/// \brief Check the Jacobians produced by a factor against finite differences. -/// \param factor The factor to test. -/// \param values Values filled in for testing the Jacobians. -/// \param numerical_derivative_step The step to use when computing the numerical derivative Jacobians -/// \param tolerance The numerical tolerance to use when comparing Jacobians. -#define EXPECT_CORRECT_FACTOR_JACOBIANS(factor, values, numerical_derivative_step, tolerance) \ - { gtsam::internal::testFactorJacobians(result_, name_, factor, values, numerical_derivative_step, tolerance); } - namespace internal { // CPPUnitLite-style test for linearization of an ExpressionFactor template -void testExpressionJacobians(TestResult& result_, const std::string& name_, +bool testExpressionJacobians(TestResult& result_, const std::string& name_, const gtsam::Expression& expression, const gtsam::Values& values, double nd_step, double tolerance) { // Create factor size_t size = traits::dimension; ExpressionFactor f(noiseModel::Unit::Create(size), expression.value(values), expression); - testFactorJacobians(result_, name_, f, values, nd_step, tolerance); + return testFactorJacobians(result_, name_, f, values, nd_step, tolerance); } } // namespace internal } // namespace gtsam @@ -80,4 +46,4 @@ void testExpressionJacobians(TestResult& result_, const std::string& name_, /// \param numerical_derivative_step The step to use when computing the finite difference Jacobians /// \param tolerance The numerical tolerance to use when comparing Jacobians. #define EXPECT_CORRECT_EXPRESSION_JACOBIANS(expression, values, numerical_derivative_step, tolerance) \ - { gtsam::internal::testExpressionJacobians(result_, name_, expression, values, numerical_derivative_step, tolerance); } + { EXPECT(gtsam::internal::testExpressionJacobians(result_, name_, expression, values, numerical_derivative_step, tolerance)); } diff --git a/gtsam/nonlinear/expressions.h b/gtsam/nonlinear/expressions.h index 2f46d6d74..5b591bcf0 100644 --- a/gtsam/nonlinear/expressions.h +++ b/gtsam/nonlinear/expressions.h @@ -12,20 +12,28 @@ namespace gtsam { -// Generics -template +// Generic between, assumes existence of traits::Between +template Expression between(const Expression& t1, const Expression& t2) { return Expression(traits::Between, t1, t2); } -// Generics -template +// Generic compose, assumes existence of traits::Compose +template Expression compose(const Expression& t1, const Expression& t2) { return Expression(traits::Compose, t1, t2); } +// Some typedefs typedef Expression double_; +typedef Expression Vector1_; +typedef Expression Vector2_; typedef Expression Vector3_; +typedef Expression Vector4_; +typedef Expression Vector5_; +typedef Expression Vector6_; +typedef Expression Vector7_; +typedef Expression Vector8_; +typedef Expression Vector9_; -} // \namespace gtsam - +} // \namespace gtsam diff --git a/gtsam/nonlinear/factorTesting.h b/gtsam/nonlinear/factorTesting.h index 442b29382..2a9d70cb4 100644 --- a/gtsam/nonlinear/factorTesting.h +++ b/gtsam/nonlinear/factorTesting.h @@ -22,6 +22,10 @@ #include #include +#include +#include +#include + namespace gtsam { /** @@ -29,6 +33,10 @@ namespace gtsam { * The benefit of this method is that it does not need to know what types are * involved to evaluate the factor. If all the machinery of gtsam is working * correctly, we should get the correct numerical derivatives out the other side. + * NOTE(frank): factor that have non vector-space measurements use between or LocalCoordinates + * to evaluate the error, and their derivatives will only be correct for near-zero errors. + * This is fixable but expensive, and does not matter in practice as most factors will sit near + * zero errors anyway. However, it means that below will only be exact for the correct measurement. */ JacobianFactor linearizeNumerically(const NoiseModelFactor& factor, const Values& values, double delta = 1e-5) { @@ -65,4 +73,44 @@ JacobianFactor linearizeNumerically(const NoiseModelFactor& factor, return JacobianFactor(jacobians, -e); } +namespace internal { +// CPPUnitLite-style test for linearization of a factor +bool testFactorJacobians(TestResult& result_, const std::string& name_, + const NoiseModelFactor& factor, const gtsam::Values& values, double delta, + double tolerance) { + + // Create expected value by numerical differentiation + JacobianFactor expected = linearizeNumerically(factor, values, delta); + + // Create actual value by linearize + boost::shared_ptr actual = // + boost::dynamic_pointer_cast(factor.linearize(values)); + if (!actual) return false; + + // Check cast result and then equality + bool equal = assert_equal(expected, *actual, tolerance); + + // if not equal, test individual jacobians: + if (!equal) { + for (size_t i = 0; i < actual->size(); i++) { + bool i_good = assert_equal((Matrix) (expected.getA(expected.begin() + i)), + (Matrix) (actual->getA(actual->begin() + i)), tolerance); + if (!i_good) { + std::cout << "Mismatch in Jacobian " << i+1 << " (base 1), as shown above" << std::endl; + } + } + } + + return equal; +} +} + +/// \brief Check the Jacobians produced by a factor against finite differences. +/// \param factor The factor to test. +/// \param values Values filled in for testing the Jacobians. +/// \param numerical_derivative_step The step to use when computing the numerical derivative Jacobians +/// \param tolerance The numerical tolerance to use when comparing Jacobians. +#define EXPECT_CORRECT_FACTOR_JACOBIANS(factor, values, numerical_derivative_step, tolerance) \ + { EXPECT(gtsam::internal::testFactorJacobians(result_, name_, factor, values, numerical_derivative_step, tolerance)); } + } // namespace gtsam diff --git a/gtsam/nonlinear/internal/ExecutionTrace.h b/gtsam/nonlinear/internal/ExecutionTrace.h index 37ce4dfd5..315261293 100644 --- a/gtsam/nonlinear/internal/ExecutionTrace.h +++ b/gtsam/nonlinear/internal/ExecutionTrace.h @@ -17,7 +17,7 @@ */ #pragma once - +#include // Configuration from CMake #include #include #include @@ -119,7 +119,6 @@ public: else if (kind == Leaf) std::cout << indent << "Leaf, key = " << content.key << std::endl; else if (kind == Function) { - std::cout << indent << "Function" << std::endl; content.ptr->print(indent + " "); } } diff --git a/gtsam/nonlinear/internal/ExpressionNode.h b/gtsam/nonlinear/internal/ExpressionNode.h index e7aa34db0..928387eb9 100644 --- a/gtsam/nonlinear/internal/ExpressionNode.h +++ b/gtsam/nonlinear/internal/ExpressionNode.h @@ -78,13 +78,14 @@ public: virtual ~ExpressionNode() { } + /// Print + virtual void print(const std::string& indent = "") const = 0; + /// Streaming GTSAM_EXPORT - friend std::ostream &operator<<(std::ostream &os, - const ExpressionNode& node) { + friend std::ostream& operator<<(std::ostream& os, const ExpressionNode& node) { os << "Expression of type " << typeid(T).name(); - if (node.traceSize_ > 0) - os << ", trace size = " << node.traceSize_; + if (node.traceSize_ > 0) os << ", trace size = " << node.traceSize_; os << "\n"; return os; } @@ -133,6 +134,11 @@ public: virtual ~ConstantExpression() { } + /// Print + virtual void print(const std::string& indent = "") const { + std::cout << indent << "Constant" << std::endl; + } + /// Return value virtual T value(const Values& values) const { return constant_; @@ -159,7 +165,7 @@ class LeafExpression: public ExpressionNode { key_(key) { } - friend class Expression ; + friend class Expression; public: @@ -167,6 +173,11 @@ public: virtual ~LeafExpression() { } + /// Print + virtual void print(const std::string& indent = "") const { + std::cout << indent << "Leaf, key = " << key_ << std::endl; + } + /// Return keys that play in this expression virtual std::set keys() const { std::set keys; @@ -200,8 +211,16 @@ struct Jacobian { typedef Eigen::Matrix::dimension, traits::dimension> type; }; -// Eigen format for printing Jacobians -static const Eigen::IOFormat kMatlabFormat(0, 1, " ", "; ", "", "", "[", "]"); +// Helper function for printing Jacobians with compact Eigen format, and trace +template +static void PrintJacobianAndTrace(const std::string& indent, + const typename Jacobian::type& dTdA, + const ExecutionTrace trace) { + static const Eigen::IOFormat kMatlabFormat(0, 1, " ", "; ", "", "", "[", "]"); + std::cout << indent << "D(" << typeid(T).name() << ")/D(" << typeid(A).name() + << ") = " << dTdA.format(kMatlabFormat) << std::endl; + trace.print(indent); +} //----------------------------------------------------------------------------- /// Unary Function Expression @@ -218,7 +237,7 @@ class UnaryExpression: public ExpressionNode { ExpressionNode::traceSize_ = upAligned(sizeof(Record)) + e1.traceSize(); } - friend class Expression ; + friend class Expression; public: @@ -226,6 +245,12 @@ public: virtual ~UnaryExpression() { } + /// Print + virtual void print(const std::string& indent = "") const { + std::cout << indent << "UnaryExpression" << std::endl; + expression1_->print(indent + " "); + } + /// Return value virtual T value(const Values& values) const { return function_(expression1_->value(values), boost::none); @@ -251,8 +276,7 @@ public: /// Print to std::cout void print(const std::string& indent) const { std::cout << indent << "UnaryExpression::Record {" << std::endl; - std::cout << indent << dTdA1.format(kMatlabFormat) << std::endl; - trace1.print(indent); + PrintJacobianAndTrace(indent, dTdA1, trace1); std::cout << indent << "}" << std::endl; } @@ -293,11 +317,11 @@ public: // Return value of type T is recorded in record->value record->value1 = expression1_->traceExecution(values, record->trace1, ptr); - // ptr is never modified by traceExecution, but if traceExecution has - // written in the buffer, the next caller expects we advance the pointer + // We have written in the buffer, the next caller expects we advance the pointer ptr += expression1_->traceSize(); trace.setFunction(record); + // Finally, the function call fills in the Jacobian dTdA1 return function_(record->value1, record->dTdA1); } }; @@ -320,7 +344,7 @@ class BinaryExpression: public ExpressionNode { upAligned(sizeof(Record)) + e1.traceSize() + e2.traceSize(); } - friend class Expression ; + friend class Expression; friend class ::ExpressionFactorBinaryTest; public: @@ -329,6 +353,13 @@ public: virtual ~BinaryExpression() { } + /// Print + virtual void print(const std::string& indent = "") const { + std::cout << indent << "BinaryExpression" << std::endl; + expression1_->print(indent + " "); + expression2_->print(indent + " "); + } + /// Return value virtual T value(const Values& values) const { using boost::none; @@ -364,10 +395,8 @@ public: /// Print to std::cout void print(const std::string& indent) const { std::cout << indent << "BinaryExpression::Record {" << std::endl; - std::cout << indent << dTdA1.format(kMatlabFormat) << std::endl; - trace1.print(indent); - std::cout << indent << dTdA2.format(kMatlabFormat) << std::endl; - trace2.print(indent); + PrintJacobianAndTrace(indent, dTdA1, trace1); + PrintJacobianAndTrace(indent, dTdA2, trace2); std::cout << indent << "}" << std::endl; } @@ -392,11 +421,11 @@ public: Record* record = new (ptr) Record(); ptr += upAligned(sizeof(Record)); record->value1 = expression1_->traceExecution(values, record->trace1, ptr); + ptr += expression1_->traceSize(); record->value2 = expression2_->traceExecution(values, record->trace2, ptr); - ptr += expression1_->traceSize() + expression2_->traceSize(); + ptr += expression2_->traceSize(); trace.setFunction(record); - return function_(record->value1, record->value2, record->dTdA1, - record->dTdA2); + return function_(record->value1, record->value2, record->dTdA1, record->dTdA2); } }; @@ -420,7 +449,7 @@ class TernaryExpression: public ExpressionNode { e1.traceSize() + e2.traceSize() + e3.traceSize(); } - friend class Expression ; + friend class Expression; public: @@ -428,6 +457,14 @@ public: virtual ~TernaryExpression() { } + /// Print + virtual void print(const std::string& indent = "") const { + std::cout << indent << "TernaryExpression" << std::endl; + expression1_->print(indent + " "); + expression2_->print(indent + " "); + expression3_->print(indent + " "); + } + /// Return value virtual T value(const Values& values) const { using boost::none; @@ -470,12 +507,9 @@ public: /// Print to std::cout void print(const std::string& indent) const { std::cout << indent << "TernaryExpression::Record {" << std::endl; - std::cout << indent << dTdA1.format(kMatlabFormat) << std::endl; - trace1.print(indent); - std::cout << indent << dTdA2.format(kMatlabFormat) << std::endl; - trace2.print(indent); - std::cout << indent << dTdA3.format(kMatlabFormat) << std::endl; - trace3.print(indent); + PrintJacobianAndTrace(indent, dTdA1, trace1); + PrintJacobianAndTrace(indent, dTdA2, trace2); + PrintJacobianAndTrace(indent, dTdA3, trace3); std::cout << indent << "}" << std::endl; } @@ -502,10 +536,11 @@ public: Record* record = new (ptr) Record(); ptr += upAligned(sizeof(Record)); record->value1 = expression1_->traceExecution(values, record->trace1, ptr); + ptr += expression1_->traceSize(); record->value2 = expression2_->traceExecution(values, record->trace2, ptr); + ptr += expression2_->traceSize(); record->value3 = expression3_->traceExecution(values, record->trace3, ptr); - ptr += expression1_->traceSize() + expression2_->traceSize() - + expression3_->traceSize(); + ptr += expression3_->traceSize(); trace.setFunction(record); return function_(record->value1, record->value2, record->value3, record->dTdA1, record->dTdA2, record->dTdA3); diff --git a/gtsam/nonlinear/internal/JacobianMap.h b/gtsam/nonlinear/internal/JacobianMap.h index f4d2e9565..c99f05b7d 100644 --- a/gtsam/nonlinear/internal/JacobianMap.h +++ b/gtsam/nonlinear/internal/JacobianMap.h @@ -31,19 +31,18 @@ namespace internal { // The JacobianMap provides a mapping from keys to the underlying blocks. class JacobianMap { private: - typedef FastVector Keys; - const FastVector& keys_; + const KeyVector& keys_; VerticalBlockMatrix& Ab_; public: /// Construct a JacobianMap for writing into a VerticalBlockMatrix Ab - JacobianMap(const Keys& keys, VerticalBlockMatrix& Ab) : + JacobianMap(const KeyVector& keys, VerticalBlockMatrix& Ab) : keys_(keys), Ab_(Ab) { } /// Access blocks of via key VerticalBlockMatrix::Block operator()(Key key) { - Keys::const_iterator it = std::find(keys_.begin(), keys_.end(), key); + KeyVector::const_iterator it = std::find(keys_.begin(), keys_.end(), key); DenseIndex block = it - keys_.begin(); return Ab_(block); } diff --git a/gtsam/nonlinear/tests/testAdaptAutoDiff.cpp b/gtsam/nonlinear/tests/testAdaptAutoDiff.cpp index 3f477098a..16117845e 100644 --- a/gtsam/nonlinear/tests/testAdaptAutoDiff.cpp +++ b/gtsam/nonlinear/tests/testAdaptAutoDiff.cpp @@ -1,6 +1,6 @@ /* ---------------------------------------------------------------------------- - * GTSAM Copyright 2010, Georgia Tech Research Corporation, + * 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) @@ -36,81 +36,43 @@ using boost::assign::map_list_of; namespace gtsam { // Special version of Cal3Bundler so that default constructor = 0,0,0 -struct Cal: public Cal3Bundler { - Cal(double f = 0, double k1 = 0, double k2 = 0, double u0 = 0, double v0 = 0) : - Cal3Bundler(f, k1, k2, u0, v0) { +struct Cal3Bundler0 : public Cal3Bundler { + Cal3Bundler0(double f = 0, double k1 = 0, double k2 = 0, double u0 = 0, + double v0 = 0) + : Cal3Bundler(f, k1, k2, u0, v0) {} + Cal3Bundler0 retract(const Vector& d) const { + return Cal3Bundler0(fx() + d(0), k1() + d(1), k2() + d(2), u0(), v0()); } - Cal retract(const Vector& d) const { - return Cal(fx() + d(0), k1() + d(1), k2() + d(2), u0(), v0()); - } - Vector3 localCoordinates(const Cal& T2) const { + Vector3 localCoordinates(const Cal3Bundler0& T2) const { return T2.vector() - vector(); } }; -template<> -struct traits : public internal::Manifold {}; +template <> +struct traits : public internal::Manifold {}; // With that, camera below behaves like Snavely's 9-dim vector -typedef PinholeCamera Camera; - +typedef PinholeCamera Camera; } using namespace std; using namespace gtsam; /* ************************************************************************* */ -// charts -TEST(AdaptAutoDiff, Canonical) { - - Canonical chart1; - EXPECT(chart1.Local(Point2(1, 0))==Vector2(1, 0)); - EXPECT(chart1.Retract(Vector2(1, 0))==Point2(1, 0)); - - Vector v2(2); - v2 << 1, 0; - Canonical chart2; - EXPECT(assert_equal(v2, chart2.Local(Vector2(1, 0)))); - EXPECT(chart2.Retract(v2)==Vector2(1, 0)); - - Canonical chart3; - Eigen::Matrix v1; - v1 << 1; - EXPECT(chart3.Local(1)==v1); - EXPECT_DOUBLES_EQUAL(chart3.Retract(v1), 1, 1e-9); - - Canonical chart4; - Point3 point(1, 2, 3); - Vector v3(3); - v3 << 1, 2, 3; - EXPECT(assert_equal(v3, chart4.Local(point))); - EXPECT(assert_equal(chart4.Retract(v3), point)); - - Canonical chart5; - Pose3 pose(Rot3::identity(), point); - Vector v6(6); - v6 << 0, 0, 0, 1, 2, 3; - EXPECT(assert_equal(v6, chart5.Local(pose))); - EXPECT(assert_equal(chart5.Retract(v6), pose)); - - Canonical chart6; - Cal cal0; - Vector z3 = Vector3::Zero(); - EXPECT(assert_equal(z3, chart6.Local(cal0))); - EXPECT(assert_equal(chart6.Retract(z3), cal0)); - - Canonical chart7; - Camera camera(Pose3(), cal0); - Vector z9 = Vector9::Zero(); - EXPECT(assert_equal(z9, chart7.Local(camera))); - EXPECT(assert_equal(chart7.Retract(z9), camera)); +// Check that ceres rotation convention is the same +TEST(AdaptAutoDiff, Rotation) { + Vector3 axisAngle(0.1, 0.2, 0.3); + Matrix3 expected = Rot3::Rodrigues(axisAngle).matrix(); + Matrix3 actual; + ceres::AngleAxisToRotationMatrix(axisAngle.data(), actual.data()); + EXPECT(assert_equal(expected, actual)); } /* ************************************************************************* */ // Some Ceres Snippets copied for testing // Copyright 2010, 2011, 2012 Google Inc. All rights reserved. -template inline T &RowMajorAccess(T *base, int rows, int cols, - int i, int j) { +template +inline T& RowMajorAccess(T* base, int rows, int cols, int i, int j) { return base[cols * i + j]; } @@ -124,14 +86,14 @@ inline double RandDouble() { struct Projective { // Function that takes P and X as separate vectors: // P, X -> x - template + template bool operator()(A const P[12], A const X[4], A x[2]) const { A PX[3]; for (int i = 0; i < 3; ++i) { - PX[i] = RowMajorAccess(P, 3, 4, i, 0) * X[0] - + RowMajorAccess(P, 3, 4, i, 1) * X[1] - + RowMajorAccess(P, 3, 4, i, 2) * X[2] - + RowMajorAccess(P, 3, 4, i, 3) * X[3]; + PX[i] = RowMajorAccess(P, 3, 4, i, 0) * X[0] + + RowMajorAccess(P, 3, 4, i, 1) * X[1] + + RowMajorAccess(P, 3, 4, i, 2) * X[2] + + RowMajorAccess(P, 3, 4, i, 3) * X[3]; } if (PX[2] != 0.0) { x[0] = PX[0] / PX[2]; @@ -160,29 +122,31 @@ TEST(AdaptAutoDiff, AutoDiff) { Projective projective; // Make arguments - typedef Eigen::Matrix M; - M P; + typedef Eigen::Matrix RowMajorMatrix34; + RowMajorMatrix34 P; P << 1, 0, 0, 0, 0, 1, 0, 5, 0, 0, 1, 0; Vector4 X(10, 0, 5, 1); // Apply the mapping, to get image point b_x. Vector expected = Vector2(2, 1); Vector2 actual = projective(P, X); - EXPECT(assert_equal(expected,actual,1e-9)); + EXPECT(assert_equal(expected, actual, 1e-9)); // Get expected derivatives - Matrix E1 = numericalDerivative21(Projective(), P, X); - Matrix E2 = numericalDerivative22(Projective(), P, X); + Matrix E1 = numericalDerivative21( + Projective(), P, X); + Matrix E2 = numericalDerivative22( + Projective(), P, X); // Get derivatives with AutoDiff Vector2 actual2; MatrixRowMajor H1(2, 12), H2(2, 4); - double *parameters[] = { P.data(), X.data() }; - double *jacobians[] = { H1.data(), H2.data() }; - CHECK( - (AutoDiff::Differentiate( projective, parameters, 2, actual2.data(), jacobians))); - EXPECT(assert_equal(E1,H1,1e-8)); - EXPECT(assert_equal(E2,H2,1e-8)); + double* parameters[] = {P.data(), X.data()}; + double* jacobians[] = {H1.data(), H2.data()}; + CHECK((AutoDiff::Differentiate( + projective, parameters, 2, actual2.data(), jacobians))); + EXPECT(assert_equal(E1, H1, 1e-8)); + EXPECT(assert_equal(E2, H2, 1e-8)); } /* ************************************************************************* */ @@ -197,78 +161,85 @@ Vector2 adapted(const Vector9& P, const Vector3& X) { throw std::runtime_error("Snavely fail"); } +/* ************************************************************************* */ +namespace example { +Camera camera(Pose3(Rot3().retract(Vector3(0.1, 0.2, 0.3)), Point3(0, 5, 0)), + Cal3Bundler0(1, 0, 0)); +Point3 point(10, 0, -5); // negative Z-axis convention of Snavely! +Vector9 P = Camera().localCoordinates(camera); +Vector3 X = Point3::Logmap(point); +Vector2 expectedMeasurement(1.2431567, 1.2525694); +Matrix E1 = numericalDerivative21(adapted, P, X); +Matrix E2 = numericalDerivative22(adapted, P, X); +} + +/* ************************************************************************* */ +// Check that Local worked as expected +TEST(AdaptAutoDiff, Local) { + using namespace example; + Vector9 expectedP = (Vector9() << 0.1, 0.2, 0.3, 0, 5, 0, 1, 0, 0).finished(); + EXPECT(equal_with_abs_tol(expectedP, P)); + Vector3 expectedX(10, 0, -5); // negative Z-axis convention of Snavely! + EXPECT(equal_with_abs_tol(expectedX, X)); +} + +/* ************************************************************************* */ +// Test Ceres AutoDiff TEST(AdaptAutoDiff, AutoDiff2) { + using namespace example; using ceres::internal::AutoDiff; + // Apply the mapping, to get image point b_x. + Vector2 actual = adapted(P, X); + EXPECT(assert_equal(expectedMeasurement, actual, 1e-6)); + // Instantiate function SnavelyProjection snavely; - // Make arguments - Vector9 P; // zero rotation, (0,5,0) translation, focal length 1 - P << 0, 0, 0, 0, 5, 0, 1, 0, 0; - Vector3 X(10, 0, -5); // negative Z-axis convention of Snavely! - - // Apply the mapping, to get image point b_x. - Vector expected = Vector2(2, 1); - Vector2 actual = adapted(P, X); - EXPECT(assert_equal(expected,actual,1e-9)); - - // Get expected derivatives - Matrix E1 = numericalDerivative21(adapted, P, X); - Matrix E2 = numericalDerivative22(adapted, P, X); - // Get derivatives with AutoDiff Vector2 actual2; MatrixRowMajor H1(2, 9), H2(2, 3); - double *parameters[] = { P.data(), X.data() }; - double *jacobians[] = { H1.data(), H2.data() }; - CHECK( - (AutoDiff::Differentiate( snavely, parameters, 2, actual2.data(), jacobians))); - EXPECT(assert_equal(E1,H1,1e-8)); - EXPECT(assert_equal(E2,H2,1e-8)); + double* parameters[] = {P.data(), X.data()}; + double* jacobians[] = {H1.data(), H2.data()}; + CHECK((AutoDiff::Differentiate( + snavely, parameters, 2, actual2.data(), jacobians))); + EXPECT(assert_equal(E1, H1, 1e-8)); + EXPECT(assert_equal(E2, H2, 1e-8)); } /* ************************************************************************* */ // Test AutoDiff wrapper Snavely -TEST(AdaptAutoDiff, AutoDiff3) { +TEST(AdaptAutoDiff, AdaptAutoDiff) { + using namespace example; - // Make arguments - Camera P(Pose3(Rot3(), Point3(0, 5, 0)), Cal(1, 0, 0)); - Point3 X(10, 0, -5); // negative Z-axis convention of Snavely! - - typedef AdaptAutoDiff Adaptor; + typedef AdaptAutoDiff Adaptor; Adaptor snavely; // Apply the mapping, to get image point b_x. - Point2 expected(2, 1); - Point2 actual = snavely(P, X); - EXPECT(assert_equal(expected,actual,1e-9)); - -// // Get expected derivatives - Matrix E1 = numericalDerivative21(Adaptor(), P, X); - Matrix E2 = numericalDerivative22(Adaptor(), P, X); + Vector2 actual = snavely(P, X); + EXPECT(assert_equal(expectedMeasurement, actual, 1e-6)); // Get derivatives with AutoDiff, not gives RowMajor results! Matrix29 H1; Matrix23 H2; - Point2 actual2 = snavely(P, X, H1, H2); - EXPECT(assert_equal(expected,actual2,1e-9)); - EXPECT(assert_equal(E1,H1,1e-8)); - EXPECT(assert_equal(E2,H2,1e-8)); + Vector2 actual2 = snavely(P, X, H1, H2); + EXPECT(assert_equal(expectedMeasurement, actual2, 1e-6)); + EXPECT(assert_equal(E1, H1, 1e-8)); + EXPECT(assert_equal(E2, H2, 1e-8)); } /* ************************************************************************* */ // Test AutoDiff wrapper in an expression -TEST(AdaptAutoDiff, Snavely) { - Expression P(1); - Expression X(2); - typedef AdaptAutoDiff Adaptor; - Expression expression(Adaptor(), P, X); +TEST(AdaptAutoDiff, SnavelyExpression) { + Expression P(1); + Expression X(2); + typedef AdaptAutoDiff Adaptor; + Expression expression(Adaptor(), P, X); + EXPECT_LONGS_EQUAL( + sizeof(internal::BinaryExpression::Record), + expression.traceSize()); #ifdef GTSAM_USE_QUATERNIONS - EXPECT_LONGS_EQUAL(384,expression.traceSize()); // Todo, should be zero -#else - EXPECT_LONGS_EQUAL(sizeof(internal::BinaryExpression::Record), - expression.traceSize()); // Todo, should be zero + EXPECT_LONGS_EQUAL(336, expression.traceSize()); #endif set expected = list_of(1)(2); EXPECT(expected == expression.keys()); @@ -280,4 +251,3 @@ int main() { return TestRegistry::runAllTests(tr); } /* ************************************************************************* */ - diff --git a/gtsam/nonlinear/tests/testExpression.cpp b/gtsam/nonlinear/tests/testExpression.cpp index 3e86bcb8c..75af5f634 100644 --- a/gtsam/nonlinear/tests/testExpression.cpp +++ b/gtsam/nonlinear/tests/testExpression.cpp @@ -175,7 +175,8 @@ using namespace binary; Expression K(3); // Create expression tree -Expression projection(PinholeCamera::project_to_camera, p_cam); +Point2 (*f)(const Point3&, OptionalJacobian<2, 3>) = &PinholeBase::Project; +Expression projection(f, p_cam); Expression uv_hat(uncalibrate, K, projection); } /* ************************************************************************* */ diff --git a/gtsam/nonlinear/tests/testValues.cpp b/gtsam/nonlinear/tests/testValues.cpp index faa285cd5..dfc14e1e6 100644 --- a/gtsam/nonlinear/tests/testValues.cpp +++ b/gtsam/nonlinear/tests/testValues.cpp @@ -26,6 +26,7 @@ #include #include // for operator += +#include #include using namespace boost::assign; #include @@ -308,12 +309,12 @@ TEST(Values, extract_keys) config.insert(key3, Pose2()); config.insert(key4, Pose2()); - FastList expected, actual; + KeyVector expected, actual; expected += key1, key2, key3, key4; actual = config.keys(); CHECK(actual.size() == expected.size()); - FastList::const_iterator itAct = actual.begin(), itExp = expected.begin(); + KeyVector::const_iterator itAct = actual.begin(), itExp = expected.begin(); for (; itAct != actual.end() && itExp != expected.end(); ++itAct, ++itExp) { EXPECT(*itExp == *itAct); } diff --git a/gtsam/sam/BearingFactor.h b/gtsam/sam/BearingFactor.h new file mode 100644 index 000000000..f190e683c --- /dev/null +++ b/gtsam/sam/BearingFactor.h @@ -0,0 +1,70 @@ +/* ---------------------------------------------------------------------------- + + * 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 BearingFactor.h + * @brief Serializable factor induced by a bearing measurement + * @date July 2015 + * @author Frank Dellaert + **/ + +#pragma once + +#include + +namespace gtsam { + +// forward declaration of Bearing functor, assumed partially specified +template +struct Bearing; + +/** + * Binary factor for a bearing measurement + * Works for any two types A1,A2 for which the functor Bearing() is + * defined + * @addtogroup SAM + */ +template ::result_type> +struct BearingFactor : public ExpressionFactor2 { + typedef ExpressionFactor2 Base; + + /// default constructor + BearingFactor() {} + + /// primary constructor + BearingFactor(Key key1, Key key2, const T& measured, + const SharedNoiseModel& model) + : Base(key1, key2, model, measured) { + this->initialize(expression(key1, key2)); + } + + // Return measurement expression + virtual Expression expression(Key key1, Key key2) const { + Expression a1_(key1); + Expression a2_(key2); + return Expression(Bearing(), a1_, a2_); + } + + /// print + void print(const std::string& s = "", + const KeyFormatter& kf = DefaultKeyFormatter) const { + std::cout << s << "BearingFactor" << std::endl; + Base::print(s, kf); + } +}; // BearingFactor + +/// traits +template +struct traits > + : public Testable > {}; + +} // namespace gtsam diff --git a/gtsam/sam/BearingRangeFactor.h b/gtsam/sam/BearingRangeFactor.h new file mode 100644 index 000000000..2dd1fecb8 --- /dev/null +++ b/gtsam/sam/BearingRangeFactor.h @@ -0,0 +1,83 @@ +/* ---------------------------------------------------------------------------- + + * 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 BearingRangeFactor.h + * @date Apr 1, 2010 + * @author Kai Ni + * @brief a single factor contains both the bearing and the range to prevent + * handle to pair bearing and range factors + */ + +#pragma once + +#include +#include +#include + +namespace gtsam { + +/** + * Binary factor for a bearing/range measurement + * @addtogroup SLAM + */ +template ::result_type, + typename R = typename Range::result_type> +class BearingRangeFactor + : public ExpressionFactor2, A1, A2> { + private: + typedef BearingRange T; + typedef ExpressionFactor2 Base; + typedef BearingRangeFactor This; + + public: + typedef boost::shared_ptr shared_ptr; + + /// default constructor + BearingRangeFactor() {} + + /// primary constructor + BearingRangeFactor(Key key1, Key key2, const B& measuredBearing, + const R& measuredRange, const SharedNoiseModel& model) + : Base(key1, key2, model, T(measuredBearing, measuredRange)) { + this->initialize(expression(key1, key2)); + } + + virtual ~BearingRangeFactor() {} + + /// @return a deep copy of this factor + virtual gtsam::NonlinearFactor::shared_ptr clone() const { + return boost::static_pointer_cast( + gtsam::NonlinearFactor::shared_ptr(new This(*this))); + } + + // Return measurement expression + virtual Expression expression(Key key1, Key key2) const { + return Expression(T::Measure, Expression(key1), + Expression(key2)); + } + + /// print + virtual void print(const std::string& s = "", + const KeyFormatter& kf = DefaultKeyFormatter) const { + std::cout << s << "BearingRangeFactor" << std::endl; + Base::print(s, kf); + } + +}; // BearingRangeFactor + +/// traits +template +struct traits > + : public Testable > {}; + +} // namespace gtsam diff --git a/gtsam/sam/CMakeLists.txt b/gtsam/sam/CMakeLists.txt new file mode 100644 index 000000000..bf20b751c --- /dev/null +++ b/gtsam/sam/CMakeLists.txt @@ -0,0 +1,6 @@ +# Install headers +file(GLOB sam_headers "*.h") +install(FILES ${sam_headers} DESTINATION include/gtsam/sam) + +# Build tests +add_subdirectory(tests) diff --git a/gtsam/sam/RangeFactor.h b/gtsam/sam/RangeFactor.h new file mode 100644 index 000000000..a5bcac822 --- /dev/null +++ b/gtsam/sam/RangeFactor.h @@ -0,0 +1,141 @@ +/* ---------------------------------------------------------------------------- + + * 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 RangeFactor.h + * @brief Serializable factor induced by a range measurement + * @date July 2015 + * @author Frank Dellaert + **/ + +#pragma once + +#include + +namespace gtsam { + +// forward declaration of Range functor, assumed partially specified +template +struct Range; + +/** + * Binary factor for a range measurement + * Works for any two types A1,A2 for which the functor Range() is defined + * @addtogroup SAM + */ +template +class RangeFactor : public ExpressionFactor2 { + private: + typedef RangeFactor This; + typedef ExpressionFactor2 Base; + + public: + /// default constructor + RangeFactor() {} + + RangeFactor(Key key1, Key key2, T measured, const SharedNoiseModel& model) + : Base(key1, key2, model, measured) { + this->initialize(expression(key1, key2)); + } + + /// @return a deep copy of this factor + virtual gtsam::NonlinearFactor::shared_ptr clone() const { + return boost::static_pointer_cast( + gtsam::NonlinearFactor::shared_ptr(new This(*this))); + } + + // Return measurement expression + virtual Expression expression(Key key1, Key key2) const { + Expression a1_(key1); + Expression a2_(key2); + return Expression(Range(), a1_, a2_); + } + + /// print + void print(const std::string& s = "", + const KeyFormatter& kf = DefaultKeyFormatter) const { + std::cout << s << "RangeFactor" << std::endl; + Base::print(s, kf); + } +}; // \ RangeFactor + +/// traits +template +struct traits > + : public Testable > {}; + +/** + * Binary factor for a range measurement, with a transform applied + * @addtogroup SAM + */ +template ::result_type> +class RangeFactorWithTransform : public ExpressionFactor2 { + private: + typedef RangeFactorWithTransform This; + typedef ExpressionFactor2 Base; + + A1 body_T_sensor_; ///< The pose of the sensor in the body frame + + public: + //// Default constructor + RangeFactorWithTransform() {} + + RangeFactorWithTransform(Key key1, Key key2, T measured, + const SharedNoiseModel& model, + const A1& body_T_sensor) + : Base(key1, key2, model, measured), body_T_sensor_(body_T_sensor) { + this->initialize(expression(key1, key2)); + } + + virtual ~RangeFactorWithTransform() {} + + /// @return a deep copy of this factor + virtual gtsam::NonlinearFactor::shared_ptr clone() const { + return boost::static_pointer_cast( + gtsam::NonlinearFactor::shared_ptr(new This(*this))); + } + + // Return measurement expression + virtual Expression expression(Key key1, Key key2) const { + Expression body_T_sensor__(body_T_sensor_); + Expression nav_T_body_(key1); + Expression nav_T_sensor_(traits::Compose, nav_T_body_, + body_T_sensor__); + Expression a2_(key2); + return Expression(Range(), nav_T_sensor_, a2_); + } + + /** print contents */ + void print(const std::string& s = "", + const KeyFormatter& keyFormatter = DefaultKeyFormatter) const { + std::cout << s << "RangeFactorWithTransform" << std::endl; + this->body_T_sensor_.print(" sensor pose in body frame: "); + Base::print(s, keyFormatter); + } + + private: + /** Serialization function */ + friend class boost::serialization::access; + template + void serialize(ARCHIVE& ar, const unsigned int /*version*/) { + ar& boost::serialization::make_nvp( + "Base", boost::serialization::base_object(*this)); + ar& BOOST_SERIALIZATION_NVP(body_T_sensor_); + } +}; // \ RangeFactorWithTransform + +/// traits +template +struct traits > + : public Testable > {}; + +} // \ namespace gtsam diff --git a/gtsam/sam/tests/CMakeLists.txt b/gtsam/sam/tests/CMakeLists.txt new file mode 100644 index 000000000..127c619ee --- /dev/null +++ b/gtsam/sam/tests/CMakeLists.txt @@ -0,0 +1 @@ +gtsamAddTestsGlob(sam "test*.cpp" "" "gtsam") diff --git a/gtsam/sam/tests/testBearingFactor.cpp b/gtsam/sam/tests/testBearingFactor.cpp new file mode 100644 index 000000000..12635a7e5 --- /dev/null +++ b/gtsam/sam/tests/testBearingFactor.cpp @@ -0,0 +1,117 @@ +/* ---------------------------------------------------------------------------- + + * 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 testBearingFactor.cpp + * @brief Unit tests for BearingFactor Class + * @author Frank Dellaert + * @date July 2015 + */ + +#include +#include +#include +#include +#include +#include +#include + +#include + +using namespace std; +using namespace gtsam; + +Key poseKey(1); +Key pointKey(2); + +typedef BearingFactor BearingFactor2D; +double measurement2D(10.0); +static SharedNoiseModel model2D(noiseModel::Isotropic::Sigma(1, 0.5)); +BearingFactor2D factor2D(poseKey, pointKey, measurement2D, model2D); + +typedef BearingFactor BearingFactor3D; +Unit3 measurement3D = Pose3().bearing(Point3(1, 0, 0)); // has to match values! +static SharedNoiseModel model3D(noiseModel::Isotropic::Sigma(2, 0.5)); +BearingFactor3D factor3D(poseKey, pointKey, measurement3D, model3D); + +/* ************************************************************************* */ +// Export Noisemodels +// See http://www.boost.org/doc/libs/1_32_0/libs/serialization/doc/special.html +BOOST_CLASS_EXPORT(gtsam::noiseModel::Isotropic); + +/* ************************************************************************* */ +TEST(BearingFactor, Serialization2D) { + EXPECT(serializationTestHelpers::equalsObj(factor2D)); + EXPECT(serializationTestHelpers::equalsXML(factor2D)); + EXPECT(serializationTestHelpers::equalsBinary(factor2D)); +} + +/* ************************************************************************* */ +TEST(BearingFactor, 2D) { + // Serialize the factor + std::string serialized = serializeXML(factor2D); + + // And de-serialize it + BearingFactor2D factor; + deserializeXML(serialized, factor); + + // Set the linearization point + Values values; + values.insert(poseKey, Pose2(1.0, 2.0, 0.57)); + values.insert(pointKey, Point2(-4.0, 11.0)); + + EXPECT_CORRECT_EXPRESSION_JACOBIANS(factor.expression(poseKey, pointKey), + values, 1e-7, 1e-5); + EXPECT_CORRECT_FACTOR_JACOBIANS(factor, values, 1e-7, 1e-5); +} + +/* ************************************************************************* */ +TEST(BearingFactor, Serialization3D) { + EXPECT(serializationTestHelpers::equalsObj(factor3D)); + EXPECT(serializationTestHelpers::equalsXML(factor3D)); + EXPECT(serializationTestHelpers::equalsBinary(factor3D)); +} + +/* ************************************************************************* */ +// TODO(frank): this test is disabled (for now) because the macros below are +// incompatible with the Unit3 localCoordinates. The issue is the following: +// For factors, we want to use Local(value, measured), because we need the error +// to be expressed in the tangent space of value. This surfaced in the Unit3 case +// where the tangent space can be radically didfferent from one value to the next. +// For derivatives, we want Local(constant, varying), because we need a derivative +// in a constant tangent space. But since the macros below call whitenedError +// which calls Local(value,measured), we actually call the reverse. This does not +// matter for types with a commutative Local, but matters a lot for Unit3. +// More thinking needed about what the right thing is, here... +//TEST(BearingFactor, 3D) { +// // Serialize the factor +// std::string serialized = serializeXML(factor3D); +// +// // And de-serialize it +// BearingFactor3D factor; +// deserializeXML(serialized, factor); +// +// // Set the linearization point +// Values values; +// values.insert(poseKey, Pose3()); +// values.insert(pointKey, Point3(1, 0, 0)); +// +// EXPECT_CORRECT_EXPRESSION_JACOBIANS(factor.expression(poseKey, pointKey), +// values, 1e-7, 1e-5); +// EXPECT_CORRECT_FACTOR_JACOBIANS(factor, values, 1e-7, 1e-5); +//} + +/* ************************************************************************* */ +int main() { + TestResult tr; + return TestRegistry::runAllTests(tr); +} +/* ************************************************************************* */ diff --git a/gtsam/sam/tests/testBearingRangeFactor.cpp b/gtsam/sam/tests/testBearingRangeFactor.cpp new file mode 100644 index 000000000..4c7a9ab91 --- /dev/null +++ b/gtsam/sam/tests/testBearingRangeFactor.cpp @@ -0,0 +1,108 @@ +/* ---------------------------------------------------------------------------- + + * 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 testBearingRangeFactor.cpp + * @brief Unit tests for BearingRangeFactor Class + * @author Frank Dellaert + * @date July 2015 + */ + +#include +#include +#include +#include +#include +#include +#include + +#include + +using namespace std; +using namespace gtsam; + +Key poseKey(1); +Key pointKey(2); + +typedef BearingRangeFactor BearingRangeFactor2D; +static SharedNoiseModel model2D(noiseModel::Isotropic::Sigma(2, 0.5)); +BearingRangeFactor2D factor2D(poseKey, pointKey, 1, 2, model2D); + +typedef BearingRangeFactor BearingRangeFactor3D; +static SharedNoiseModel model3D(noiseModel::Isotropic::Sigma(3, 0.5)); +BearingRangeFactor3D factor3D(poseKey, pointKey, + Pose3().bearing(Point3(1, 0, 0)), 1, model3D); + +/* ************************************************************************* */ +// Export Noisemodels +// See http://www.boost.org/doc/libs/1_32_0/libs/serialization/doc/special.html +BOOST_CLASS_EXPORT(gtsam::noiseModel::Isotropic); + +/* ************************************************************************* */ +TEST(BearingRangeFactor, Serialization2D) { + EXPECT(serializationTestHelpers::equalsObj(factor2D)); + EXPECT(serializationTestHelpers::equalsXML(factor2D)); + EXPECT(serializationTestHelpers::equalsBinary(factor2D)); +} + +/* ************************************************************************* */ +TEST(BearingRangeFactor, 2D) { + // Serialize the factor + std::string serialized = serializeXML(factor2D); + + // And de-serialize it + BearingRangeFactor2D factor; + deserializeXML(serialized, factor); + + // Set the linearization point + Values values; + values.insert(poseKey, Pose2(1.0, 2.0, 0.57)); + values.insert(pointKey, Point2(-4.0, 11.0)); + + EXPECT_CORRECT_EXPRESSION_JACOBIANS(factor.expression(poseKey, pointKey), + values, 1e-7, 1e-5); + EXPECT_CORRECT_FACTOR_JACOBIANS(factor, values, 1e-7, 1e-5); +} + +/* ************************************************************************* */ +TEST(BearingRangeFactor, Serialization3D) { + EXPECT(serializationTestHelpers::equalsObj(factor3D)); + EXPECT(serializationTestHelpers::equalsXML(factor3D)); + EXPECT(serializationTestHelpers::equalsBinary(factor3D)); +} + +/* ************************************************************************* */ +// TODO(frank): this test is disabled (for now) because the macros below are +// incompatible with the Unit3 localCoordinates. See testBearingFactor... +//TEST(BearingRangeFactor, 3D) { +// // Serialize the factor +// std::string serialized = serializeXML(factor3D); +// +// // And de-serialize it +// BearingRangeFactor3D factor; +// deserializeXML(serialized, factor); +// +// // Set the linearization point +// Values values; +// values.insert(poseKey, Pose3()); +// values.insert(pointKey, Point3(1, 0, 0)); +// +// EXPECT_CORRECT_EXPRESSION_JACOBIANS(factor.expression(poseKey, pointKey), +// values, 1e-7, 1e-5); +// EXPECT_CORRECT_FACTOR_JACOBIANS(factor, values, 1e-7, 1e-5); +//} + +/* ************************************************************************* */ +int main() { + TestResult tr; + return TestRegistry::runAllTests(tr); +} +/* ************************************************************************* */ diff --git a/gtsam/slam/tests/testRangeFactor.cpp b/gtsam/sam/tests/testRangeFactor.cpp similarity index 79% rename from gtsam/slam/tests/testRangeFactor.cpp rename to gtsam/sam/tests/testRangeFactor.cpp index a8455d685..706c20e78 100644 --- a/gtsam/slam/tests/testRangeFactor.cpp +++ b/gtsam/sam/tests/testRangeFactor.cpp @@ -16,14 +16,15 @@ * @date Oct 2012 */ -#include -#include +#include #include -#include #include -#include +#include #include +#include #include + +#include #include using namespace std; @@ -37,6 +38,10 @@ typedef RangeFactor RangeFactor3D; typedef RangeFactorWithTransform RangeFactorWithTransform2D; typedef RangeFactorWithTransform RangeFactorWithTransform3D; +Key poseKey(1); +Key pointKey(2); +double measurement(10.0); + /* ************************************************************************* */ Vector factorError2D(const Pose2& pose, const Point2& point, const RangeFactor2D& factor) { @@ -63,19 +68,33 @@ Vector factorErrorWithTransform3D(const Pose3& pose, const Point3& point, /* ************************************************************************* */ TEST( RangeFactor, Constructor) { - Key poseKey(1); - Key pointKey(2); - double measurement(10.0); - RangeFactor2D factor2D(poseKey, pointKey, measurement, model); RangeFactor3D factor3D(poseKey, pointKey, measurement, model); } +/* ************************************************************************* */ +// Export Noisemodels +// See http://www.boost.org/doc/libs/1_32_0/libs/serialization/doc/special.html +BOOST_CLASS_EXPORT(gtsam::noiseModel::Unit); + +/* ************************************************************************* */ +TEST(RangeFactor, Serialization2D) { + RangeFactor2D factor2D(poseKey, pointKey, measurement, model); + EXPECT(serializationTestHelpers::equalsObj(factor2D)); + EXPECT(serializationTestHelpers::equalsXML(factor2D)); + EXPECT(serializationTestHelpers::equalsBinary(factor2D)); +} + +/* ************************************************************************* */ +TEST(RangeFactor, Serialization3D) { + RangeFactor3D factor3D(poseKey, pointKey, measurement, model); + EXPECT(serializationTestHelpers::equalsObj(factor3D)); + EXPECT(serializationTestHelpers::equalsXML(factor3D)); + EXPECT(serializationTestHelpers::equalsBinary(factor3D)); +} + /* ************************************************************************* */ TEST( RangeFactor, ConstructorWithTransform) { - Key poseKey(1); - Key pointKey(2); - double measurement(10.0); Pose2 body_P_sensor_2D(0.25, -0.10, -M_PI_2); Pose3 body_P_sensor_3D(Rot3::RzRyRx(-M_PI_2, 0.0, -M_PI_2), Point3(0.25, -0.10, 1.0)); @@ -89,10 +108,6 @@ TEST( RangeFactor, ConstructorWithTransform) { /* ************************************************************************* */ TEST( RangeFactor, Equals ) { // Create two identical factors and make sure they're equal - Key poseKey(1); - Key pointKey(2); - double measurement(10.0); - RangeFactor2D factor2D_1(poseKey, pointKey, measurement, model); RangeFactor2D factor2D_2(poseKey, pointKey, measurement, model); CHECK(assert_equal(factor2D_1, factor2D_2)); @@ -105,9 +120,6 @@ TEST( RangeFactor, Equals ) { /* ************************************************************************* */ TEST( RangeFactor, EqualsWithTransform ) { // Create two identical factors and make sure they're equal - Key poseKey(1); - Key pointKey(2); - double measurement(10.0); Pose2 body_P_sensor_2D(0.25, -0.10, -M_PI_2); Pose3 body_P_sensor_3D(Rot3::RzRyRx(-M_PI_2, 0.0, -M_PI_2), Point3(0.25, -0.10, 1.0)); @@ -128,9 +140,6 @@ TEST( RangeFactor, EqualsWithTransform ) { /* ************************************************************************* */ TEST( RangeFactor, Error2D ) { // Create a factor - Key poseKey(1); - Key pointKey(2); - double measurement(10.0); RangeFactor2D factor(poseKey, pointKey, measurement, model); // Set the linearization point @@ -150,9 +159,6 @@ TEST( RangeFactor, Error2D ) { /* ************************************************************************* */ TEST( RangeFactor, Error2DWithTransform ) { // Create a factor - Key poseKey(1); - Key pointKey(2); - double measurement(10.0); Pose2 body_P_sensor(0.25, -0.10, -M_PI_2); RangeFactorWithTransform2D factor(poseKey, pointKey, measurement, model, body_P_sensor); @@ -176,9 +182,6 @@ TEST( RangeFactor, Error2DWithTransform ) { /* ************************************************************************* */ TEST( RangeFactor, Error3D ) { // Create a factor - Key poseKey(1); - Key pointKey(2); - double measurement(10.0); RangeFactor3D factor(poseKey, pointKey, measurement, model); // Set the linearization point @@ -198,9 +201,6 @@ TEST( RangeFactor, Error3D ) { /* ************************************************************************* */ TEST( RangeFactor, Error3DWithTransform ) { // Create a factor - Key poseKey(1); - Key pointKey(2); - double measurement(10.0); Pose3 body_P_sensor(Rot3::RzRyRx(-M_PI_2, 0.0, -M_PI_2), Point3(0.25, -0.10, 1.0)); RangeFactorWithTransform3D factor(poseKey, pointKey, measurement, model, @@ -225,9 +225,6 @@ TEST( RangeFactor, Error3DWithTransform ) { /* ************************************************************************* */ TEST( RangeFactor, Jacobian2D ) { // Create a factor - Key poseKey(1); - Key pointKey(2); - double measurement(10.0); RangeFactor2D factor(poseKey, pointKey, measurement, model); // Set the linearization point @@ -253,9 +250,6 @@ TEST( RangeFactor, Jacobian2D ) { /* ************************************************************************* */ TEST( RangeFactor, Jacobian2DWithTransform ) { // Create a factor - Key poseKey(1); - Key pointKey(2); - double measurement(10.0); Pose2 body_P_sensor(0.25, -0.10, -M_PI_2); RangeFactorWithTransform2D factor(poseKey, pointKey, measurement, model, body_P_sensor); @@ -285,9 +279,6 @@ TEST( RangeFactor, Jacobian2DWithTransform ) { /* ************************************************************************* */ TEST( RangeFactor, Jacobian3D ) { // Create a factor - Key poseKey(1); - Key pointKey(2); - double measurement(10.0); RangeFactor3D factor(poseKey, pointKey, measurement, model); // Set the linearization point @@ -313,9 +304,6 @@ TEST( RangeFactor, Jacobian3D ) { /* ************************************************************************* */ TEST( RangeFactor, Jacobian3DWithTransform ) { // Create a factor - Key poseKey(1); - Key pointKey(2); - double measurement(10.0); Pose3 body_P_sensor(Rot3::RzRyRx(-M_PI_2, 0.0, -M_PI_2), Point3(0.25, -0.10, 1.0)); RangeFactorWithTransform3D factor(poseKey, pointKey, measurement, model, @@ -343,6 +331,64 @@ TEST( RangeFactor, Jacobian3DWithTransform ) { CHECK(assert_equal(H2Expected, H2Actual, 1e-9)); } +/* ************************************************************************* */ +// Do a test with Point3 +TEST(RangeFactor, Point3) { + // Create a factor + RangeFactor factor(poseKey, pointKey, measurement, model); + + // Set the linearization point + Point3 pose(1.0, 2.0, 00); + Point3 point(-4.0, 11.0, 0); + + // The expected error is ||(5.0, 9.0)|| - 10.0 = 0.295630141 meter / UnitCovariance + Vector expectedError = (Vector(1) << 0.295630141).finished(); + + // Verify we get the expected error + CHECK(assert_equal(expectedError, factor.evaluateError(pose, point), 1e-9)); +} + +/* ************************************************************************* */ +// Do tests with SimpleCamera +TEST( RangeFactor, Camera) { + RangeFactor factor1(poseKey, pointKey, measurement, model); + RangeFactor factor2(poseKey, pointKey, measurement, model); + RangeFactor factor3(poseKey, pointKey, measurement, model); +} + +/* ************************************************************************* */ +// Do a test with non GTSAM types + +namespace gtsam{ +template <> +struct Range { + typedef double result_type; + double operator()(const Vector3& v1, const Vector3& v2, + OptionalJacobian<1, 3> H1, OptionalJacobian<1, 3> H2) { + return (v2 - v1).norm(); + // derivatives not implemented + } +}; +} + +TEST(RangeFactor, NonGTSAM) { + // Create a factor + Key poseKey(1); + Key pointKey(2); + double measurement(10.0); + RangeFactor factor(poseKey, pointKey, measurement, model); + + // Set the linearization point + Vector3 pose(1.0, 2.0, 00); + Vector3 point(-4.0, 11.0, 0); + + // The expected error is ||(5.0, 9.0)|| - 10.0 = 0.295630141 meter / UnitCovariance + Vector expectedError = (Vector(1) << 0.295630141).finished(); + + // Verify we get the expected error + CHECK(assert_equal(expectedError, factor.evaluateError(pose, point), 1e-9)); +} + /* ************************************************************************* */ int main() { TestResult tr; diff --git a/gtsam/sfm/CMakeLists.txt b/gtsam/sfm/CMakeLists.txt new file mode 100644 index 000000000..fde997840 --- /dev/null +++ b/gtsam/sfm/CMakeLists.txt @@ -0,0 +1,6 @@ +# Install headers +file(GLOB sfm_headers "*.h") +install(FILES ${sfm_headers} DESTINATION include/gtsam/sfm) + +# Build tests +add_subdirectory(tests) diff --git a/gtsam/sfm/tests/CMakeLists.txt b/gtsam/sfm/tests/CMakeLists.txt new file mode 100644 index 000000000..22245dffe --- /dev/null +++ b/gtsam/sfm/tests/CMakeLists.txt @@ -0,0 +1 @@ +gtsamAddTestsGlob(sfm "test*.cpp" "" "gtsam") diff --git a/gtsam/slam/BearingFactor.h b/gtsam/slam/BearingFactor.h index c78b5a3bf..1a1fac922 100644 --- a/gtsam/slam/BearingFactor.h +++ b/gtsam/slam/BearingFactor.h @@ -9,94 +9,13 @@ * -------------------------------------------------------------------------- */ -/** - * @file BearingFactor.H - * @author Frank Dellaert - **/ - #pragma once -#include -#include -#include +#ifdef _MSC_VER +#pragma message("BearingFactor is now an ExpressionFactor in SAM directory") +#else +#warning "BearingFactor is now an ExpressionFactor in SAM directory" +#endif -namespace gtsam { - /** - * Binary factor for a bearing measurement - * @addtogroup SLAM - */ - template - class BearingFactor: public NoiseModelFactor2 { - private: - - typedef POSE Pose; - typedef ROTATION Rot; - typedef POINT Point; - - typedef BearingFactor This; - typedef NoiseModelFactor2 Base; - - Rot measured_; /** measurement */ - - /** concept check by type */ - GTSAM_CONCEPT_TESTABLE_TYPE(Rot) - GTSAM_CONCEPT_POSE_TYPE(Pose) - - public: - - /** default constructor for serialization/testing only */ - BearingFactor() {} - - /** primary constructor */ - BearingFactor(Key poseKey, Key pointKey, const Rot& measured, - const SharedNoiseModel& model) : - Base(model, poseKey, pointKey), measured_(measured) { - } - - virtual ~BearingFactor() {} - - /// @return a deep copy of this factor - virtual gtsam::NonlinearFactor::shared_ptr clone() const { - return boost::static_pointer_cast( - gtsam::NonlinearFactor::shared_ptr(new This(*this))); } - - /** h(x)-z -> between(z,h(x)) for Rot2 manifold */ - Vector evaluateError(const Pose& pose, const Point& point, - boost::optional H1, boost::optional H2) const { - Rot hx = pose.bearing(point, H1, H2); - return Rot::Logmap(measured_.between(hx)); - } - - /** return the measured */ - const Rot& measured() const { - return measured_; - } - - /** equals */ - virtual bool equals(const NonlinearFactor& expected, double tol=1e-9) const { - const This *e = dynamic_cast (&expected); - return e != NULL && Base::equals(*e, tol) && this->measured_.equals(e->measured_, tol); - } - - /** print contents */ - void print(const std::string& s="", const KeyFormatter& keyFormatter = DefaultKeyFormatter) const { - std::cout << s << "BearingFactor, bearing = "; - measured_.print(); - Base::print("", keyFormatter); - } - - private: - - /** Serialization function */ - friend class boost::serialization::access; - template - void serialize(ARCHIVE & ar, const unsigned int /*version*/) { - ar & boost::serialization::make_nvp("NoiseModelFactor2", - boost::serialization::base_object(*this)); - ar & BOOST_SERIALIZATION_NVP(measured_); - } - - }; // BearingFactor - -} // namespace gtsam +#include diff --git a/gtsam/slam/BearingRangeFactor.h b/gtsam/slam/BearingRangeFactor.h index 1b51224d2..901860015 100644 --- a/gtsam/slam/BearingRangeFactor.h +++ b/gtsam/slam/BearingRangeFactor.h @@ -1,6 +1,6 @@ /* ---------------------------------------------------------------------------- - * GTSAM Copyright 2010, Georgia Tech Research Corporation, + * 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) @@ -9,116 +9,13 @@ * -------------------------------------------------------------------------- */ -/** - * @file BearingRangeFactor.h - * @date Apr 1, 2010 - * @author Kai Ni - * @brief a single factor contains both the bearing and the range to prevent handle to pair bearing and range factors - */ - #pragma once -#include -#include -#include +#ifdef _MSC_VER +#pragma message( \ + "BearingRangeFactor is now an ExpressionFactor in SAM directory") +#else +#warning "BearingRangeFactor is now an ExpressionFactor in SAM directory" +#endif -namespace gtsam { - - /** - * Binary factor for a bearing measurement - * @addtogroup SLAM - */ - template - class BearingRangeFactor: public NoiseModelFactor2 - { - public: - typedef BearingRangeFactor This; - typedef NoiseModelFactor2 Base; - typedef boost::shared_ptr shared_ptr; - - private: - typedef POSE Pose; - typedef ROTATION Rot; - typedef POINT Point; - - // the measurement - Rot measuredBearing_; - double measuredRange_; - - /** concept check by type */ - GTSAM_CONCEPT_TESTABLE_TYPE(Rot) - GTSAM_CONCEPT_RANGE_MEASUREMENT_TYPE(Pose, Point) - GTSAM_CONCEPT_POSE_TYPE(Pose) - - public: - - BearingRangeFactor() {} /* Default constructor */ - BearingRangeFactor(Key poseKey, Key pointKey, const Rot& measuredBearing, const double measuredRange, - const SharedNoiseModel& model) : - Base(model, poseKey, pointKey), measuredBearing_(measuredBearing), measuredRange_(measuredRange) { - } - - virtual ~BearingRangeFactor() {} - - /// @return a deep copy of this factor - virtual gtsam::NonlinearFactor::shared_ptr clone() const { - return boost::static_pointer_cast( - gtsam::NonlinearFactor::shared_ptr(new This(*this))); } - - /** Print */ - virtual void print(const std::string& s = "", const KeyFormatter& keyFormatter = DefaultKeyFormatter) const { - std::cout << s << "BearingRangeFactor(" - << keyFormatter(this->key1()) << "," - << keyFormatter(this->key2()) << ")\n"; - measuredBearing_.print("measured bearing: "); - std::cout << "measured range: " << measuredRange_ << std::endl; - this->noiseModel_->print("noise model:\n"); - } - - /** equals */ - virtual bool equals(const NonlinearFactor& expected, double tol=1e-9) const { - const This *e = dynamic_cast (&expected); - return e != NULL && Base::equals(*e, tol) && - fabs(this->measuredRange_ - e->measuredRange_) < tol && - this->measuredBearing_.equals(e->measuredBearing_, tol); - } - - /** h(x)-z -> between(z,h(x)) for Rot manifold */ - Vector evaluateError(const Pose& pose, const Point& point, - boost::optional H1, boost::optional H2) const { - Matrix H11, H21, H12, H22; - boost::optional H11_ = H1 ? boost::optional(H11) : boost::optional(); - boost::optional H21_ = H1 ? boost::optional(H21) : boost::optional(); - boost::optional H12_ = H2 ? boost::optional(H12) : boost::optional(); - boost::optional H22_ = H2 ? boost::optional(H22) : boost::optional(); - - Rot y1 = pose.bearing(point, H11_, H12_); - Vector e1 = Rot::Logmap(measuredBearing_.between(y1)); - - double y2 = pose.range(point, H21_, H22_); - Vector e2 = (Vector(1) << y2 - measuredRange_).finished(); - - if (H1) *H1 = gtsam::stack(2, &H11, &H21); - if (H2) *H2 = gtsam::stack(2, &H12, &H22); - return concatVectors(2, &e1, &e2); - } - - /** return the measured */ - const std::pair measured() const { - return std::make_pair(measuredBearing_, measuredRange_); - } - - private: - - /** Serialization function */ - friend class boost::serialization::access; - template - void serialize(ARCHIVE & ar, const unsigned int /*version*/) { - ar & boost::serialization::make_nvp("NoiseModelFactor2", - boost::serialization::base_object(*this)); - ar & BOOST_SERIALIZATION_NVP(measuredBearing_); - ar & BOOST_SERIALIZATION_NVP(measuredRange_); - } - }; // BearingRangeFactor - -} // namespace gtsam +#include diff --git a/gtsam/slam/EssentialMatrixFactor.h b/gtsam/slam/EssentialMatrixFactor.h index 9d4a8e6e5..da22225e5 100644 --- a/gtsam/slam/EssentialMatrixFactor.h +++ b/gtsam/slam/EssentialMatrixFactor.h @@ -173,7 +173,7 @@ public: Point3 _1T2 = E.direction().point3(); Point3 d1T2 = d * _1T2; Point3 dP2 = E.rotation().unrotate(dP1_ - d1T2); // 2R1*((x,y,1)-d*1T2) - pn = SimpleCamera::project_to_camera(dP2); + pn = PinholeBase::Project(dP2); } else { @@ -186,7 +186,7 @@ public: Point3 dP2 = E.rotation().unrotate(dP1_ - d1T2, DdP2_rot, DP2_point); Matrix23 Dpn_dP2; - pn = SimpleCamera::project_to_camera(dP2, Dpn_dP2); + pn = PinholeBase::Project(dP2, Dpn_dP2); if (DE) { Matrix DdP2_E(3, 5); diff --git a/gtsam/slam/GeneralSFMFactor.h b/gtsam/slam/GeneralSFMFactor.h index 2516b2bcc..d2b042fed 100644 --- a/gtsam/slam/GeneralSFMFactor.h +++ b/gtsam/slam/GeneralSFMFactor.h @@ -25,13 +25,16 @@ #include #include #include +#include #include #include #include #include +#include #include #include #include +#include #include #include @@ -48,209 +51,249 @@ class access; namespace gtsam { - /** - * Non-linear factor for a constraint derived from a 2D measurement. - * The calibration is unknown here compared to GenericProjectionFactor - * @addtogroup SLAM - */ - template - class GeneralSFMFactor: public NoiseModelFactor2 { +/** + * Non-linear factor for a constraint derived from a 2D measurement. + * The calibration is unknown here compared to GenericProjectionFactor + * @addtogroup SLAM + */ +template +class GeneralSFMFactor: public NoiseModelFactor2 { - GTSAM_CONCEPT_MANIFOLD_TYPE(CAMERA) - GTSAM_CONCEPT_MANIFOLD_TYPE(LANDMARK) + GTSAM_CONCEPT_MANIFOLD_TYPE(CAMERA); + GTSAM_CONCEPT_MANIFOLD_TYPE(LANDMARK); - static const int DimC = FixedDimension::value; - static const int DimL = FixedDimension::value; + static const int DimC = FixedDimension::value; + static const int DimL = FixedDimension::value; + typedef Eigen::Matrix JacobianC; + typedef Eigen::Matrix JacobianL; - protected: +protected: - Point2 measured_; ///< the 2D measurement + Point2 measured_; ///< the 2D measurement - public: +public: - typedef GeneralSFMFactor This; ///< typedef for this object - typedef NoiseModelFactor2 Base; ///< typedef for the base class + typedef GeneralSFMFactor This;///< typedef for this object + typedef NoiseModelFactor2 Base;///< typedef for the base class - // shorthand for a smart pointer to a factor - typedef boost::shared_ptr shared_ptr; - - /** - * Constructor - * @param measured is the 2 dimensional location of point in image (the measurement) - * @param model is the standard deviation of the measurements - * @param cameraKey is the index of the camera - * @param landmarkKey is the index of the landmark - */ - GeneralSFMFactor(const Point2& measured, const SharedNoiseModel& model, Key cameraKey, Key landmarkKey) : - Base(model, cameraKey, landmarkKey), measured_(measured) {} - - GeneralSFMFactor():measured_(0.0,0.0) {} ///< default constructor - GeneralSFMFactor(const Point2 & p):measured_(p) {} ///< constructor that takes a Point2 - GeneralSFMFactor(double x, double y):measured_(x,y) {} ///< constructor that takes doubles x,y to make a Point2 - - virtual ~GeneralSFMFactor() {} ///< destructor - - /// @return a deep copy of this factor - virtual gtsam::NonlinearFactor::shared_ptr clone() const { - return boost::static_pointer_cast( - gtsam::NonlinearFactor::shared_ptr(new This(*this))); } - - /** - * print - * @param s optional string naming the factor - * @param keyFormatter optional formatter for printing out Symbols - */ - void print(const std::string& s = "SFMFactor", const KeyFormatter& keyFormatter = DefaultKeyFormatter) const { - Base::print(s, keyFormatter); - measured_.print(s + ".z"); - } - - /** - * equals - */ - bool equals(const NonlinearFactor &p, double tol = 1e-9) const { - const This* e = dynamic_cast(&p); - return e && Base::equals(p, tol) && this->measured_.equals(e->measured_, tol) ; - } - - /** h(x)-z */ - Vector evaluateError(const CAMERA& camera, const LANDMARK& point, - boost::optional H1=boost::none, boost::optional H2=boost::none) const { - - try { - Point2 reprojError(camera.project2(point,H1,H2) - measured_); - return reprojError.vector(); - } - catch( CheiralityException& e) { - if (H1) *H1 = zeros(2, DimC); - if (H2) *H2 = zeros(2, DimL); - std::cout << e.what() << ": Landmark "<< DefaultKeyFormatter(this->key2()) - << " behind Camera " << DefaultKeyFormatter(this->key1()) << std::endl; - return zero(2); - } - } - - /** return the measured */ - inline const Point2 measured() const { - return measured_; - } - - private: - /** Serialization function */ - friend class boost::serialization::access; - template - void serialize(Archive & ar, const unsigned int /*version*/) { - ar & boost::serialization::make_nvp("NoiseModelFactor2", - boost::serialization::base_object(*this)); - ar & BOOST_SERIALIZATION_NVP(measured_); - } - }; - - template - struct traits > : Testable< - GeneralSFMFactor > { - }; + // shorthand for a smart pointer to a factor + typedef boost::shared_ptr shared_ptr; /** - * Non-linear factor for a constraint derived from a 2D measurement. - * Compared to GeneralSFMFactor, it is a ternary-factor because the calibration is isolated from camera.. + * Constructor + * @param measured is the 2 dimensional location of point in image (the measurement) + * @param model is the standard deviation of the measurements + * @param cameraKey is the index of the camera + * @param landmarkKey is the index of the landmark */ - template - class GeneralSFMFactor2: public NoiseModelFactor3 { + GeneralSFMFactor(const Point2& measured, const SharedNoiseModel& model, Key cameraKey, Key landmarkKey) : + Base(model, cameraKey, landmarkKey), measured_(measured) {} - GTSAM_CONCEPT_MANIFOLD_TYPE(CALIBRATION) - static const int DimK = FixedDimension::value; + GeneralSFMFactor():measured_(0.0,0.0) {} ///< default constructor + GeneralSFMFactor(const Point2 & p):measured_(p) {} ///< constructor that takes a Point2 + GeneralSFMFactor(double x, double y):measured_(x,y) {} ///< constructor that takes doubles x,y to make a Point2 - protected: + virtual ~GeneralSFMFactor() {} ///< destructor - Point2 measured_; ///< the 2D measurement + /// @return a deep copy of this factor + virtual gtsam::NonlinearFactor::shared_ptr clone() const { + return boost::static_pointer_cast( + gtsam::NonlinearFactor::shared_ptr(new This(*this)));} - public: + /** + * print + * @param s optional string naming the factor + * @param keyFormatter optional formatter for printing out Symbols + */ + void print(const std::string& s = "SFMFactor", const KeyFormatter& keyFormatter = DefaultKeyFormatter) const { + Base::print(s, keyFormatter); + measured_.print(s + ".z"); + } - typedef GeneralSFMFactor2 This; - typedef PinholeCamera Camera; ///< typedef for camera type - typedef NoiseModelFactor3 Base; ///< typedef for the base class + /** + * equals + */ + bool equals(const NonlinearFactor &p, double tol = 1e-9) const { + const This* e = dynamic_cast(&p); + return e && Base::equals(p, tol) && this->measured_.equals(e->measured_, tol); + } - // shorthand for a smart pointer to a factor - typedef boost::shared_ptr shared_ptr; - - /** - * Constructor - * @param measured is the 2 dimensional location of point in image (the measurement) - * @param model is the standard deviation of the measurements - * @param poseKey is the index of the camera - * @param landmarkKey is the index of the landmark - * @param calibKey is the index of the calibration - */ - GeneralSFMFactor2(const Point2& measured, const SharedNoiseModel& model, Key poseKey, Key landmarkKey, Key calibKey) : - Base(model, poseKey, landmarkKey, calibKey), measured_(measured) {} - GeneralSFMFactor2():measured_(0.0,0.0) {} ///< default constructor - - virtual ~GeneralSFMFactor2() {} ///< destructor - - /// @return a deep copy of this factor - virtual gtsam::NonlinearFactor::shared_ptr clone() const { - return boost::static_pointer_cast( - gtsam::NonlinearFactor::shared_ptr(new This(*this))); } - - /** - * print - * @param s optional string naming the factor - * @param keyFormatter optional formatter useful for printing Symbols - */ - void print(const std::string& s = "SFMFactor2", const KeyFormatter& keyFormatter = DefaultKeyFormatter) const { - Base::print(s, keyFormatter); - measured_.print(s + ".z"); + /** h(x)-z */ + Vector evaluateError(const CAMERA& camera, const LANDMARK& point, + boost::optional H1=boost::none, boost::optional H2=boost::none) const { + try { + Point2 reprojError(camera.project2(point,H1,H2) - measured_); + return reprojError.vector(); } - - /** - * equals - */ - bool equals(const NonlinearFactor &p, double tol = 1e-9) const { - const This* e = dynamic_cast(&p); - return e && Base::equals(p, tol) && this->measured_.equals(e->measured_, tol) ; - } - - /** h(x)-z */ - Vector evaluateError(const Pose3& pose3, const Point3& point, const CALIBRATION &calib, - boost::optional H1=boost::none, - boost::optional H2=boost::none, - boost::optional H3=boost::none) const - { - try { - Camera camera(pose3,calib); - Point2 reprojError(camera.project(point, H1, H2, H3) - measured_); - return reprojError.vector(); - } - catch( CheiralityException& e) { - if (H1) *H1 = zeros(2, 6); - if (H2) *H2 = zeros(2, 3); - if (H3) *H3 = zeros(2, DimK); - std::cout << e.what() << ": Landmark "<< DefaultKeyFormatter(this->key2()) - << " behind Camera " << DefaultKeyFormatter(this->key1()) << std::endl; - } + catch( CheiralityException& e) { + if (H1) *H1 = JacobianC::Zero(); + if (H2) *H2 = JacobianL::Zero(); + // TODO warn if verbose output asked for return zero(2); } + } - /** return the measured */ - inline const Point2 measured() const { - return measured_; + /// Linearize using fixed-size matrices + boost::shared_ptr linearize(const Values& values) const { + // Only linearize if the factor is active + if (!this->active(values)) return boost::shared_ptr(); + + const Key key1 = this->key1(), key2 = this->key2(); + JacobianC H1; + JacobianL H2; + Vector2 b; + try { + const CAMERA& camera = values.at(key1); + const LANDMARK& point = values.at(key2); + Point2 reprojError(camera.project2(point, H1, H2) - measured()); + b = -reprojError.vector(); + } catch (CheiralityException& e) { + H1.setZero(); + H2.setZero(); + b.setZero(); + // TODO warn if verbose output asked for } - private: - /** Serialization function */ - friend class boost::serialization::access; - template - void serialize(Archive & ar, const unsigned int /*version*/) { - ar & boost::serialization::make_nvp("NoiseModelFactor3", - boost::serialization::base_object(*this)); - ar & BOOST_SERIALIZATION_NVP(measured_); + // Whiten the system if needed + const SharedNoiseModel& noiseModel = this->get_noiseModel(); + if (noiseModel && !noiseModel->isUnit()) { + // TODO: implement WhitenSystem for fixed size matrices and include + // above + H1 = noiseModel->Whiten(H1); + H2 = noiseModel->Whiten(H2); + b = noiseModel->Whiten(b); } - }; - template - struct traits > : Testable< - GeneralSFMFactor2 > { - }; + // Create new (unit) noiseModel, preserving constraints if applicable + SharedDiagonal model; + if (noiseModel && noiseModel->isConstrained()) { + model = boost::static_pointer_cast(noiseModel)->unit(); + } + + return boost::make_shared >(key1, H1, key2, H2, b, model); + } + + /** return the measured */ + inline const Point2 measured() const { + return measured_; + } + +private: + /** Serialization function */ + friend class boost::serialization::access; + template + void serialize(Archive & ar, const unsigned int /*version*/) { + ar & boost::serialization::make_nvp("NoiseModelFactor2", + boost::serialization::base_object(*this)); + ar & BOOST_SERIALIZATION_NVP(measured_); + } +}; + +template +struct traits > : Testable< + GeneralSFMFactor > { +}; + +/** + * Non-linear factor for a constraint derived from a 2D measurement. + * Compared to GeneralSFMFactor, it is a ternary-factor because the calibration is isolated from camera.. + */ +template +class GeneralSFMFactor2: public NoiseModelFactor3 { + + GTSAM_CONCEPT_MANIFOLD_TYPE(CALIBRATION); + static const int DimK = FixedDimension::value; + +protected: + + Point2 measured_; ///< the 2D measurement + +public: + + typedef GeneralSFMFactor2 This; + typedef PinholeCamera Camera;///< typedef for camera type + typedef NoiseModelFactor3 Base;///< typedef for the base class + + // shorthand for a smart pointer to a factor + typedef boost::shared_ptr shared_ptr; + + /** + * Constructor + * @param measured is the 2 dimensional location of point in image (the measurement) + * @param model is the standard deviation of the measurements + * @param poseKey is the index of the camera + * @param landmarkKey is the index of the landmark + * @param calibKey is the index of the calibration + */ + GeneralSFMFactor2(const Point2& measured, const SharedNoiseModel& model, Key poseKey, Key landmarkKey, Key calibKey) : + Base(model, poseKey, landmarkKey, calibKey), measured_(measured) {} + GeneralSFMFactor2():measured_(0.0,0.0) {} ///< default constructor + + virtual ~GeneralSFMFactor2() {} ///< destructor + + /// @return a deep copy of this factor + virtual gtsam::NonlinearFactor::shared_ptr clone() const { + return boost::static_pointer_cast( + gtsam::NonlinearFactor::shared_ptr(new This(*this)));} + + /** + * print + * @param s optional string naming the factor + * @param keyFormatter optional formatter useful for printing Symbols + */ + void print(const std::string& s = "SFMFactor2", const KeyFormatter& keyFormatter = DefaultKeyFormatter) const { + Base::print(s, keyFormatter); + measured_.print(s + ".z"); + } + + /** + * equals + */ + bool equals(const NonlinearFactor &p, double tol = 1e-9) const { + const This* e = dynamic_cast(&p); + return e && Base::equals(p, tol) && this->measured_.equals(e->measured_, tol); + } + + /** h(x)-z */ + Vector evaluateError(const Pose3& pose3, const Point3& point, const CALIBRATION &calib, + boost::optional H1=boost::none, + boost::optional H2=boost::none, + boost::optional H3=boost::none) const + { + try { + Camera camera(pose3,calib); + Point2 reprojError(camera.project(point, H1, H2, H3) - measured_); + return reprojError.vector(); + } + catch( CheiralityException& e) { + if (H1) *H1 = zeros(2, 6); + if (H2) *H2 = zeros(2, 3); + if (H3) *H3 = zeros(2, DimK); + std::cout << e.what() << ": Landmark "<< DefaultKeyFormatter(this->key2()) + << " behind Camera " << DefaultKeyFormatter(this->key1()) << std::endl; + } + return zero(2); + } + + /** return the measured */ + inline const Point2 measured() const { + return measured_; + } + +private: + /** Serialization function */ + friend class boost::serialization::access; + template + void serialize(Archive & ar, const unsigned int /*version*/) { + ar & boost::serialization::make_nvp("NoiseModelFactor3", + boost::serialization::base_object(*this)); + ar & BOOST_SERIALIZATION_NVP(measured_); + } +}; + +template +struct traits > : Testable< + GeneralSFMFactor2 > { +}; } //namespace diff --git a/gtsam/slam/JacobianFactorQ.h b/gtsam/slam/JacobianFactorQ.h index ed6213058..16560a43e 100644 --- a/gtsam/slam/JacobianFactorQ.h +++ b/gtsam/slam/JacobianFactorQ.h @@ -17,7 +17,7 @@ #pragma once -#include "RegularJacobianFactor.h" +#include namespace gtsam { /** @@ -28,7 +28,7 @@ class JacobianFactorQ: public RegularJacobianFactor { typedef RegularJacobianFactor Base; typedef Eigen::Matrix MatrixZD; - typedef std::pair KeyMatrixZD; + typedef std::pair KeyMatrix; public: @@ -42,7 +42,6 @@ public: Base() { Matrix zeroMatrix = Matrix::Zero(0, D); Vector zeroVector = Vector::Zero(0); - typedef std::pair KeyMatrix; std::vector QF; QF.reserve(keys.size()); BOOST_FOREACH(const Key& key, keys) @@ -51,24 +50,25 @@ public: } /// Constructor - JacobianFactorQ(const std::vector& Fblocks, const Matrix& E, - const Matrix3& P, const Vector& b, const SharedDiagonal& model = - SharedDiagonal()) : + JacobianFactorQ(const FastVector& keys, + const std::vector& FBlocks, const Matrix& E, const Matrix3& P, + const Vector& b, const SharedDiagonal& model = SharedDiagonal()) : Base() { size_t j = 0, m2 = E.rows(), m = m2 / ZDim; // Calculate projector Q Matrix Q = eye(m2) - E * P * E.transpose(); // Calculate pre-computed Jacobian matrices // TODO: can we do better ? - typedef std::pair KeyMatrix; std::vector QF; QF.reserve(m); // Below, we compute each mZDim*D block A_j = Q_j * F_j = (mZDim*ZDim) * (Zdim*D) - BOOST_FOREACH(const KeyMatrixZD& it, Fblocks) + for (size_t k = 0; k < FBlocks.size(); ++k) { + Key key = keys[k]; QF.push_back( - KeyMatrix(it.first, Q.block(0, ZDim * j++, m2, ZDim) * it.second)); + KeyMatrix(key, - Q.block(0, ZDim * j++, m2, ZDim) * FBlocks[k])); + } // Which is then passed to the normal JacobianFactor constructor - JacobianFactor::fillTerms(QF, Q * b, model); + JacobianFactor::fillTerms(QF, - Q * b, model); } }; // end class JacobianFactorQ diff --git a/gtsam/slam/JacobianFactorQR.h b/gtsam/slam/JacobianFactorQR.h index 4c1b0ff14..77102c24b 100644 --- a/gtsam/slam/JacobianFactorQR.h +++ b/gtsam/slam/JacobianFactorQR.h @@ -6,8 +6,8 @@ */ #pragma once -#include #include +#include #include namespace gtsam { @@ -22,25 +22,24 @@ class JacobianFactorQR: public RegularJacobianFactor { typedef RegularJacobianFactor Base; typedef Eigen::Matrix MatrixZD; - typedef std::pair KeyMatrixZD; public: /** * Constructor */ - JacobianFactorQR(const std::vector& Fblocks, const Matrix& E, - const Matrix3& P, const Vector& b, // + JacobianFactorQR(const FastVector& keys, + const std::vector& FBlocks, const Matrix& E, const Matrix3& P, + const Vector& b, // const SharedDiagonal& model = SharedDiagonal()) : Base() { // Create a number of Jacobian factors in a factor graph GaussianFactorGraph gfg; Symbol pointKey('p', 0); - size_t i = 0; - BOOST_FOREACH(const KeyMatrixZD& it, Fblocks) { - gfg.add(pointKey, E.block(ZDim * i, 0), it.first, it.second, - b.segment(ZDim * i), model); - i += 1; + for (size_t k = 0; k < FBlocks.size(); ++k) { + Key key = keys[k]; + gfg.add(pointKey, E.block(ZDim * k, 0), key, FBlocks[k], + b.segment < ZDim > (ZDim * k), model); } //gfg.print("gfg"); diff --git a/gtsam/slam/JacobianFactorSVD.h b/gtsam/slam/JacobianFactorSVD.h index b4389d681..86636c38f 100644 --- a/gtsam/slam/JacobianFactorSVD.h +++ b/gtsam/slam/JacobianFactorSVD.h @@ -5,18 +5,17 @@ */ #pragma once -#include "gtsam/slam/RegularJacobianFactor.h" +#include namespace gtsam { /** - * JacobianFactor for Schur complement that uses Q noise model + * JacobianFactor for Schur complement */ template class JacobianFactorSVD: public RegularJacobianFactor { typedef RegularJacobianFactor Base; typedef Eigen::Matrix MatrixZD; // e.g 2 x 6 with Z=Point2 - typedef std::pair KeyMatrixZD; typedef std::pair KeyMatrix; public: @@ -38,13 +37,21 @@ public: JacobianFactor::fillTerms(QF, zeroVector, model); } - /// Constructor - JacobianFactorSVD(const std::vector& Fblocks, - const Matrix& Enull, const Vector& b, // + /** + * @brief Constructor + * Takes the CameraSet derivatives (as ZDim*D blocks of block-diagonal F) + * and a reduced point derivative, Enull + * and creates a reduced-rank Jacobian factor on the CameraSet + * + * @Fblocks: + */ + JacobianFactorSVD(const FastVector& keys, + const std::vector& Fblocks, const Matrix& Enull, + const Vector& b, // const SharedDiagonal& model = SharedDiagonal()) : Base() { size_t numKeys = Enull.rows() / ZDim; - size_t j = 0, m2 = ZDim * numKeys - 3; + size_t m2 = ZDim * numKeys - 3; // PLAIN NULL SPACE TRICK // Matrix Q = Enull * Enull.transpose(); // BOOST_FOREACH(const KeyMatrixZD& it, Fblocks) @@ -52,10 +59,12 @@ public: // JacobianFactor factor(QF, Q * b); std::vector QF; QF.reserve(numKeys); - BOOST_FOREACH(const KeyMatrixZD& it, Fblocks) + for (size_t k = 0; k < Fblocks.size(); ++k) { + Key key = keys[k]; QF.push_back( - KeyMatrix(it.first, - (Enull.transpose()).block(0, ZDim * j++, m2, ZDim) * it.second)); + KeyMatrix(key, + (Enull.transpose()).block(0, ZDim * k, m2, ZDim) * Fblocks[k])); + } JacobianFactor::fillTerms(QF, Enull.transpose() * b, model); } }; diff --git a/gtsam/slam/PriorFactor.h b/gtsam/slam/PriorFactor.h index a738d4cf0..8305fce12 100644 --- a/gtsam/slam/PriorFactor.h +++ b/gtsam/slam/PriorFactor.h @@ -85,11 +85,11 @@ namespace gtsam { /** implement functions needed to derive from Factor */ /** vector of errors */ - Vector evaluateError(const T& p, boost::optional H = boost::none) const { - if (H) (*H) = eye(traits::GetDimension(p)); - // manifold equivalent of h(x)-z -> log(z,h(x)) + Vector evaluateError(const T& x, boost::optional H = boost::none) const { + if (H) (*H) = eye(traits::GetDimension(x)); + // manifold equivalent of z-x -> Local(x,z) // TODO(ASL) Add Jacobians. - return traits::Local(prior_,p); + return -traits::Local(x, prior_); } const VALUE & prior() const { return prior_; } diff --git a/gtsam/slam/RangeFactor.h b/gtsam/slam/RangeFactor.h index d45dd5ce0..d50674d75 100644 --- a/gtsam/slam/RangeFactor.h +++ b/gtsam/slam/RangeFactor.h @@ -9,189 +9,14 @@ * -------------------------------------------------------------------------- */ -/** - * @file RangeFactor.H - * @author Frank Dellaert - **/ - #pragma once -#include -#include -#include +#ifdef _MSC_VER +#pragma message("RangeFactor is now an ExpressionFactor in SAM directory") +#else +#warning "RangeFactor is now an ExpressionFactor in SAM directory" +#endif -namespace gtsam { -/** - * Binary factor for a range measurement - * @addtogroup SLAM - */ -template -class RangeFactor: public NoiseModelFactor2 { -private: +#include - double measured_; /** measurement */ - - typedef RangeFactor This; - typedef NoiseModelFactor2 Base; - - // Concept requirements for this factor - GTSAM_CONCEPT_RANGE_MEASUREMENT_TYPE(T1, T2) - -public: - - RangeFactor() { - } /* Default constructor */ - - RangeFactor(Key key1, Key key2, double measured, - const SharedNoiseModel& model) : - Base(model, key1, key2), measured_(measured) { - } - - virtual ~RangeFactor() { - } - - /// @return a deep copy of this factor - virtual gtsam::NonlinearFactor::shared_ptr clone() const { - return boost::static_pointer_cast( - gtsam::NonlinearFactor::shared_ptr(new This(*this))); - } - - /** h(x)-z */ - Vector evaluateError(const T1& t1, const T2& t2, boost::optional H1 = - boost::none, boost::optional H2 = boost::none) const { - double hx; - hx = t1.range(t2, H1, H2); - return (Vector(1) << hx - measured_).finished(); - } - - /** return the measured */ - double measured() const { - return measured_; - } - - /** equals specialized to this factor */ - virtual bool equals(const NonlinearFactor& expected, - double tol = 1e-9) const { - const This *e = dynamic_cast(&expected); - return e != NULL && Base::equals(*e, tol) - && fabs(this->measured_ - e->measured_) < tol; - } - - /** print contents */ - void print(const std::string& s = "", const KeyFormatter& keyFormatter = - DefaultKeyFormatter) const { - std::cout << s << "RangeFactor, range = " << measured_ << std::endl; - Base::print("", keyFormatter); - } - -private: - - /** Serialization function */ - friend class boost::serialization::access; - template - void serialize(ARCHIVE & ar, const unsigned int /*version*/) { - ar - & boost::serialization::make_nvp("NoiseModelFactor2", - boost::serialization::base_object(*this)); - ar & BOOST_SERIALIZATION_NVP(measured_); - } -}; // \ RangeFactor - -/// traits -template -struct traits > : public Testable > {}; - -/** - * Binary factor for a range measurement, with a transform applied - * @addtogroup SLAM - */ -template -class RangeFactorWithTransform: public NoiseModelFactor2 { -private: - - double measured_; /** measurement */ - POSE body_P_sensor_; ///< The pose of the sensor in the body frame - - typedef RangeFactorWithTransform This; - typedef NoiseModelFactor2 Base; - - // Concept requirements for this factor - GTSAM_CONCEPT_RANGE_MEASUREMENT_TYPE(POSE, T2) - -public: - - RangeFactorWithTransform() { - } /* Default constructor */ - - RangeFactorWithTransform(Key key1, Key key2, double measured, - const SharedNoiseModel& model, const POSE& body_P_sensor) : - Base(model, key1, key2), measured_(measured), body_P_sensor_( - body_P_sensor) { - } - - virtual ~RangeFactorWithTransform() { - } - - /// @return a deep copy of this factor - virtual gtsam::NonlinearFactor::shared_ptr clone() const { - return boost::static_pointer_cast( - gtsam::NonlinearFactor::shared_ptr(new This(*this))); - } - - /** h(x)-z */ - Vector evaluateError(const POSE& t1, const T2& t2, - boost::optional H1 = boost::none, boost::optional H2 = - boost::none) const { - double hx; - if (H1) { - Matrix H0; - hx = t1.compose(body_P_sensor_, H0).range(t2, H1, H2); - *H1 = *H1 * H0; - } else { - hx = t1.compose(body_P_sensor_).range(t2, H1, H2); - } - return (Vector(1) << hx - measured_).finished(); - } - - /** return the measured */ - double measured() const { - return measured_; - } - - /** equals specialized to this factor */ - virtual bool equals(const NonlinearFactor& expected, - double tol = 1e-9) const { - const This *e = dynamic_cast(&expected); - return e != NULL && Base::equals(*e, tol) - && fabs(this->measured_ - e->measured_) < tol - && body_P_sensor_.equals(e->body_P_sensor_); - } - - /** print contents */ - void print(const std::string& s = "", const KeyFormatter& keyFormatter = - DefaultKeyFormatter) const { - std::cout << s << "RangeFactor, range = " << measured_ << std::endl; - this->body_P_sensor_.print(" sensor pose in body frame: "); - Base::print("", keyFormatter); - } - -private: - - /** Serialization function */ - friend class boost::serialization::access; - template - void serialize(ARCHIVE & ar, const unsigned int /*version*/) { - ar - & boost::serialization::make_nvp("NoiseModelFactor2", - boost::serialization::base_object(*this)); - ar & BOOST_SERIALIZATION_NVP(measured_); - ar & BOOST_SERIALIZATION_NVP(body_P_sensor_); - } -}; // \ RangeFactorWithTransform - -/// traits -template -struct traits > : public Testable > {}; - -} // \ namespace gtsam diff --git a/gtsam/slam/RegularImplicitSchurFactor.h b/gtsam/slam/RegularImplicitSchurFactor.h index b1490d465..c713eff72 100644 --- a/gtsam/slam/RegularImplicitSchurFactor.h +++ b/gtsam/slam/RegularImplicitSchurFactor.h @@ -7,6 +7,7 @@ #pragma once +#include #include #include #include @@ -17,7 +18,7 @@ namespace gtsam { /** * RegularImplicitSchurFactor */ -template // +template class RegularImplicitSchurFactor: public GaussianFactor { public: @@ -26,14 +27,20 @@ public: protected: - typedef Eigen::Matrix Matrix2D; ///< type of an F block - typedef Eigen::Matrix MatrixDD; ///< camera hessian - typedef std::pair KeyMatrix2D; ///< named F block + // This factor is closely related to a CameraSet + typedef CameraSet Set; - std::vector Fblocks_; ///< All 2*D F blocks (one for each camera) - Matrix3 PointCovariance_; ///< the 3*3 matrix P = inv(E'E) (2*2 if degenerate) - Matrix E_; ///< The 2m*3 E Jacobian with respect to the point - Vector b_; ///< 2m-dimensional RHS vector + typedef typename CAMERA::Measurement Z; + static const int D = traits::dimension; ///< Camera dimension + static const int ZDim = traits::dimension; ///< Measurement dimension + + typedef Eigen::Matrix MatrixZD; ///< type of an F block + typedef Eigen::Matrix MatrixDD; ///< camera hessian + + const std::vector FBlocks_; ///< All ZDim*D F blocks (one for each camera) + const Matrix PointCovariance_; ///< the 3*3 matrix P = inv(E'E) (2*2 if degenerate) + const Matrix E_; ///< The 2m*3 E Jacobian with respect to the point + const Vector b_; ///< 2m-dimensional RHS vector public: @@ -41,54 +48,40 @@ public: RegularImplicitSchurFactor() { } - /// Construct from blcoks of F, E, inv(E'*E), and RHS vector b - RegularImplicitSchurFactor(const std::vector& Fblocks, const Matrix& E, - const Matrix3& P, const Vector& b) : - Fblocks_(Fblocks), PointCovariance_(P), E_(E), b_(b) { - initKeys(); - } - - /// initialize keys from Fblocks - void initKeys() { - keys_.reserve(Fblocks_.size()); - BOOST_FOREACH(const KeyMatrix2D& it, Fblocks_) - keys_.push_back(it.first); + /// Construct from blocks of F, E, inv(E'*E), and RHS vector b + RegularImplicitSchurFactor(const FastVector& keys, + const std::vector& FBlocks, const Matrix& E, const Matrix& P, + const Vector& b) : + GaussianFactor(keys), FBlocks_(FBlocks), PointCovariance_(P), E_(E), b_(b) { } /// Destructor virtual ~RegularImplicitSchurFactor() { } - // Write access, only use for construction! - - inline std::vector& Fblocks() { - return Fblocks_; + std::vector& FBlocks() const { + return FBlocks_; } - inline Matrix3& PointCovariance() { - return PointCovariance_; - } - - inline Matrix& E() { + const Matrix& E() const { return E_; } - inline Vector& b() { + const Vector& b() const { return b_; } - /// Get matrix P - inline const Matrix3& getPointCovariance() const { + const Matrix& getPointCovariance() const { return PointCovariance_; } /// print - void print(const std::string& s = "", - const KeyFormatter& keyFormatter = DefaultKeyFormatter) const { + void print(const std::string& s = "", const KeyFormatter& keyFormatter = + DefaultKeyFormatter) const { std::cout << " RegularImplicitSchurFactor " << std::endl; Factor::print(s); for (size_t pos = 0; pos < size(); ++pos) { - std::cout << "Fblock:\n" << Fblocks_[pos].second << std::endl; + std::cout << "Fblock:\n" << FBlocks_[pos] << std::endl; } std::cout << "PointCovariance:\n" << PointCovariance_ << std::endl; std::cout << "E:\n" << E_ << std::endl; @@ -100,10 +93,11 @@ public: const This* f = dynamic_cast(&lf); if (!f) return false; - for (size_t pos = 0; pos < size(); ++pos) { - if (keys_[pos] != f->keys_[pos]) return false; - if (Fblocks_[pos].first != f->Fblocks_[pos].first) return false; - if (!equal_with_abs_tol(Fblocks_[pos].second,f->Fblocks_[pos].second,tol)) return false; + for (size_t k = 0; k < FBlocks_.size(); ++k) { + if (keys_[k] != f->keys_[k]) + return false; + if (!equal_with_abs_tol(FBlocks_[k], f->FBlocks_[k], tol)) + return false; } return equal_with_abs_tol(PointCovariance_, f->PointCovariance_, tol) && equal_with_abs_tol(E_, f->E_, tol) @@ -115,24 +109,37 @@ public: return D; } + virtual void updateHessian(const FastVector& keys, + SymmetricBlockMatrix* info) const { + throw std::runtime_error( + "RegularImplicitSchurFactor::updateHessian non implemented"); + } virtual Matrix augmentedJacobian() const { throw std::runtime_error( "RegularImplicitSchurFactor::augmentedJacobian non implemented"); return Matrix(); } virtual std::pair jacobian() const { - throw std::runtime_error("RegularImplicitSchurFactor::jacobian non implemented"); + throw std::runtime_error( + "RegularImplicitSchurFactor::jacobian non implemented"); return std::make_pair(Matrix(), Vector()); } + + /// *Compute* full augmented information matrix virtual Matrix augmentedInformation() const { - throw std::runtime_error( - "RegularImplicitSchurFactor::augmentedInformation non implemented"); - return Matrix(); + + // Do the Schur complement + SymmetricBlockMatrix augmentedHessian = // + Set::SchurComplement(FBlocks_, E_, b_); + return augmentedHessian.matrix(); } + + /// *Compute* full information matrix virtual Matrix information() const { - throw std::runtime_error( - "RegularImplicitSchurFactor::information non implemented"); - return Matrix(); + Matrix augmented = augmentedInformation(); + int m = this->keys_.size(); + size_t M = D * m; + return augmented.block(0, 0, M, M); } /// Return the diagonal of the Hessian for this factor @@ -140,17 +147,17 @@ public: // diag(Hessian) = diag(F' * (I - E * PointCov * E') * F); VectorValues d; - for (size_t pos = 0; pos < size(); ++pos) { // for each camera - Key j = keys_[pos]; + for (size_t k = 0; k < size(); ++k) { // for each camera + Key j = keys_[k]; // Calculate Fj'*Ej for the current camera (observing a single point) - // D x 3 = (D x 2) * (2 x 3) - const Matrix2D& Fj = Fblocks_[pos].second; - Eigen::Matrix FtE = Fj.transpose() - * E_.block<2, 3>(2 * pos, 0); + // D x 3 = (D x ZDim) * (ZDim x 3) + const MatrixZD& Fj = FBlocks_[k]; + Eigen::Matrix FtE = Fj.transpose() + * E_.block(ZDim * k, 0); Eigen::Matrix dj; - for (size_t k = 0; k < D; ++k) { // for each diagonal element of the camera hessian + for (int k = 0; k < D; ++k) { // for each diagonal element of the camera hessian // Vector column_k_Fj = Fj.col(k); dj(k) = Fj.col(k).squaredNorm(); // dot(column_k_Fj, column_k_Fj); // Vector column_k_FtE = FtE.row(k); @@ -176,13 +183,13 @@ public: Key j = keys_[pos]; // Calculate Fj'*Ej for the current camera (observing a single point) - // D x 3 = (D x 2) * (2 x 3) - const Matrix2D& Fj = Fblocks_[pos].second; + // D x 3 = (D x ZDim) * (ZDim x 3) + const MatrixZD& Fj = FBlocks_[pos]; Eigen::Matrix FtE = Fj.transpose() - * E_.block<2, 3>(2 * pos, 0); + * E_.block(ZDim * pos, 0); DVector dj; - for (size_t k = 0; k < D; ++k) { // for each diagonal element of the camera hessian + for (int k = 0; k < D; ++k) { // for each diagonal element of the camera hessian dj(k) = Fj.col(k).squaredNorm(); // (1 x 1) = (1 x 3) * (3 * 3) * (3 x 1) dj(k) -= FtE.row(k) * PointCovariance_ * FtE.row(k).transpose(); @@ -197,38 +204,41 @@ public: // F'*(I - E*P*E')*F for (size_t pos = 0; pos < size(); ++pos) { Key j = keys_[pos]; - // F'*F - F'*E*P*E'*F (9*2)*(2*9) - (9*2)*(2*3)*(3*3)*(3*2)*(2*9) - const Matrix2D& Fj = Fblocks_[pos].second; + // F'*F - F'*E*P*E'*F e.g. (9*2)*(2*9) - (9*2)*(2*3)*(3*3)*(3*2)*(2*9) + const MatrixZD& Fj = FBlocks_[pos]; // Eigen::Matrix FtE = Fj.transpose() - // * E_.block<2, 3>(2 * pos, 0); + // * E_.block(ZDim * pos, 0); // blocks[j] = Fj.transpose() * Fj // - FtE * PointCovariance_ * FtE.transpose(); - const Matrix23& Ej = E_.block<2, 3>(2 * pos, 0); - blocks[j] = Fj.transpose() * (Fj - Ej * PointCovariance_ * Ej.transpose() * Fj); + const Matrix23& Ej = E_.block(ZDim * pos, 0); + blocks[j] = Fj.transpose() + * (Fj - Ej * PointCovariance_ * Ej.transpose() * Fj); // F'*(I - E*P*E')*F, TODO: this should work, but it does not :-( - // static const Eigen::Matrix I2 = eye(2); + // static const Eigen::Matrix I2 = eye(ZDim); // Matrix2 Q = // - // I2 - E_.block<2, 3>(2 * pos, 0) * PointCovariance_ * E_.block<2, 3>(2 * pos, 0).transpose(); + // I2 - E_.block(ZDim * pos, 0) * PointCovariance_ * E_.block(ZDim * pos, 0).transpose(); // blocks[j] = Fj.transpose() * Q * Fj; } return blocks; } virtual GaussianFactor::shared_ptr clone() const { - return boost::make_shared >(Fblocks_, - PointCovariance_, E_, b_); - throw std::runtime_error("RegularImplicitSchurFactor::clone non implemented"); + return boost::make_shared >(keys_, + FBlocks_, PointCovariance_, E_, b_); + throw std::runtime_error( + "RegularImplicitSchurFactor::clone non implemented"); } virtual bool empty() const { return false; } virtual GaussianFactor::shared_ptr negate() const { - return boost::make_shared >(Fblocks_, - PointCovariance_, E_, b_); - throw std::runtime_error("RegularImplicitSchurFactor::negate non implemented"); + return boost::make_shared >(keys_, + FBlocks_, PointCovariance_, E_, b_); + throw std::runtime_error( + "RegularImplicitSchurFactor::negate non implemented"); } // Raw Vector version of y += F'*alpha*(I - E*P*E')*F*x, for testing @@ -246,22 +256,24 @@ public: typedef std::vector Error2s; /** - * @brief Calculate corrected error Q*(e-2*b) = (I - E*P*E')*(e-2*b) + * @brief Calculate corrected error Q*(e-ZDim*b) = (I - E*P*E')*(e-ZDim*b) */ void projectError2(const Error2s& e1, Error2s& e2) const { - // d1 = E.transpose() * (e1-2*b) = (3*2m)*2m + // d1 = E.transpose() * (e1-ZDim*b) = (3*2m)*2m Vector3 d1; d1.setZero(); for (size_t k = 0; k < size(); k++) - d1 += E_.block < 2, 3 > (2 * k, 0).transpose() * (e1[k] - 2 * b_.segment < 2 > (k * 2)); + d1 += E_.block(ZDim * k, 0).transpose() + * (e1[k] - ZDim * b_.segment(k * ZDim)); // d2 = E.transpose() * e1 = (3*2m)*2m Vector3 d2 = PointCovariance_ * d1; // e3 = alpha*(e1 - E*d2) = 1*[2m-(2m*3)*3] for (size_t k = 0; k < size(); k++) - e2[k] = e1[k] - 2 * b_.segment < 2 > (k * 2) - E_.block < 2, 3 > (2 * k, 0) * d2; + e2[k] = e1[k] - ZDim * b_.segment(k * ZDim) + - E_.block(ZDim * k, 0) * d2; } /* @@ -281,7 +293,7 @@ public: // e1 = F * x - b = (2m*dm)*dm for (size_t k = 0; k < size(); ++k) - e1[k] = Fblocks_[k].second * x.at(keys_[k]); + e1[k] = FBlocks_[k] * x.at(keys_[k]); projectError2(e1, e2); double result = 0; @@ -303,7 +315,7 @@ public: // e1 = F * x - b = (2m*dm)*dm for (size_t k = 0; k < size(); ++k) - e1[k] = Fblocks_[k].second * x.at(keys_[k]) - b_.segment < 2 > (k * 2); + e1[k] = FBlocks_[k] * x.at(keys_[k]) - b_.segment(k * ZDim); projectError(e1, e2); double result = 0; @@ -316,21 +328,21 @@ public: /** * @brief Calculate corrected error Q*e = (I - E*P*E')*e */ - void projectError(const Error2s& e1, Error2s& e2) const { + void projectError(const Error2s& e1, Error2s& e2) const { - // d1 = E.transpose() * e1 = (3*2m)*2m - Vector3 d1; - d1.setZero(); - for (size_t k = 0; k < size(); k++) - d1 += E_.block < 2, 3 > (2 * k, 0).transpose() * e1[k]; + // d1 = E.transpose() * e1 = (3*2m)*2m + Vector3 d1; + d1.setZero(); + for (size_t k = 0; k < size(); k++) + d1 += E_.block(ZDim * k, 0).transpose() * e1[k]; - // d2 = E.transpose() * e1 = (3*2m)*2m - Vector3 d2 = PointCovariance_ * d1; + // d2 = E.transpose() * e1 = (3*2m)*2m + Vector3 d2 = PointCovariance_ * d1; - // e3 = alpha*(e1 - E*d2) = 1*[2m-(2m*3)*3] - for (size_t k = 0; k < size(); k++) - e2[k] = e1[k] - E_.block < 2, 3 > (2 * k, 0) * d2; - } + // e3 = alpha*(e1 - E*d2) = 1*[2m-(2m*3)*3] + for (size_t k = 0; k < size(); k++) + e2[k] = e1[k] - E_.block(ZDim * k, 0) * d2; + } /// Scratch space for multiplyHessianAdd mutable Error2s e1, e2; @@ -351,19 +363,17 @@ public: e2.resize(size()); // e1 = F * x = (2m*dm)*dm - size_t k = 0; - BOOST_FOREACH(const KeyMatrix2D& it, Fblocks_) { - Key key = it.first; - e1[k++] = it.second * ConstDMap(x + D * key); + for (size_t k = 0; k < size(); ++k) { + Key key = keys_[k]; + e1[k] = FBlocks_[k] * ConstDMap(x + D * key); } projectError(e1, e2); // y += F.transpose()*e2 = (2d*2m)*2m - k = 0; - BOOST_FOREACH(const KeyMatrix2D& it, Fblocks_) { - Key key = it.first; - DMap(y + D * key) += it.second.transpose() * alpha * e2[k++]; + for (size_t k = 0; k < size(); ++k) { + Key key = keys_[k]; + DMap(y + D * key) += FBlocks_[k].transpose() * alpha * e2[k]; } } @@ -384,7 +394,7 @@ public: // e1 = F * x = (2m*dm)*dm for (size_t k = 0; k < size(); ++k) - e1[k] = Fblocks_[k].second * x.at(keys_[k]); + e1[k] = FBlocks_[k] * x.at(keys_[k]); projectError(e1, e2); @@ -396,8 +406,8 @@ public: Vector& yi = it.first->second; // Create the value as a zero vector if it does not exist. if (it.second) - yi = Vector::Zero(Fblocks_[k].second.cols()); - yi += Fblocks_[k].second.transpose() * alpha * e2[k]; + yi = Vector::Zero(FBlocks_[k].cols()); + yi += FBlocks_[k].transpose() * alpha * e2[k]; } } @@ -407,9 +417,9 @@ public: void multiplyHessianDummy(double alpha, const VectorValues& x, VectorValues& y) const { - BOOST_FOREACH(const KeyMatrix2D& Fi, Fblocks_) { + for (size_t k = 0; k < size(); ++k) { static const Vector empty; - Key key = Fi.first; + Key key = keys_[k]; std::pair it = y.tryInsert(key, empty); Vector& yi = it.first->second; yi = x.at(key); @@ -424,14 +434,14 @@ public: e1.resize(size()); e2.resize(size()); for (size_t k = 0; k < size(); k++) - e1[k] = b_.segment < 2 > (2 * k); + e1[k] = b_.segment(ZDim * k); projectError(e1, e2); // g = F.transpose()*e2 VectorValues g; for (size_t k = 0; k < size(); ++k) { Key key = keys_[k]; - g.insert(key, -Fblocks_[k].second.transpose() * e2[k]); + g.insert(key, -FBlocks_[k].transpose() * e2[k]); } // return it @@ -451,27 +461,33 @@ public: e1.resize(size()); e2.resize(size()); for (size_t k = 0; k < size(); k++) - e1[k] = b_.segment < 2 > (2 * k); + e1[k] = b_.segment(ZDim * k); projectError(e1, e2); for (size_t k = 0; k < size(); ++k) { // for each camera in the factor Key j = keys_[k]; - DMap(d + D * j) += -Fblocks_[k].second.transpose() * e2[k]; + DMap(d + D * j) += -FBlocks_[k].transpose() * e2[k]; } } /// Gradient wrt a key at any values Vector gradient(Key key, const VectorValues& x) const { - throw std::runtime_error("gradient for RegularImplicitSchurFactor is not implemented yet"); + throw std::runtime_error( + "gradient for RegularImplicitSchurFactor is not implemented yet"); } - }; // end class RegularImplicitSchurFactor +template +const int RegularImplicitSchurFactor::D; + +template +const int RegularImplicitSchurFactor::ZDim; + // traits -template struct traits > : public Testable< - RegularImplicitSchurFactor > { +template struct traits > : public Testable< + RegularImplicitSchurFactor > { }; } diff --git a/gtsam/slam/SmartFactorBase.h b/gtsam/slam/SmartFactorBase.h index cdbe71718..01a8fcf8d 100644 --- a/gtsam/slam/SmartFactorBase.h +++ b/gtsam/slam/SmartFactorBase.h @@ -15,6 +15,7 @@ * @author Luca Carlone * @author Zsolt Kira * @author Frank Dellaert + * @author Chris Beall */ #pragma once @@ -22,9 +23,9 @@ #include #include #include -#include #include +#include #include #include @@ -41,13 +42,23 @@ namespace gtsam { * The methods take a Cameras argument, which should behave like PinholeCamera, and * the value of a point, which is kept in the base class. */ -template +template class SmartFactorBase: public NonlinearFactor { -protected: - +private: + typedef NonlinearFactor Base; + typedef SmartFactorBase This; typedef typename CAMERA::Measurement Z; +protected: + /** + * As of Feb 22, 2015, the noise model is the same for all measurements and + * is isotropic. This allows for moving most calculations of Schur complement + * etc to be moved to CameraSet very easily, and also agrees pragmatically + * with what is normally done. + */ + SharedIsotropic noiseModel_; + /** * 2D measurement and noise model for each of the m views * We keep a copy of measurements for I/O and computing the error. @@ -55,45 +66,54 @@ protected: */ std::vector measured_; - std::vector noise_; ///< noise model used - - boost::optional body_P_sensor_; ///< The pose of the sensor in the body frame (one for all cameras) + /// @name Pose of the camera in the body frame + const boost::optional body_P_sensor_; ///< Pose of the camera in the body frame + /// @} + static const int Dim = traits::dimension; ///< Camera dimension static const int ZDim = traits::dimension; ///< Measurement dimension - /// Definitions for blocks of F - typedef Eigen::Matrix Matrix2D; // F - typedef Eigen::Matrix MatrixD2; // F' - typedef std::pair KeyMatrix2D; // Fblocks - typedef Eigen::Matrix MatrixDD; // camera hessian block + // Definitions for block matrices used internally + typedef Eigen::Matrix MatrixD2; // F' + typedef Eigen::Matrix MatrixDD; // camera hessian block typedef Eigen::Matrix Matrix23; - typedef Eigen::Matrix VectorD; + typedef Eigen::Matrix VectorD; typedef Eigen::Matrix Matrix2; - /// shorthand for base class type - typedef NonlinearFactor Base; - - /// shorthand for this class - typedef SmartFactorBase This; - public: + // Definitions for blocks of F, externally visible + typedef Eigen::Matrix MatrixZD; // F + EIGEN_MAKE_ALIGNED_OPERATOR_NEW /// shorthand for a smart pointer to a factor typedef boost::shared_ptr shared_ptr; + /// We use the new CameraSte data structure to refer to a set of cameras typedef CameraSet Cameras; - /** - * Constructor - * @param body_P_sensor is the transform from sensor to body frame (default identity) - */ - SmartFactorBase(boost::optional body_P_sensor = boost::none) : - body_P_sensor_(body_P_sensor) { + /// Default Constructor, for serialization + SmartFactorBase() {} + + /// Constructor + SmartFactorBase(const SharedNoiseModel& sharedNoiseModel, + boost::optional body_P_sensor = boost::none) : + body_P_sensor_(body_P_sensor){ + + if (!sharedNoiseModel) + throw std::runtime_error("SmartFactorBase: sharedNoiseModel is required"); + + SharedIsotropic sharedIsotropic = boost::dynamic_pointer_cast< + noiseModel::Isotropic>(sharedNoiseModel); + + if (!sharedIsotropic) + throw std::runtime_error("SmartFactorBase: needs isotropic"); + + noiseModel_ = sharedIsotropic; } - /** Virtual destructor */ + /// Virtual destructor, subclasses from NonlinearFactor virtual ~SmartFactorBase() { } @@ -101,36 +121,20 @@ public: * Add a new measurement and pose key * @param measured_i is the 2m dimensional projection of a single landmark * @param poseKey is the index corresponding to the camera observing the landmark - * @param noise_i is the measurement noise + * @param sharedNoiseModel is the measurement noise */ - void add(const Z& measured_i, const Key& poseKey_i, - const SharedNoiseModel& noise_i) { + void add(const Z& measured_i, const Key& cameraKey_i) { this->measured_.push_back(measured_i); - this->keys_.push_back(poseKey_i); - this->noise_.push_back(noise_i); + this->keys_.push_back(cameraKey_i); } /** - * Add a bunch of measurements, together with the camera keys and noises + * Add a bunch of measurements, together with the camera keys */ - void add(std::vector& measurements, std::vector& poseKeys, - std::vector& noises) { + void add(std::vector& measurements, std::vector& cameraKeys) { for (size_t i = 0; i < measurements.size(); i++) { this->measured_.push_back(measurements.at(i)); - this->keys_.push_back(poseKeys.at(i)); - this->noise_.push_back(noises.at(i)); - } - } - - /** - * Add a bunch of measurements and uses the same noise model for all of them - */ - void add(std::vector& measurements, std::vector& poseKeys, - const SharedNoiseModel& noise) { - for (size_t i = 0; i < measurements.size(); i++) { - this->measured_.push_back(measurements.at(i)); - this->keys_.push_back(poseKeys.at(i)); - this->noise_.push_back(noise); + this->keys_.push_back(cameraKeys.at(i)); } } @@ -139,11 +143,10 @@ public: * The noise is assumed to be the same for all measurements */ template - void add(const SFM_TRACK& trackToAdd, const SharedNoiseModel& noise) { + void add(const SFM_TRACK& trackToAdd) { for (size_t k = 0; k < trackToAdd.number_measurements(); k++) { this->measured_.push_back(trackToAdd.measurements[k].second); this->keys_.push_back(trackToAdd.measurements[k].first); - this->noise_.push_back(noise); } } @@ -157,9 +160,12 @@ public: return measured_; } - /** return the noise models */ - const std::vector& noise() const { - return noise_; + /// Collect all cameras: important that in key order + virtual Cameras cameras(const Values& values) const { + Cameras cameras; + BOOST_FOREACH(const Key& k, this->keys_) + cameras.push_back(values.at(k)); + return cameras; } /** @@ -172,10 +178,10 @@ public: std::cout << s << "SmartFactorBase, z = \n"; for (size_t k = 0; k < measured_.size(); ++k) { std::cout << "measurement, p = " << measured_[k] << "\t"; - noise_[k]->print("noise model = "); + noiseModel_->print("noise model = "); } - if (this->body_P_sensor_) - this->body_P_sensor_->print(" sensor pose in body frame: "); + if(body_P_sensor_) + body_P_sensor_->print("body_P_sensor_:\n"); Base::print("", keyFormatter); } @@ -189,519 +195,105 @@ public: areMeasurementsEqual = false; break; } - return e && Base::equals(p, tol) && areMeasurementsEqual - && ((!body_P_sensor_ && !e->body_P_sensor_) - || (body_P_sensor_ && e->body_P_sensor_ - && body_P_sensor_->equals(*e->body_P_sensor_))); + return e && Base::equals(p, tol) && areMeasurementsEqual; } - /// Calculate vector of re-projection errors, before applying noise model - Vector reprojectionError(const Cameras& cameras, const Point3& point) const { - - // Project into CameraSet - std::vector predicted; - try { - predicted = cameras.project(point); - } catch (CheiralityException&) { - std::cout << "reprojectionError: Cheirality exception " << std::endl; - exit(EXIT_FAILURE); // TODO: throw exception + /// Compute reprojection errors [h(x)-z] = [cameras.project(p)-z] and derivatives + template + Vector unwhitenedError(const Cameras& cameras, const POINT& point, + boost::optional Fs = boost::none, // + boost::optional E = boost::none) const { + Vector ue = cameras.reprojectionError(point, measured_, Fs, E); + if(body_P_sensor_){ + for(size_t i=0; i < Fs->size(); i++){ + Pose3 w_Pose_body = (cameras[i].pose()).compose(body_P_sensor_->inverse()); + Matrix J(6, 6); + Pose3 world_P_body = w_Pose_body.compose(*body_P_sensor_, J); + Fs->at(i) = Fs->at(i) * J; + } } - - // Calculate vector of errors - size_t nrCameras = cameras.size(); - Vector b(ZDim * nrCameras); - for (size_t i = 0, row = 0; i < nrCameras; i++, row += ZDim) { - Z e = predicted[i] - measured_.at(i); - b.segment(row) = e.vector(); - } - - return b; - } - - /// Calculate vector of re-projection errors, noise model applied - Vector whitenedError(const Cameras& cameras, const Point3& point) const { - Vector b = reprojectionError(cameras, point); - size_t nrCameras = cameras.size(); - for (size_t i = 0, row = 0; i < nrCameras; i++, row += ZDim) - b.segment(row) = noise_.at(i)->whiten(b.segment(row)); - return b; + return ue; } /** - * Calculate the error of the factor. + * Calculate vector of re-projection errors [h(x)-z] = [cameras.project(p) - z] + * Noise model applied + */ + template + Vector whitenedError(const Cameras& cameras, const POINT& point) const { + Vector e = cameras.reprojectionError(point, measured_); + if (noiseModel_) + noiseModel_->whitenInPlace(e); + return e; + } + + /** Calculate the error of the factor. * This is the log-likelihood, e.g. \f$ 0.5(h(x)-z)^2/\sigma^2 \f$ in case of Gaussian. * In this class, we take the raw prediction error \f$ h(x)-z \f$, ask the noise model * to transform it to \f$ (h(x)-z)^2/\sigma^2 \f$, and then multiply by 0.5. - * This is different from reprojectionError(cameras,point) as each point is whitened + * Will be used in "error(Values)" function required by NonlinearFactor base class */ + template double totalReprojectionError(const Cameras& cameras, - const Point3& point) const { - Vector b = reprojectionError(cameras, point); - double overallError = 0; - size_t nrCameras = cameras.size(); - for (size_t i = 0; i < nrCameras; i++) - overallError += noise_.at(i)->distance(b.segment(i * ZDim)); - return 0.5 * overallError; - } - - /** - * Compute whitenedError, returning only the derivative E, i.e., - * the stacked ZDim*3 derivatives of project with respect to the point. - * Assumes non-degenerate ! TODO explain this - */ - Vector whitenedError(const Cameras& cameras, const Point3& point, - Matrix& E) const { - - // Project into CameraSet, calculating derivatives - std::vector predicted; - try { - using boost::none; - predicted = cameras.project(point, none, E, none); - } catch (CheiralityException&) { - std::cout << "whitenedError(E): Cheirality exception " << std::endl; - exit(EXIT_FAILURE); // TODO: throw exception - } - - // if needed, whiten - size_t m = keys_.size(); - Vector b(ZDim * m); - for (size_t i = 0, row = 0; i < m; i++, row += ZDim) { - - // Calculate error - const Z& zi = measured_.at(i); - Vector bi = (zi - predicted[i]).vector(); - - // if needed, whiten - SharedNoiseModel model = noise_.at(i); - if (model) { - // TODO: re-factor noiseModel to take any block/fixed vector/matrix - Vector dummy; - Matrix Ei = E.block(row, 0); - model->WhitenSystem(Ei, dummy); - E.block(row, 0) = Ei; - } - b.segment(row) = bi; - } - return b; - } - - /** - * Compute F, E, and optionally H, where F and E are the stacked derivatives - * with respect to the cameras, point, and calibration, respectively. - * The value of cameras/point are passed as parameters. - * Returns error vector b - * TODO: the treatment of body_P_sensor_ is weird: the transformation - * is applied in the caller, but the derivatives are computed here. - */ - Vector whitenedError(const Cameras& cameras, const Point3& point, Matrix& F, - Matrix& E, boost::optional G = boost::none) const { - - // Project into CameraSet, calculating derivatives - std::vector predicted; - try { - predicted = cameras.project(point, F, E, G); - } catch (CheiralityException&) { - std::cout << "whitenedError(E,F): Cheirality exception " << std::endl; - exit(EXIT_FAILURE); // TODO: throw exception - } - - // Calculate error and whiten derivatives if needed - size_t m = keys_.size(); - Vector b(ZDim * m); - for (size_t i = 0, row = 0; i < m; i++, row += ZDim) { - - // Calculate error - const Z& zi = measured_.at(i); - Vector bi = (zi - predicted[i]).vector(); - - // if we have a sensor offset, correct camera derivatives - if (body_P_sensor_) { - // TODO: no simpler way ?? - const Pose3& pose_i = cameras[i].pose(); - Pose3 w_Pose_body = pose_i.compose(body_P_sensor_->inverse()); - Matrix66 J; - Pose3 world_P_body = w_Pose_body.compose(*body_P_sensor_, J); - F.block(row, 0) *= J; - } - - // if needed, whiten - SharedNoiseModel model = noise_.at(i); - if (model) { - // TODO, refactor noiseModel so we can take blocks - Matrix Fi = F.block(row, 0); - Matrix Ei = E.block(row, 0); - if (!G) - model->WhitenSystem(Fi, Ei, bi); - else { - Matrix Gi = G->block(row, 0); - model->WhitenSystem(Fi, Ei, Gi, bi); - G->block(row, 0) = Gi; - } - F.block(row, 0) = Fi; - E.block(row, 0) = Ei; - } - b.segment(row) = bi; - } - return b; + const POINT& point) const { + Vector e = whitenedError(cameras, point); + return 0.5 * e.dot(e); } /// Computes Point Covariance P from E - static Matrix3 PointCov(Matrix& E) { + static Matrix PointCov(Matrix& E) { return (E.transpose() * E).inverse(); } - /// Computes Point Covariance P, with lambda parameter - static Matrix3 PointCov(Matrix& E, double lambda, - bool diagonalDamping = false) { - - Matrix3 EtE = E.transpose() * E; - - if (diagonalDamping) { // diagonal of the hessian - EtE(0, 0) += lambda * EtE(0, 0); - EtE(1, 1) += lambda * EtE(1, 1); - EtE(2, 2) += lambda * EtE(2, 2); - } else { - EtE(0, 0) += lambda; - EtE(1, 1) += lambda; - EtE(2, 2) += lambda; - } - - return (EtE).inverse(); - } - - /// Assumes non-degenerate ! - void computeEP(Matrix& E, Matrix& P, const Cameras& cameras, - const Point3& point) const { - whitenedError(cameras, point, E); - P = PointCov(E); - } - /** * Compute F, E, and b (called below in both vanilla and SVD versions), where * F is a vector of derivatives wrpt the cameras, and E the stacked derivatives * with respect to the point. The value of cameras/point are passed as parameters. + * TODO: Kill this obsolete method */ - double computeJacobians(std::vector& Fblocks, Matrix& E, - Vector& b, const Cameras& cameras, const Point3& point) const { - + template + void computeJacobians(std::vector& Fblocks, Matrix& E, Vector& b, + const Cameras& cameras, const POINT& point) const { // Project into Camera set and calculate derivatives - // TODO: if D==6 we optimize only camera pose. That is fairly hacky! - Matrix F, G; - using boost::none; - boost::optional optionalG(G); - b = whitenedError(cameras, point, F, E, D == 6 ? none : optionalG); - - // Now calculate f and divide up the F derivatives into Fblocks - double f = 0.0; - size_t m = keys_.size(); - for (size_t i = 0, row = 0; i < m; i++, row += ZDim) { - - // Accumulate normalized error - f += b.segment(row).squaredNorm(); - - // Get piece of F and possibly G - Matrix2D Fi; - if (D == 6) - Fi << F.block(row, 0); - else - Fi << F.block(row, 0), G.block(row, 0); - - // Push it onto Fblocks - Fblocks.push_back(KeyMatrix2D(keys_[i], Fi)); - } - return f; - } - - /// Create BIG block-diagonal matrix F from Fblocks - static void FillDiagonalF(const std::vector& Fblocks, Matrix& F) { - size_t m = Fblocks.size(); - F.resize(ZDim * m, D * m); - F.setZero(); - for (size_t i = 0; i < m; ++i) - F.block(This::ZDim * i, D * i) = Fblocks.at(i).second; - } - - /** - * Compute F, E, and b, where F and E are the stacked derivatives - * with respect to the point. The value of cameras/point are passed as parameters. - */ - double computeJacobians(Matrix& F, Matrix& E, Vector& b, - const Cameras& cameras, const Point3& point) const { - std::vector Fblocks; - double f = computeJacobians(Fblocks, E, b, cameras, point); - FillDiagonalF(Fblocks, F); - return f; + // As in expressionFactor, RHS vector b = - (h(x_bar) - z) = z-h(x_bar) + // Indeed, nonlinear error |h(x_bar+dx)-z| ~ |h(x_bar) + A*dx - z| + // = |A*dx - (z-h(x_bar))| + b = -unwhitenedError(cameras, point, Fblocks, E); } /// SVD version - double computeJacobiansSVD(std::vector& Fblocks, Matrix& Enull, - Vector& b, const Cameras& cameras, const Point3& point) const { + template + void computeJacobiansSVD(std::vector& Fblocks, Matrix& Enull, + Vector& b, const Cameras& cameras, const POINT& point) const { Matrix E; - double f = computeJacobians(Fblocks, E, b, cameras, point); + computeJacobians(Fblocks, E, b, cameras, point); + + static const int N = FixedDimension::value; // 2 (Unit3) or 3 (Point3) // Do SVD on A Eigen::JacobiSVD svd(E, Eigen::ComputeFullU); Vector s = svd.singularValues(); size_t m = this->keys_.size(); - // Enull = zeros(ZDim * m, ZDim * m - 3); - Enull = svd.matrixU().block(0, 3, ZDim * m, ZDim * m - 3); // last ZDim*m-3 columns - - return f; + Enull = svd.matrixU().block(0, N, ZDim * m, ZDim * m - N); // last ZDim*m-N columns } - /// Matrix version of SVD - // TODO, there should not be a Matrix version, really - double computeJacobiansSVD(Matrix& F, Matrix& Enull, Vector& b, - const Cameras& cameras, const Point3& point) const { - std::vector Fblocks; - double f = computeJacobiansSVD(Fblocks, Enull, b, cameras, point); - FillDiagonalF(Fblocks, F); - return f; - } - - /** - * Linearize returns a Hessianfactor that is an approximation of error(p) - */ - boost::shared_ptr > createHessianFactor( + /// Linearize to a Hessianfactor + boost::shared_ptr > createHessianFactor( const Cameras& cameras, const Point3& point, const double lambda = 0.0, bool diagonalDamping = false) const { - int numKeys = this->keys_.size(); - - std::vector Fblocks; + std::vector Fblocks; Matrix E; Vector b; - double f = computeJacobians(Fblocks, E, b, cameras, point); - Matrix3 P = PointCov(E, lambda, diagonalDamping); + computeJacobians(Fblocks, E, b, cameras, point); -//#define HESSIAN_BLOCKS // slower, as internally the Hessian factor will transform the blocks into SymmetricBlockMatrix -#ifdef HESSIAN_BLOCKS - // Create structures for Hessian Factors - std::vector < Matrix > Gs(numKeys * (numKeys + 1) / 2); - std::vector < Vector > gs(numKeys); + // build augmented hessian + SymmetricBlockMatrix augmentedHessian = Cameras::SchurComplement(Fblocks, E, + b); - sparseSchurComplement(Fblocks, E, P, b, Gs, gs); - // schurComplement(Fblocks, E, P, b, Gs, gs); - - //std::vector < Matrix > Gs2(Gs.begin(), Gs.end()); - //std::vector < Vector > gs2(gs.begin(), gs.end()); - - return boost::make_shared < RegularHessianFactor > (this->keys_, Gs, gs, f); -#else // we create directly a SymmetricBlockMatrix - size_t n1 = D * numKeys + 1; - std::vector dims(numKeys + 1); // this also includes the b term - std::fill(dims.begin(), dims.end() - 1, D); - dims.back() = 1; - - SymmetricBlockMatrix augmentedHessian(dims, Matrix::Zero(n1, n1)); // for 10 cameras, size should be (10*D+1 x 10*D+1) - sparseSchurComplement(Fblocks, E, P, b, augmentedHessian); // augmentedHessian.matrix().block (i1,i2) = ... - augmentedHessian(numKeys, numKeys)(0, 0) = f; - return boost::make_shared >(this->keys_, + return boost::make_shared >(keys_, augmentedHessian); -#endif - } - - /** - * Do Schur complement, given Jacobian as F,E,P. - * Slow version - works on full matrices - */ - void schurComplement(const std::vector& Fblocks, const Matrix& E, - const Matrix3& P, const Vector& b, - /*output ->*/std::vector& Gs, std::vector& gs) const { - // Schur complement trick - // Gs = F' * F - F' * E * inv(E'*E) * E' * F - // gs = F' * (b - E * inv(E'*E) * E' * b) - // This version uses full matrices - - int numKeys = this->keys_.size(); - - /// Compute Full F ???? - Matrix F; - FillDiagonalF(Fblocks, F); - - Matrix H(D * numKeys, D * numKeys); - Vector gs_vector; - - H.noalias() = F.transpose() * (F - (E * (P * (E.transpose() * F)))); - gs_vector.noalias() = F.transpose() * (b - (E * (P * (E.transpose() * b)))); - - // Populate Gs and gs - int GsCount2 = 0; - for (DenseIndex i1 = 0; i1 < numKeys; i1++) { // for each camera - DenseIndex i1D = i1 * D; - gs.at(i1) = gs_vector.segment(i1D); - for (DenseIndex i2 = 0; i2 < numKeys; i2++) { - if (i2 >= i1) { - Gs.at(GsCount2) = H.block(i1D, i2 * D); - GsCount2++; - } - } - } - } - - /** - * Do Schur complement, given Jacobian as F,E,P, return SymmetricBlockMatrix - * Fast version - works on with sparsity - */ - void sparseSchurComplement(const std::vector& Fblocks, - const Matrix& E, const Matrix3& P /*Point Covariance*/, const Vector& b, - /*output ->*/SymmetricBlockMatrix& augmentedHessian) const { - // Schur complement trick - // Gs = F' * F - F' * E * P * E' * F - // gs = F' * (b - E * P * E' * b) - - // a single point is observed in numKeys cameras - size_t numKeys = this->keys_.size(); - - // Blockwise Schur complement - for (size_t i1 = 0; i1 < numKeys; i1++) { // for each camera - - const Matrix2D& Fi1 = Fblocks.at(i1).second; - const Matrix23 Ei1_P = E.block(ZDim * i1, 0) * P; - - // D = (Dx2) * (2) - // (augmentedHessian.matrix()).block (i1,numKeys+1) = Fi1.transpose() * b.segment < 2 > (2 * i1); // F' * b - augmentedHessian(i1, numKeys) = Fi1.transpose() - * b.segment(ZDim * i1) // F' * b - - Fi1.transpose() * (Ei1_P * (E.transpose() * b)); // D = (DxZDim) * (ZDimx3) * (3*ZDimm) * (ZDimm x 1) - - // (DxD) = (DxZDim) * ( (ZDimxD) - (ZDimx3) * (3xZDim) * (ZDimxD) ) - augmentedHessian(i1, i1) = Fi1.transpose() - * (Fi1 - Ei1_P * E.block(ZDim * i1, 0).transpose() * Fi1); - - // upper triangular part of the hessian - for (size_t i2 = i1 + 1; i2 < numKeys; i2++) { // for each camera - const Matrix2D& Fi2 = Fblocks.at(i2).second; - - // (DxD) = (Dx2) * ( (2x2) * (2xD) ) - augmentedHessian(i1, i2) = -Fi1.transpose() - * (Ei1_P * E.block(ZDim * i2, 0).transpose() * Fi2); - } - } // end of for over cameras - } - - /** - * Do Schur complement, given Jacobian as F,E,P, return Gs/gs - * Fast version - works on with sparsity - */ - void sparseSchurComplement(const std::vector& Fblocks, - const Matrix& E, const Matrix3& P /*Point Covariance*/, const Vector& b, - /*output ->*/std::vector& Gs, std::vector& gs) const { - // Schur complement trick - // Gs = F' * F - F' * E * P * E' * F - // gs = F' * (b - E * P * E' * b) - - // a single point is observed in numKeys cameras - size_t numKeys = this->keys_.size(); - - int GsIndex = 0; - // Blockwise Schur complement - for (size_t i1 = 0; i1 < numKeys; i1++) { // for each camera - // GsIndex points to the upper triangular blocks - // 0 1 2 3 4 - // X 5 6 7 8 - // X X 9 10 11 - // X X X 12 13 - // X X X X 14 - const Matrix2D& Fi1 = Fblocks.at(i1).second; - - const Matrix23 Ei1_P = E.block(ZDim * i1, 0) * P; - - { // for i1 = i2 - // D = (Dx2) * (2) - gs.at(i1) = Fi1.transpose() * b.segment(ZDim * i1) // F' * b - - Fi1.transpose() * (Ei1_P * (E.transpose() * b)); // D = (DxZDim) * (ZDimx3) * (3*ZDimm) * (ZDimm x 1) - - // (DxD) = (DxZDim) * ( (ZDimxD) - (ZDimx3) * (3xZDim) * (ZDimxD) ) - Gs.at(GsIndex) = Fi1.transpose() - * (Fi1 - Ei1_P * E.block(ZDim * i1, 0).transpose() * Fi1); - GsIndex++; - } - // upper triangular part of the hessian - for (size_t i2 = i1 + 1; i2 < numKeys; i2++) { // for each camera - const Matrix2D& Fi2 = Fblocks.at(i2).second; - - // (DxD) = (Dx2) * ( (2x2) * (2xD) ) - Gs.at(GsIndex) = -Fi1.transpose() - * (Ei1_P * E.block(ZDim * i2, 0).transpose() * Fi2); - GsIndex++; - } - } // end of for over cameras - } - - /** - * Applies Schur complement (exploiting block structure) to get a smart factor on cameras, - * and adds the contribution of the smart factor to a pre-allocated augmented Hessian. - */ - void updateSparseSchurComplement(const std::vector& Fblocks, - const Matrix& E, const Matrix3& P /*Point Covariance*/, const Vector& b, - const double f, const FastVector allKeys, - /*output ->*/SymmetricBlockMatrix& augmentedHessian) const { - // Schur complement trick - // Gs = F' * F - F' * E * P * E' * F - // gs = F' * (b - E * P * E' * b) - - MatrixDD matrixBlock; - typedef SymmetricBlockMatrix::Block Block; ///< A block from the Hessian matrix - - FastMap KeySlotMap; - for (size_t slot = 0; slot < allKeys.size(); slot++) - KeySlotMap.insert(std::make_pair(allKeys[slot], slot)); - - // a single point is observed in numKeys cameras - size_t numKeys = this->keys_.size(); // cameras observing current point - size_t aug_numKeys = (augmentedHessian.rows() - 1) / D; // all cameras in the group - - // Blockwise Schur complement - for (size_t i1 = 0; i1 < numKeys; i1++) { // for each camera in the current factor - - const Matrix2D& Fi1 = Fblocks.at(i1).second; - const Matrix23 Ei1_P = E.block(ZDim * i1, 0) * P; - - // D = (DxZDim) * (ZDim) - // allKeys are the list of all camera keys in the group, e.g, (1,3,4,5,7) - // we should map those to a slot in the local (grouped) hessian (0,1,2,3,4) - // Key cameraKey_i1 = this->keys_[i1]; - DenseIndex aug_i1 = KeySlotMap[this->keys_[i1]]; - - // information vector - store previous vector - // vectorBlock = augmentedHessian(aug_i1, aug_numKeys).knownOffDiagonal(); - // add contribution of current factor - augmentedHessian(aug_i1, aug_numKeys) = augmentedHessian(aug_i1, - aug_numKeys).knownOffDiagonal() - + Fi1.transpose() * b.segment(ZDim * i1) // F' * b - - Fi1.transpose() * (Ei1_P * (E.transpose() * b)); // D = (DxZDim) * (ZDimx3) * (3*ZDimm) * (ZDimm x 1) - - // (DxD) = (DxZDim) * ( (ZDimxD) - (ZDimx3) * (3xZDim) * (ZDimxD) ) - // main block diagonal - store previous block - matrixBlock = augmentedHessian(aug_i1, aug_i1); - // add contribution of current factor - augmentedHessian(aug_i1, aug_i1) = - matrixBlock - + (Fi1.transpose() - * (Fi1 - - Ei1_P * E.block(ZDim * i1, 0).transpose() * Fi1)); - - // upper triangular part of the hessian - for (size_t i2 = i1 + 1; i2 < numKeys; i2++) { // for each camera - const Matrix2D& Fi2 = Fblocks.at(i2).second; - - //Key cameraKey_i2 = this->keys_[i2]; - DenseIndex aug_i2 = KeySlotMap[this->keys_[i2]]; - - // (DxD) = (DxZDim) * ( (ZDimxZDim) * (ZDimxD) ) - // off diagonal block - store previous block - // matrixBlock = augmentedHessian(aug_i1, aug_i2).knownOffDiagonal(); - // add contribution of current factor - augmentedHessian(aug_i1, aug_i2) = - augmentedHessian(aug_i1, aug_i2).knownOffDiagonal() - - Fi1.transpose() - * (Ei1_P * E.block(ZDim * i2, 0).transpose() * Fi2); - } - } // end of for over cameras - - augmentedHessian(aug_numKeys, aug_numKeys)(0, 0) += f; } /** @@ -713,73 +305,100 @@ public: const double lambda, bool diagonalDamping, SymmetricBlockMatrix& augmentedHessian, const FastVector allKeys) const { - - // int numKeys = this->keys_.size(); - - std::vector Fblocks; Matrix E; Vector b; - double f = computeJacobians(Fblocks, E, b, cameras, point); - Matrix3 P = PointCov(E, lambda, diagonalDamping); - updateSparseSchurComplement(Fblocks, E, P, b, f, allKeys, augmentedHessian); // augmentedHessian.matrix().block (i1,i2) = ... + std::vector Fblocks; + computeJacobians(Fblocks, E, b, cameras, point); + Cameras::UpdateSchurComplement(Fblocks, E, b, allKeys, keys_, + augmentedHessian); } - /** - * Return Jacobians as RegularImplicitSchurFactor with raw access - */ - boost::shared_ptr > createRegularImplicitSchurFactor( - const Cameras& cameras, const Point3& point, double lambda = 0.0, - bool diagonalDamping = false) const { - typename boost::shared_ptr > f( - new RegularImplicitSchurFactor()); - computeJacobians(f->Fblocks(), f->E(), f->b(), cameras, point); - f->PointCovariance() = PointCov(f->E(), lambda, diagonalDamping); - f->initKeys(); - return f; + /// Whiten the Jacobians computed by computeJacobians using noiseModel_ + void whitenJacobians(std::vector& F, Matrix& E, Vector& b) const { + noiseModel_->WhitenSystem(E, b); + // TODO make WhitenInPlace work with any dense matrix type + for (size_t i = 0; i < F.size(); i++) + F[i] = noiseModel_->Whiten(F[i]); + } + + /// Return Jacobians as RegularImplicitSchurFactor with raw access + boost::shared_ptr > // + createRegularImplicitSchurFactor(const Cameras& cameras, const Point3& point, + double lambda = 0.0, bool diagonalDamping = false) const { + Matrix E; + Vector b; + std::vector F; + computeJacobians(F, E, b, cameras, point); + whitenJacobians(F, E, b); + Matrix P = Cameras::PointCov(E, lambda, diagonalDamping); + return boost::make_shared >(keys_, F, E, + P, b); } /** * Return Jacobians as JacobianFactorQ */ - boost::shared_ptr > createJacobianQFactor( + boost::shared_ptr > createJacobianQFactor( const Cameras& cameras, const Point3& point, double lambda = 0.0, bool diagonalDamping = false) const { - std::vector Fblocks; Matrix E; Vector b; - computeJacobians(Fblocks, E, b, cameras, point); - Matrix3 P = PointCov(E, lambda, diagonalDamping); - return boost::make_shared >(Fblocks, E, P, b); + std::vector F; + computeJacobians(F, E, b, cameras, point); + const size_t M = b.size(); + Matrix P = Cameras::PointCov(E, lambda, diagonalDamping); + SharedIsotropic n = noiseModel::Isotropic::Sigma(M, noiseModel_->sigma()); + return boost::make_shared >(keys_, F, E, P, b, n); } /** - * Return Jacobians as JacobianFactor + * Return Jacobians as JacobianFactorSVD * TODO lambda is currently ignored */ boost::shared_ptr createJacobianSVDFactor( const Cameras& cameras, const Point3& point, double lambda = 0.0) const { - size_t numKeys = this->keys_.size(); - std::vector Fblocks; + size_t m = this->keys_.size(); + std::vector F; Vector b; - Matrix Enull(ZDim * numKeys, ZDim * numKeys - 3); - computeJacobiansSVD(Fblocks, Enull, b, cameras, point); - return boost::make_shared >(Fblocks, Enull, b); + const size_t M = ZDim * m; + Matrix E0(M, M - 3); + computeJacobiansSVD(F, E0, b, cameras, point); + SharedIsotropic n = noiseModel::Isotropic::Sigma(M - 3, + noiseModel_->sigma()); + return boost::make_shared >(keys_, F, E0, b, n); + } + + /// Create BIG block-diagonal matrix F from Fblocks + static void FillDiagonalF(const std::vector& Fblocks, Matrix& F) { + size_t m = Fblocks.size(); + F.resize(ZDim * m, Dim * m); + F.setZero(); + for (size_t i = 0; i < m; ++i) + F.block(ZDim * i, Dim * i) = Fblocks.at(i); + } + + + Pose3 body_P_sensor() const{ + if(body_P_sensor_) + return *body_P_sensor_; + else + return Pose3(); // if unspecified, the transformation is the identity } private: - /// Serialization function +/// Serialization function friend class boost::serialization::access; template void serialize(ARCHIVE & ar, const unsigned int /*version*/) { ar & BOOST_SERIALIZATION_BASE_OBJECT_NVP(Base); ar & BOOST_SERIALIZATION_NVP(measured_); - ar & BOOST_SERIALIZATION_NVP(body_P_sensor_); } -} -; +}; +// end class SmartFactorBase -template -const int SmartFactorBase::ZDim; +// Definitions need to avoid link errors (above are only declarations) +template const int SmartFactorBase::Dim; +template const int SmartFactorBase::ZDim; } // \ namespace gtsam diff --git a/gtsam/slam/SmartProjectionFactor.h b/gtsam/slam/SmartProjectionFactor.h index a28482583..09fe84caa 100644 --- a/gtsam/slam/SmartProjectionFactor.h +++ b/gtsam/slam/SmartProjectionFactor.h @@ -11,7 +11,7 @@ /** * @file SmartProjectionFactor.h - * @brief Base class to create smart factors on poses or cameras + * @brief Smart factor on cameras (pose + calibration) * @author Luca Carlone * @author Zsolt Kira * @author Frank Dellaert @@ -22,7 +22,6 @@ #include #include -#include #include #include @@ -32,108 +31,144 @@ namespace gtsam { -/** - * Structure for storing some state memory, used to speed up optimization - * @addtogroup SLAM - */ -class SmartProjectionFactorState { - -protected: - -public: - - SmartProjectionFactorState() { - } - // Hessian representation (after Schur complement) - bool calculatedHessian; - Matrix H; - Vector gs_vector; - std::vector Gs; - std::vector gs; - double f; +/// Linearization mode: what factor to linearize to +enum LinearizationMode { + HESSIAN, IMPLICIT_SCHUR, JACOBIAN_Q, JACOBIAN_SVD }; -enum LinearizationMode { - HESSIAN, JACOBIAN_SVD, JACOBIAN_Q +/// How to manage degeneracy +enum DegeneracyMode { + IGNORE_DEGENERACY, ZERO_ON_DEGENERACY, HANDLE_INFINITY +}; + +/* + * Parameters for the smart projection factors + */ +struct GTSAM_EXPORT SmartProjectionParams { + + LinearizationMode linearizationMode; ///< How to linearize the factor + DegeneracyMode degeneracyMode; ///< How to linearize the factor + + /// @name Parameters governing the triangulation + /// @{ + TriangulationParameters triangulation; + double retriangulationThreshold; ///< threshold to decide whether to re-triangulate + /// @} + + /// @name Parameters governing how triangulation result is treated + /// @{ + bool throwCheirality; ///< If true, re-throws Cheirality exceptions (default: false) + bool verboseCheirality; ///< If true, prints text for Cheirality exceptions (default: false) + /// @} + + // Constructor + SmartProjectionParams(LinearizationMode linMode = HESSIAN, + DegeneracyMode degMode = IGNORE_DEGENERACY, bool throwCheirality = false, + bool verboseCheirality = false) : + linearizationMode(linMode), degeneracyMode(degMode), retriangulationThreshold( + 1e-5), throwCheirality(throwCheirality), verboseCheirality( + verboseCheirality) { + } + + virtual ~SmartProjectionParams() { + } + + void print(const std::string& str) const { + std::cout << "linearizationMode: " << linearizationMode << "\n"; + std::cout << " degeneracyMode: " << degeneracyMode << "\n"; + std::cout << triangulation << std::endl; + } + + LinearizationMode getLinearizationMode() const { + return linearizationMode; + } + DegeneracyMode getDegeneracyMode() const { + return degeneracyMode; + } + TriangulationParameters getTriangulationParameters() const { + return triangulation; + } + bool getVerboseCheirality() const { + return verboseCheirality; + } + bool getThrowCheirality() const { + return throwCheirality; + } + void setLinearizationMode(LinearizationMode linMode) { + linearizationMode = linMode; + } + void setDegeneracyMode(DegeneracyMode degMode) { + degeneracyMode = degMode; + } + void setRankTolerance(double rankTol) { + triangulation.rankTolerance = rankTol; + } + void setEnableEPI(bool enableEPI) { + triangulation.enableEPI = enableEPI; + } + void setLandmarkDistanceThreshold(double landmarkDistanceThreshold) { + triangulation.landmarkDistanceThreshold = landmarkDistanceThreshold; + } + void setDynamicOutlierRejectionThreshold(double dynOutRejectionThreshold) { + triangulation.dynamicOutlierRejectionThreshold = dynOutRejectionThreshold; + } }; /** * SmartProjectionFactor: triangulates point and keeps an estimate of it around. + * This factor operates with monocular cameras, where a camera is expected to + * behave like PinholeCamera or PinholePose. This factor is intended + * to be used directly with PinholeCamera, which optimizes the camera pose + * and calibration. This also requires that values contains the involved + * cameras (instead of poses and calibrations separately). + * If the calibration is fixed use SmartProjectionPoseFactor instead! */ -template -class SmartProjectionFactor: public SmartFactorBase, - D> { +template +class SmartProjectionFactor: public SmartFactorBase { + +public: + +private: + typedef SmartFactorBase Base; + typedef SmartProjectionFactor This; + typedef SmartProjectionFactor SmartProjectionCameraFactor; + protected: - // Some triangulation parameters - const double rankTolerance_; ///< threshold to decide whether triangulation is degenerate_ - const double retriangulationThreshold_; ///< threshold to decide whether to re-triangulate + /// @name Parameters + /// @{ + SmartProjectionParams params_; + /// @} + + /// @name Caching triangulation + /// @{ + mutable TriangulationResult result_; ///< result from triangulateSafe mutable std::vector cameraPosesTriangulation_; ///< current triangulation poses - - const bool manageDegeneracy_; ///< if set to true will use the rotation-only version for degenerate cases - - const bool enableEPI_; ///< if set to true, will refine triangulation using LM - - const double linearizationThreshold_; ///< threshold to decide whether to re-linearize - mutable std::vector cameraPosesLinearization_; ///< current linearization poses - - mutable Point3 point_; ///< Current estimate of the 3D point - - mutable bool degenerate_; - mutable bool cheiralityException_; - - // verbosity handling for Cheirality Exceptions - const bool throwCheirality_; ///< If true, rethrows Cheirality exceptions (default: false) - const bool verboseCheirality_; ///< If true, prints text for Cheirality exceptions (default: false) - - boost::shared_ptr state_; - - /// shorthand for smart projection factor state variable - typedef boost::shared_ptr SmartFactorStatePtr; - - /// shorthand for base class type - typedef SmartFactorBase, D> Base; - - double landmarkDistanceThreshold_; // if the landmark is triangulated at a - // distance larger than that the factor is considered degenerate - - double dynamicOutlierRejectionThreshold_; // if this is nonnegative the factor will check if the - // average reprojection error is smaller than this threshold after triangulation, - // and the factor is disregarded if the error is large - - /// shorthand for this class - typedef SmartProjectionFactor This; + /// @} public: /// shorthand for a smart pointer to a factor typedef boost::shared_ptr shared_ptr; - /// shorthand for a pinhole camera - typedef PinholeCamera Camera; - typedef CameraSet Cameras; + /// shorthand for a set of cameras + typedef CameraSet Cameras; + + /** + * Default constructor, only for serialization + */ + SmartProjectionFactor() {} /** * Constructor - * @param rankTol tolerance used to check if point triangulation is degenerate - * @param linThreshold threshold on relative pose changes used to decide whether to relinearize (selective relinearization) - * @param manageDegeneracy is true, in presence of degenerate triangulation, the factor is converted to a rotation-only constraint, - * otherwise the factor is simply neglected - * @param enableEPI if set to true linear triangulation is refined with embedded LM iterations - * @param body_P_sensor is the transform from sensor to body frame (default identity) + * @param body_P_sensor pose of the camera in the body frame + * @param params internal parameters of the smart factors */ - SmartProjectionFactor(const double rankTol, const double linThreshold, - const bool manageDegeneracy, const bool enableEPI, - boost::optional body_P_sensor = boost::none, - double landmarkDistanceThreshold = 1e10, - double dynamicOutlierRejectionThreshold = -1, SmartFactorStatePtr state = - SmartFactorStatePtr(new SmartProjectionFactorState())) : - Base(body_P_sensor), rankTolerance_(rankTol), retriangulationThreshold_( - 1e-5), manageDegeneracy_(manageDegeneracy), enableEPI_(enableEPI), linearizationThreshold_( - linThreshold), degenerate_(false), cheiralityException_(false), throwCheirality_( - false), verboseCheirality_(false), state_(state), landmarkDistanceThreshold_( - landmarkDistanceThreshold), dynamicOutlierRejectionThreshold_( - dynamicOutlierRejectionThreshold) { + SmartProjectionFactor(const SharedNoiseModel& sharedNoiseModel, + const boost::optional body_P_sensor = boost::none, + const SmartProjectionParams& params = SmartProjectionParams()) : + Base(sharedNoiseModel, body_P_sensor), params_(params), // + result_(TriangulationResult::Degenerate()) { } /** Virtual destructor */ @@ -147,24 +182,33 @@ public: */ void print(const std::string& s = "", const KeyFormatter& keyFormatter = DefaultKeyFormatter) const { - std::cout << s << "SmartProjectionFactor, z = \n"; - std::cout << "rankTolerance_ = " << rankTolerance_ << std::endl; - std::cout << "degenerate_ = " << degenerate_ << std::endl; - std::cout << "cheiralityException_ = " << cheiralityException_ << std::endl; + std::cout << s << "SmartProjectionFactor\n"; + std::cout << "linearizationMode:\n" << params_.linearizationMode + << std::endl; + std::cout << "triangulationParameters:\n" << params_.triangulation + << std::endl; + std::cout << "result:\n" << result_ << std::endl; Base::print("", keyFormatter); } - /// Check if the new linearization point_ is the same as the one used for previous triangulation + /// equals + virtual bool equals(const NonlinearFactor& p, double tol = 1e-9) const { + const This *e = dynamic_cast(&p); + return e && params_.linearizationMode == e->params_.linearizationMode + && Base::equals(p, tol); + } + + /// Check if the new linearization point is the same as the one used for previous triangulation bool decideIfTriangulate(const Cameras& cameras) const { - // several calls to linearize will be done from the same linearization point_, hence it is not needed to re-triangulate + // several calls to linearize will be done from the same linearization point, hence it is not needed to re-triangulate // Note that this is not yet "selecting linearization", that will come later, and we only check if the - // current linearization is the "same" (up to tolerance) w.r.t. the last time we triangulated the point_ + // current linearization is the "same" (up to tolerance) w.r.t. the last time we triangulated the point size_t m = cameras.size(); bool retriangulate = false; - // if we do not have a previous linearization point_ or the new linearization point_ includes more poses + // if we do not have a previous linearization point or the new linearization point includes more poses if (cameraPosesTriangulation_.empty() || cameras.size() != cameraPosesTriangulation_.size()) retriangulate = true; @@ -172,7 +216,7 @@ public: if (!retriangulate) { for (size_t i = 0; i < cameras.size(); i++) { if (!cameras[i].pose().equals(cameraPosesTriangulation_[i], - retriangulationThreshold_)) { + params_.retriangulationThreshold)) { retriangulate = true; // at least two poses are different, hence we retriangulate break; } @@ -187,137 +231,34 @@ public: cameraPosesTriangulation_.push_back(cameras[i].pose()); } - return retriangulate; // if we arrive to this point_ all poses are the same and we don't need re-triangulation - } - - /// This function checks if the new linearization point_ is 'close' to the previous one used for linearization - bool decideIfLinearize(const Cameras& cameras) const { - // "selective linearization" - // The function evaluates how close are the old and the new poses, transformed in the ref frame of the first pose - // (we only care about the "rigidity" of the poses, not about their absolute pose) - - if (this->linearizationThreshold_ < 0) //by convention if linearizationThreshold is negative we always relinearize - return true; - - // if we do not have a previous linearization point_ or the new linearization point_ includes more poses - if (cameraPosesLinearization_.empty() - || (cameras.size() != cameraPosesLinearization_.size())) - return true; - - Pose3 firstCameraPose, firstCameraPoseOld; - for (size_t i = 0; i < cameras.size(); i++) { - - if (i == 0) { // we store the initial pose, this is useful for selective re-linearization - firstCameraPose = cameras[i].pose(); - firstCameraPoseOld = cameraPosesLinearization_[i]; - continue; - } - - // we compare the poses in the frame of the first pose - Pose3 localCameraPose = firstCameraPose.between(cameras[i].pose()); - Pose3 localCameraPoseOld = firstCameraPoseOld.between( - cameraPosesLinearization_[i]); - if (!localCameraPose.equals(localCameraPoseOld, - this->linearizationThreshold_)) - return true; // at least two "relative" poses are different, hence we re-linearize - } - return false; // if we arrive to this point_ all poses are the same and we don't need re-linearize + return retriangulate; // if we arrive to this point all poses are the same and we don't need re-triangulation } /// triangulateSafe - size_t triangulateSafe(const Values& values) const { - return triangulateSafe(this->cameras(values)); - } - - /// triangulateSafe - size_t triangulateSafe(const Cameras& cameras) const { + TriangulationResult triangulateSafe(const Cameras& cameras) const { size_t m = cameras.size(); - if (m < 2) { // if we have a single pose the corresponding factor is uninformative - degenerate_ = true; - return m; - } + if (m < 2) // if we have a single pose the corresponding factor is uninformative + return TriangulationResult::Degenerate(); + bool retriangulate = decideIfTriangulate(cameras); - - if (retriangulate) { - // We triangulate the 3D position of the landmark - try { - // std::cout << "triangulatePoint3 i \n" << rankTolerance << std::endl; - point_ = triangulatePoint3(cameras, this->measured_, - rankTolerance_, enableEPI_); - degenerate_ = false; - cheiralityException_ = false; - - // Check landmark distance and reprojection errors to avoid outliers - double totalReprojError = 0.0; - size_t i = 0; - BOOST_FOREACH(const Camera& camera, cameras) { - Point3 cameraTranslation = camera.pose().translation(); - // we discard smart factors corresponding to points that are far away - if (cameraTranslation.distance(point_) > landmarkDistanceThreshold_) { - degenerate_ = true; - break; - } - const Point2& zi = this->measured_.at(i); - try { - Point2 reprojectionError(camera.project(point_) - zi); - totalReprojError += reprojectionError.vector().norm(); - } catch (CheiralityException) { - cheiralityException_ = true; - } - i += 1; - } - // we discard smart factors that have large reprojection error - if (dynamicOutlierRejectionThreshold_ > 0 - && totalReprojError / m > dynamicOutlierRejectionThreshold_) - degenerate_ = true; - - } catch (TriangulationUnderconstrainedException&) { - // if TriangulationUnderconstrainedException can be - // 1) There is a single pose for triangulation - this should not happen because we checked the number of poses before - // 2) The rank of the matrix used for triangulation is < 3: rotation-only, parallel cameras (or motion towards the landmark) - // in the second case we want to use a rotation-only smart factor - degenerate_ = true; - cheiralityException_ = false; - } catch (TriangulationCheiralityException&) { - // point is behind one of the cameras: can be the case of close-to-parallel cameras or may depend on outliers - // we manage this case by either discarding the smart factor, or imposing a rotation-only constraint - cheiralityException_ = true; - } - } - return m; + if (retriangulate) + result_ = gtsam::triangulateSafe(cameras, this->measured_, + params_.triangulation); + return result_; } /// triangulate bool triangulateForLinearize(const Cameras& cameras) const { - - bool isDebug = false; - size_t nrCameras = this->triangulateSafe(cameras); - - if (nrCameras < 2 - || (!this->manageDegeneracy_ - && (this->cheiralityException_ || this->degenerate_))) { - if (isDebug) { - std::cout - << "createRegularImplicitSchurFactor: degenerate configuration" - << std::endl; - } - return false; - } else { - - // instead, if we want to manage the exception.. - if (this->cheiralityException_ || this->degenerate_) { // if we want to manage the exceptions with rotation-only factors - this->degenerate_ = true; - } - return true; - } + triangulateSafe(cameras); // imperative, might reset result_ + return bool(result_); } /// linearize returns a Hessianfactor that is an approximation of error(p) - boost::shared_ptr > createHessianFactor( - const Cameras& cameras, const double lambda = 0.0) const { + boost::shared_ptr > createHessianFactor( + const Cameras& cameras, const double lambda = 0.0, bool diagonalDamping = + false) const { - bool isDebug = false; size_t numKeys = this->keys_.size(); // Create structures for Hessian Factors std::vector js; @@ -331,264 +272,198 @@ public: exit(1); } - this->triangulateSafe(cameras); + triangulateSafe(cameras); - if (numKeys < 2 - || (!this->manageDegeneracy_ - && (this->cheiralityException_ || this->degenerate_))) { - // std::cout << "In linearize: exception" << std::endl; + if (params_.degeneracyMode == ZERO_ON_DEGENERACY && !result_) { + // failed: return"empty" Hessian BOOST_FOREACH(Matrix& m, Gs) - m = zeros(D, D); + m = zeros(Base::Dim, Base::Dim); BOOST_FOREACH(Vector& v, gs) - v = zero(D); - return boost::make_shared >(this->keys_, Gs, gs, - 0.0); + v = zero(Base::Dim); + return boost::make_shared >(this->keys_, + Gs, gs, 0.0); } - // instead, if we want to manage the exception.. - if (this->cheiralityException_ || this->degenerate_) { // if we want to manage the exceptions with rotation-only factors - this->degenerate_ = true; - } - - bool doLinearize = this->decideIfLinearize(cameras); - - if (this->linearizationThreshold_ >= 0 && doLinearize) // if we apply selective relinearization and we need to relinearize - for (size_t i = 0; i < cameras.size(); i++) - this->cameraPosesLinearization_[i] = cameras[i].pose(); - - if (!doLinearize) { // return the previous Hessian factor - std::cout << "=============================" << std::endl; - std::cout << "doLinearize " << doLinearize << std::endl; - std::cout << "this->linearizationThreshold_ " - << this->linearizationThreshold_ << std::endl; - std::cout << "this->degenerate_ " << this->degenerate_ << std::endl; - std::cout - << "something wrong in SmartProjectionHessianFactor: selective relinearization should be disabled" - << std::endl; - exit(1); - return boost::make_shared >(this->keys_, - this->state_->Gs, this->state_->gs, this->state_->f); - } - - // ================================================================== - Matrix F, E; + // Jacobian could be 3D Point3 OR 2D Unit3, difference is E.cols(). + std::vector Fblocks; + Matrix E; Vector b; - double f = computeJacobians(F, E, b, cameras); + computeJacobiansWithTriangulatedPoint(Fblocks, E, b, cameras); - // Schur complement trick - // Frank says: should be possible to do this more efficiently? - // And we care, as in grouped factors this is called repeatedly - Matrix H(D * numKeys, D * numKeys); - Vector gs_vector; + // Whiten using noise model + Base::whitenJacobians(Fblocks, E, b); - Matrix3 P = Base::PointCov(E, lambda); - H.noalias() = F.transpose() * (F - (E * (P * (E.transpose() * F)))); - gs_vector.noalias() = F.transpose() * (b - (E * (P * (E.transpose() * b)))); - if (isDebug) - std::cout << "gs_vector size " << gs_vector.size() << std::endl; + // build augmented hessian + SymmetricBlockMatrix augmentedHessian = // + Cameras::SchurComplement(Fblocks, E, b, lambda, diagonalDamping); - // Populate Gs and gs - int GsCount2 = 0; - for (DenseIndex i1 = 0; i1 < (DenseIndex) numKeys; i1++) { // for each camera - DenseIndex i1D = i1 * D; - gs.at(i1) = gs_vector.segment(i1D); - for (DenseIndex i2 = 0; i2 < (DenseIndex) numKeys; i2++) { - if (i2 >= i1) { - Gs.at(GsCount2) = H.block(i1D, i2 * D); - GsCount2++; - } - } - } - // ================================================================== - if (this->linearizationThreshold_ >= 0) { // if we do not use selective relinearization we don't need to store these variables - this->state_->Gs = Gs; - this->state_->gs = gs; - this->state_->f = f; - } - return boost::make_shared >(this->keys_, Gs, gs, f); + return boost::make_shared >(this->keys_, + augmentedHessian); } // create factor - boost::shared_ptr > createRegularImplicitSchurFactor( + boost::shared_ptr > createRegularImplicitSchurFactor( const Cameras& cameras, double lambda) const { if (triangulateForLinearize(cameras)) - return Base::createRegularImplicitSchurFactor(cameras, point_, lambda); + return Base::createRegularImplicitSchurFactor(cameras, *result_, lambda); else - return boost::shared_ptr >(); + // failed: return empty + return boost::shared_ptr >(); } /// create factor - boost::shared_ptr > createJacobianQFactor( + boost::shared_ptr > createJacobianQFactor( const Cameras& cameras, double lambda) const { if (triangulateForLinearize(cameras)) - return Base::createJacobianQFactor(cameras, point_, lambda); + return Base::createJacobianQFactor(cameras, *result_, lambda); else - return boost::make_shared >(this->keys_); + // failed: return empty + return boost::make_shared >(this->keys_); } /// Create a factor, takes values - boost::shared_ptr > createJacobianQFactor( + boost::shared_ptr > createJacobianQFactor( const Values& values, double lambda) const { - Cameras myCameras; - // TODO triangulate twice ?? - bool nonDegenerate = computeCamerasAndTriangulate(values, myCameras); - if (nonDegenerate) - return createJacobianQFactor(myCameras, lambda); - else - return boost::make_shared >(this->keys_); + return createJacobianQFactor(this->cameras(values), lambda); } /// different (faster) way to compute Jacobian factor boost::shared_ptr createJacobianSVDFactor( const Cameras& cameras, double lambda) const { if (triangulateForLinearize(cameras)) - return Base::createJacobianSVDFactor(cameras, point_, lambda); + return Base::createJacobianSVDFactor(cameras, *result_, lambda); else - return boost::make_shared >(this->keys_); + // failed: return empty + return boost::make_shared >(this->keys_); } - /// Returns true if nonDegenerate - bool computeCamerasAndTriangulate(const Values& values, - Cameras& myCameras) const { - Values valuesFactor; + /// linearize to a Hessianfactor + virtual boost::shared_ptr > linearizeToHessian( + const Values& values, double lambda = 0.0) const { + return createHessianFactor(this->cameras(values), lambda); + } - // Select only the cameras - BOOST_FOREACH(const Key key, this->keys_) - valuesFactor.insert(key, values.at(key)); + /// linearize to an Implicit Schur factor + virtual boost::shared_ptr > linearizeToImplicit( + const Values& values, double lambda = 0.0) const { + return createRegularImplicitSchurFactor(this->cameras(values), lambda); + } - myCameras = this->cameras(valuesFactor); - size_t nrCameras = this->triangulateSafe(myCameras); + /// linearize to a JacobianfactorQ + virtual boost::shared_ptr > linearizeToJacobian( + const Values& values, double lambda = 0.0) const { + return createJacobianQFactor(this->cameras(values), lambda); + } - if (nrCameras < 2 - || (!this->manageDegeneracy_ - && (this->cheiralityException_ || this->degenerate_))) - return false; - - // instead, if we want to manage the exception.. - if (this->cheiralityException_ || this->degenerate_) // if we want to manage the exceptions with rotation-only factors - this->degenerate_ = true; - - if (this->degenerate_) { - std::cout << "SmartProjectionFactor: this is not ready" << std::endl; - std::cout << "this->cheiralityException_ " << this->cheiralityException_ - << std::endl; - std::cout << "this->degenerate_ " << this->degenerate_ << std::endl; + /** + * Linearize to Gaussian Factor + * @param values Values structure which must contain camera poses for this factor + * @return a Gaussian factor + */ + boost::shared_ptr linearizeDamped(const Cameras& cameras, + const double lambda = 0.0) const { + // depending on flag set on construction we may linearize to different linear factors + switch (params_.linearizationMode) { + case HESSIAN: + return createHessianFactor(cameras, lambda); + case IMPLICIT_SCHUR: + return createRegularImplicitSchurFactor(cameras, lambda); + case JACOBIAN_SVD: + return createJacobianSVDFactor(cameras, lambda); + case JACOBIAN_Q: + return createJacobianQFactor(cameras, lambda); + default: + throw std::runtime_error("SmartFactorlinearize: unknown mode"); } - return true; } - /// Assumes non-degenerate ! - void computeEP(Matrix& E, Matrix& P, const Cameras& cameras) const { - return Base::computeEP(E, P, cameras, point_); + /** + * Linearize to Gaussian Factor + * @param values Values structure which must contain camera poses for this factor + * @return a Gaussian factor + */ + boost::shared_ptr linearizeDamped(const Values& values, + const double lambda = 0.0) const { + // depending on flag set on construction we may linearize to different linear factors + Cameras cameras = this->cameras(values); + return linearizeDamped(cameras, lambda); } - /// Takes values - bool computeEP(Matrix& E, Matrix& P, const Values& values) const { - Cameras myCameras; - bool nonDegenerate = computeCamerasAndTriangulate(values, myCameras); + /// linearize + virtual boost::shared_ptr linearize( + const Values& values) const { + return linearizeDamped(values); + } + + /** + * Triangulate and compute derivative of error with respect to point + * @return whether triangulation worked + */ + bool triangulateAndComputeE(Matrix& E, const Cameras& cameras) const { + bool nonDegenerate = triangulateForLinearize(cameras); if (nonDegenerate) - computeEP(E, P, myCameras); + cameras.project2(*result_, boost::none, E); return nonDegenerate; } - /// Version that takes values, and creates the point - bool computeJacobians(std::vector& Fblocks, - Matrix& E, Vector& b, const Values& values) const { - Cameras myCameras; - bool nonDegenerate = computeCamerasAndTriangulate(values, myCameras); - if (nonDegenerate) - computeJacobians(Fblocks, E, b, myCameras); - return nonDegenerate; + /** + * Triangulate and compute derivative of error with respect to point + * @return whether triangulation worked + */ + bool triangulateAndComputeE(Matrix& E, const Values& values) const { + Cameras cameras = this->cameras(values); + return triangulateAndComputeE(E, cameras); } /// Compute F, E only (called below in both vanilla and SVD versions) /// Assumes the point has been computed /// Note E can be 2m*3 or 2m*2, in case point is degenerate - double computeJacobians(std::vector& Fblocks, - Matrix& E, Vector& b, const Cameras& cameras) const { + void computeJacobiansWithTriangulatedPoint( + std::vector& Fblocks, Matrix& E, Vector& b, + const Cameras& cameras) const { - if (this->degenerate_) { - std::cout << "manage degeneracy " << manageDegeneracy_ << std::endl; - std::cout << "point " << point_ << std::endl; - std::cout - << "SmartProjectionFactor: Management of degeneracy is disabled - not ready to be used" - << std::endl; - if (D > 6) { - std::cout - << "Management of degeneracy is not yet ready when one also optimizes for the calibration " - << std::endl; - } - - int numKeys = this->keys_.size(); - E = zeros(2 * numKeys, 2); - b = zero(2 * numKeys); - double f = 0; - for (size_t i = 0; i < this->measured_.size(); i++) { - if (i == 0) { // first pose - this->point_ = cameras[i].backprojectPointAtInfinity( - this->measured_.at(i)); - // 3D parametrization of point at infinity: [px py 1] - } - Matrix Fi, Ei; - Vector bi = -(cameras[i].projectPointAtInfinity(this->point_, Fi, Ei) - - this->measured_.at(i)).vector(); - - this->noise_.at(i)->WhitenSystem(Fi, Ei, bi); - f += bi.squaredNorm(); - Fblocks.push_back(typename Base::KeyMatrix2D(this->keys_[i], Fi)); - E.block<2, 2>(2 * i, 0) = Ei; - subInsert(b, bi, 2 * i); - } - return f; + if (!result_) { + // Handle degeneracy + // TODO check flag whether we should do this + Unit3 backProjected = cameras[0].backprojectPointAtInfinity( + this->measured_.at(0)); + Base::computeJacobians(Fblocks, E, b, cameras, backProjected); } else { - // nondegenerate: just return Base version - return Base::computeJacobians(Fblocks, E, b, cameras, point_); - } // end else + // valid result: just return Base version + Base::computeJacobians(Fblocks, E, b, cameras, *result_); + } + } + + /// Version that takes values, and creates the point + bool triangulateAndComputeJacobians( + std::vector& Fblocks, Matrix& E, Vector& b, + const Values& values) const { + Cameras cameras = this->cameras(values); + bool nonDegenerate = triangulateForLinearize(cameras); + if (nonDegenerate) + computeJacobiansWithTriangulatedPoint(Fblocks, E, b, cameras); + return nonDegenerate; } /// takes values - bool computeJacobiansSVD(std::vector& Fblocks, - Matrix& Enull, Vector& b, const Values& values) const { - typename Base::Cameras myCameras; - double good = computeCamerasAndTriangulate(values, myCameras); - if (good) - computeJacobiansSVD(Fblocks, Enull, b, myCameras); - return true; - } - - /// SVD version - double computeJacobiansSVD(std::vector& Fblocks, - Matrix& Enull, Vector& b, const Cameras& cameras) const { - return Base::computeJacobiansSVD(Fblocks, Enull, b, cameras, point_); - } - - /// Returns Matrix, TODO: maybe should not exist -> not sparse ! - // TODO should there be a lambda? - double computeJacobiansSVD(Matrix& F, Matrix& Enull, Vector& b, - const Cameras& cameras) const { - return Base::computeJacobiansSVD(F, Enull, b, cameras, point_); - } - - /// Returns Matrix, TODO: maybe should not exist -> not sparse ! - double computeJacobians(Matrix& F, Matrix& E, Vector& b, - const Cameras& cameras) const { - return Base::computeJacobians(F, E, b, cameras, point_); - } - - /// Calculate vector of re-projection errors, before applying noise model - /// Assumes triangulation was done and degeneracy handled - Vector reprojectionError(const Cameras& cameras) const { - return Base::reprojectionError(cameras, point_); - } - - /// Calculate vector of re-projection errors, before applying noise model - Vector reprojectionError(const Values& values) const { - Cameras myCameras; - bool nonDegenerate = computeCamerasAndTriangulate(values, myCameras); + bool triangulateAndComputeJacobiansSVD( + std::vector& Fblocks, Matrix& Enull, Vector& b, + const Values& values) const { + Cameras cameras = this->cameras(values); + bool nonDegenerate = triangulateForLinearize(cameras); if (nonDegenerate) - return reprojectionError(myCameras); + Base::computeJacobiansSVD(Fblocks, Enull, b, cameras, *result_); + return nonDegenerate; + } + + /// Calculate vector of re-projection errors, before applying noise model + Vector reprojectionErrorAfterTriangulation(const Values& values) const { + Cameras cameras = this->cameras(values); + bool nonDegenerate = triangulateForLinearize(cameras); + if (nonDegenerate) + return Base::unwhitenedError(cameras, *result_); else - return zero(myCameras.size() * 2); + return zero(cameras.size() * 2); } /** @@ -600,86 +475,57 @@ public: double totalReprojectionError(const Cameras& cameras, boost::optional externalPoint = boost::none) const { - size_t nrCameras; - if (externalPoint) { - nrCameras = this->keys_.size(); - point_ = *externalPoint; - degenerate_ = false; - cheiralityException_ = false; - } else { - nrCameras = this->triangulateSafe(cameras); - } + if (externalPoint) + result_ = TriangulationResult(*externalPoint); + else + result_ = triangulateSafe(cameras); - if (nrCameras < 2 - || (!this->manageDegeneracy_ - && (this->cheiralityException_ || this->degenerate_))) { + if (result_) + // All good, just use version in base class + return Base::totalReprojectionError(cameras, *result_); + else if (params_.degeneracyMode == HANDLE_INFINITY) { + // Otherwise, manage the exceptions with rotation-only factors + const Point2& z0 = this->measured_.at(0); + Unit3 backprojected = cameras.front().backprojectPointAtInfinity(z0); + return Base::totalReprojectionError(cameras, backprojected); + } else // if we don't want to manage the exceptions we discard the factor - // std::cout << "In error evaluation: exception" << std::endl; return 0.0; - } + } - if (this->cheiralityException_) { // if we want to manage the exceptions with rotation-only factors - std::cout - << "SmartProjectionHessianFactor: cheirality exception (this should not happen if CheiralityException is disabled)!" - << std::endl; - this->degenerate_ = true; - } - - if (this->degenerate_) { - // return 0.0; // TODO: this maybe should be zero? - std::cout - << "SmartProjectionHessianFactor: trying to manage degeneracy (this should not happen is manageDegeneracy is disabled)!" - << std::endl; - size_t i = 0; - double overallError = 0; - BOOST_FOREACH(const Camera& camera, cameras) { - const Point2& zi = this->measured_.at(i); - if (i == 0) // first pose - this->point_ = camera.backprojectPointAtInfinity(zi); // 3D parametrization of point at infinity - Point2 reprojectionError( - camera.projectPointAtInfinity(this->point_) - zi); - overallError += 0.5 - * this->noise_.at(i)->distance(reprojectionError.vector()); - i += 1; - } - return overallError; - } else { - // Just use version in base class - return Base::totalReprojectionError(cameras, point_); + /// Calculate total reprojection error + virtual double error(const Values& values) const { + if (this->active(values)) { + return totalReprojectionError(Base::cameras(values)); + } else { // else of active flag + return 0.0; } } - /// Cameras are computed in derived class - virtual Cameras cameras(const Values& values) const = 0; - /** return the landmark */ - boost::optional point() const { - return point_; + TriangulationResult point() const { + return result_; } /** COMPUTE the landmark */ - boost::optional point(const Values& values) const { - triangulateSafe(values); - return point_; + TriangulationResult point(const Values& values) const { + Cameras cameras = this->cameras(values); + return triangulateSafe(cameras); + } + + /// Is result valid? + bool isValid() const { + return result_; } /** return the degenerate state */ - inline bool isDegenerate() const { - return (cheiralityException_ || degenerate_); + bool isDegenerate() const { + return result_.degenerate(); } /** return the cheirality status flag */ - inline bool isPointBehindCamera() const { - return cheiralityException_; - } - /** return cheirality verbosity */ - inline bool verboseCheirality() const { - return verboseCheirality_; - } - - /** return flag for throwing cheirality exceptions */ - inline bool throwCheirality() const { - return throwCheirality_; + bool isPointBehindCamera() const { + return result_.behindCamera(); } private: @@ -687,11 +533,18 @@ private: /// Serialization function friend class boost::serialization::access; template - void serialize(ARCHIVE & ar, const unsigned int /*version*/) { + void serialize(ARCHIVE & ar, const unsigned int version) { ar & BOOST_SERIALIZATION_BASE_OBJECT_NVP(Base); - ar & BOOST_SERIALIZATION_NVP(throwCheirality_); - ar & BOOST_SERIALIZATION_NVP(verboseCheirality_); + ar & BOOST_SERIALIZATION_NVP(params_.throwCheirality); + ar & BOOST_SERIALIZATION_NVP(params_.verboseCheirality); } +} +; + +/// traits +template +struct traits > : public Testable< + SmartProjectionFactor > { }; } // \ namespace gtsam diff --git a/gtsam/slam/SmartProjectionPoseFactor.h b/gtsam/slam/SmartProjectionPoseFactor.h index 127bf284f..455e0de87 100644 --- a/gtsam/slam/SmartProjectionPoseFactor.h +++ b/gtsam/slam/SmartProjectionPoseFactor.h @@ -11,7 +11,7 @@ /** * @file SmartProjectionPoseFactor.h - * @brief Produces an Hessian factors on POSES from monocular measurements of a single landmark + * @brief Smart factor on poses, assuming camera calibration is fixed * @author Luca Carlone * @author Chris Beall * @author Zsolt Kira @@ -34,91 +34,52 @@ namespace gtsam { */ /** - * The calibration is known here. The factor only constraints poses (variable dimension is 6) + * This factor assumes that camera calibration is fixed, and that + * the calibration is the same for all cameras involved in this factor. + * The factor only constrains poses (variable dimension is 6). + * This factor requires that values contains the involved poses (Pose3). + * If the calibration should be optimized, as well, use SmartProjectionFactor instead! * @addtogroup SLAM */ template -class SmartProjectionPoseFactor: public SmartProjectionFactor { +class SmartProjectionPoseFactor: public SmartProjectionFactor< + PinholePose > { + +private: + typedef PinholePose Camera; + typedef SmartProjectionFactor Base; + typedef SmartProjectionPoseFactor This; + protected: - LinearizationMode linearizeTo_; ///< How to linearize the factor (HESSIAN, JACOBIAN_SVD, JACOBIAN_Q) - - std::vector > K_all_; ///< shared pointer to calibration object (one for each camera) + boost::shared_ptr K_; ///< calibration object (one for all cameras) public: - /// shorthand for base class type - typedef SmartProjectionFactor Base; - - /// shorthand for this class - typedef SmartProjectionPoseFactor This; - /// shorthand for a smart pointer to a factor typedef boost::shared_ptr shared_ptr; /** - * Constructor - * @param rankTol tolerance used to check if point triangulation is degenerate - * @param linThreshold threshold on relative pose changes used to decide whether to relinearize (selective relinearization) - * @param manageDegeneracy is true, in presence of degenerate triangulation, the factor is converted to a rotation-only constraint, - * otherwise the factor is simply neglected - * @param enableEPI if set to true linear triangulation is refined with embedded LM iterations - * @param body_P_sensor is the transform from sensor to body frame (default identity) + * Default constructor, only for serialization */ - SmartProjectionPoseFactor(const double rankTol = 1, - const double linThreshold = -1, const bool manageDegeneracy = false, - const bool enableEPI = false, boost::optional body_P_sensor = boost::none, - LinearizationMode linearizeTo = HESSIAN, double landmarkDistanceThreshold = 1e10, - double dynamicOutlierRejectionThreshold = -1) : - Base(rankTol, linThreshold, manageDegeneracy, enableEPI, body_P_sensor, - landmarkDistanceThreshold, dynamicOutlierRejectionThreshold), linearizeTo_(linearizeTo) {} + SmartProjectionPoseFactor() {} + + /** + * Constructor + * @param Isotropic measurement noise + * @param K (fixed) calibration, assumed to be the same for all cameras + * @param body_P_sensor pose of the camera in the body frame + * @param params internal parameters of the smart factors + */ + SmartProjectionPoseFactor(const SharedNoiseModel& sharedNoiseModel, + const boost::shared_ptr K, + const boost::optional body_P_sensor = boost::none, + const SmartProjectionParams& params = SmartProjectionParams()) : + Base(sharedNoiseModel, body_P_sensor, params), K_(K) { + } /** Virtual destructor */ - virtual ~SmartProjectionPoseFactor() {} - - /** - * add a new measurement and pose key - * @param measured is the 2m dimensional location of the projection of a single landmark in the m view (the measurement) - * @param poseKey is key corresponding to the camera observing the same landmark - * @param noise_i is the measurement noise - * @param K_i is the (known) camera calibration - */ - void add(const Point2 measured_i, const Key poseKey_i, - const SharedNoiseModel noise_i, - const boost::shared_ptr K_i) { - Base::add(measured_i, poseKey_i, noise_i); - K_all_.push_back(K_i); - } - - /** - * Variant of the previous one in which we include a set of measurements - * @param measurements vector of the 2m dimensional location of the projection of a single landmark in the m view (the measurement) - * @param poseKeys vector of keys corresponding to the camera observing the same landmark - * @param noises vector of measurement noises - * @param Ks vector of calibration objects - */ - void add(std::vector measurements, std::vector poseKeys, - std::vector noises, - std::vector > Ks) { - Base::add(measurements, poseKeys, noises); - for (size_t i = 0; i < measurements.size(); i++) { - K_all_.push_back(Ks.at(i)); - } - } - - /** - * Variant of the previous one in which we include a set of measurements with the same noise and calibration - * @param mmeasurements vector of the 2m dimensional location of the projection of a single landmark in the m view (the measurement) - * @param poseKeys vector of keys corresponding to the camera observing the same landmark - * @param noise measurement noise (same for all measurements) - * @param K the (known) camera calibration (same for all measurements) - */ - void add(std::vector measurements, std::vector poseKeys, - const SharedNoiseModel noise, const boost::shared_ptr K) { - for (size_t i = 0; i < measurements.size(); i++) { - Base::add(measurements.at(i), poseKeys.at(i), noise); - K_all_.push_back(K); - } + virtual ~SmartProjectionPoseFactor() { } /** @@ -129,59 +90,15 @@ public: void print(const std::string& s = "", const KeyFormatter& keyFormatter = DefaultKeyFormatter) const { std::cout << s << "SmartProjectionPoseFactor, z = \n "; - BOOST_FOREACH(const boost::shared_ptr& K, K_all_) - K->print("calibration = "); Base::print("", keyFormatter); } /// equals virtual bool equals(const NonlinearFactor& p, double tol = 1e-9) const { const This *e = dynamic_cast(&p); - return e && Base::equals(p, tol); } - /** - * Collect all cameras involved in this factor - * @param values Values structure which must contain camera poses corresponding - * to keys involved in this factor - * @return vector of Values - */ - typename Base::Cameras cameras(const Values& values) const { - typename Base::Cameras cameras; - size_t i=0; - BOOST_FOREACH(const Key& k, this->keys_) { - Pose3 pose = values.at(k); - if(Base::body_P_sensor_) - pose = pose.compose(*(Base::body_P_sensor_)); - - typename Base::Camera camera(pose, *K_all_[i++]); - cameras.push_back(camera); - } - return cameras; - } - - /** - * Linearize to Gaussian Factor - * @param values Values structure which must contain camera poses for this factor - * @return - */ - virtual boost::shared_ptr linearize( - const Values& values) const { - // depending on flag set on construction we may linearize to different linear factors - switch(linearizeTo_){ - case JACOBIAN_SVD : - return this->createJacobianSVDFactor(cameras(values), 0.0); - break; - case JACOBIAN_Q : - return this->createJacobianQFactor(cameras(values), 0.0); - break; - default: - return this->createHessianFactor(cameras(values)); - break; - } - } - /** * error calculates the error of the factor. */ @@ -193,9 +110,28 @@ public: } } - /** return the calibration object */ - inline const std::vector > calibration() const { - return K_all_; + /** return calibration shared pointers */ + inline const boost::shared_ptr calibration() const { + return K_; + } + + /** + * Collect all cameras involved in this factor + * @param values Values structure which must contain camera poses corresponding + * to keys involved in this factor + * @return vector of Values + */ + typename Base::Cameras cameras(const Values& values) const { + typename Base::Cameras cameras; + BOOST_FOREACH(const Key& k, this->keys_) { + Pose3 pose = values.at(k); + if (Base::body_P_sensor_) + pose = pose.compose(*(Base::body_P_sensor_)); + + Camera camera(pose, K_); + cameras.push_back(camera); + } + return cameras; } private: @@ -205,10 +141,11 @@ private: template void serialize(ARCHIVE & ar, const unsigned int /*version*/) { ar & BOOST_SERIALIZATION_BASE_OBJECT_NVP(Base); - ar & BOOST_SERIALIZATION_NVP(K_all_); + ar & BOOST_SERIALIZATION_NVP(K_); } -}; // end of class declaration +}; +// end of class declaration /// traits template diff --git a/gtsam/slam/TriangulationFactor.h b/gtsam/slam/TriangulationFactor.h index d0371d1f8..aa50929a5 100644 --- a/gtsam/slam/TriangulationFactor.h +++ b/gtsam/slam/TriangulationFactor.h @@ -16,9 +16,9 @@ */ #include -#include -#include +#include #include +#include namespace gtsam { @@ -27,19 +27,28 @@ namespace gtsam { * The calibration and pose are assumed known. * @addtogroup SLAM */ -template +template class TriangulationFactor: public NoiseModelFactor1 { public: - /// Camera type - typedef PinholeCamera Camera; + /// CAMERA type + typedef CAMERA Camera; protected: + /// shorthand for base class type + typedef NoiseModelFactor1 Base; + + /// shorthand for this class + typedef TriangulationFactor This; + + /// shorthand for measurement type, e.g. Point2 or StereoPoint2 + typedef typename CAMERA::Measurement Measurement; + // Keep a copy of measurement and calibration for I/O - const Camera camera_; ///< Camera in which this landmark was seen - const Point2 measured_; ///< 2D measurement + const CAMERA camera_; ///< CAMERA in which this landmark was seen + const Measurement measured_; ///< 2D measurement // verbosity handling for Cheirality Exceptions const bool throwCheirality_; ///< If true, rethrows Cheirality exceptions (default: false) @@ -47,12 +56,6 @@ protected: public: - /// shorthand for base class type - typedef NoiseModelFactor1 Base; - - /// shorthand for this class - typedef TriangulationFactor This; - /// shorthand for a smart pointer to a factor typedef boost::shared_ptr shared_ptr; @@ -70,14 +73,17 @@ public: * @param throwCheirality determines whether Cheirality exceptions are rethrown * @param verboseCheirality determines whether exceptions are printed for Cheirality */ - TriangulationFactor(const Camera& camera, const Point2& measured, + TriangulationFactor(const CAMERA& camera, const Measurement& measured, const SharedNoiseModel& model, Key pointKey, bool throwCheirality = false, bool verboseCheirality = false) : Base(model, pointKey), camera_(camera), measured_(measured), throwCheirality_( throwCheirality), verboseCheirality_(verboseCheirality) { - if (model && model->dim() != 2) + if (model && model->dim() != Measurement::dimension) throw std::invalid_argument( - "TriangulationFactor must be created with 2-dimensional noise model."); + "TriangulationFactor must be created with " + + boost::lexical_cast((int) Measurement::dimension) + + "-dimensional noise model."); + } /** Virtual destructor */ @@ -114,18 +120,18 @@ public: Vector evaluateError(const Point3& point, boost::optional H2 = boost::none) const { try { - Point2 error(camera_.project(point, boost::none, H2, boost::none) - measured_); + Measurement error(camera_.project2(point, boost::none, H2) - measured_); return error.vector(); } catch (CheiralityException& e) { if (H2) - *H2 = zeros(2, 3); + *H2 = zeros(Measurement::dimension, 3); if (verboseCheirality_) std::cout << e.what() << ": Landmark " << DefaultKeyFormatter(this->key()) << " moved behind camera" << std::endl; if (throwCheirality_) throw e; - return ones(2) * 2.0 * camera_.calibration().fx(); + return ones(Measurement::dimension) * 2.0 * camera_.calibration().fx(); } } @@ -147,14 +153,14 @@ public: // Allocate memory for Jacobian factor, do only once if (Ab.rows() == 0) { std::vector dimensions(1, 3); - Ab = VerticalBlockMatrix(dimensions, 2, true); - A.resize(2,3); - b.resize(2); + Ab = VerticalBlockMatrix(dimensions, Measurement::dimension, true); + A.resize(Measurement::dimension,3); + b.resize(Measurement::dimension); } // Would be even better if we could pass blocks to project const Point3& point = x.at(key()); - b = -(camera_.project(point, boost::none, A, boost::none) - measured_).vector(); + b = -(camera_.project2(point, boost::none, A) - measured_).vector(); if (noiseModel_) this->noiseModel_->WhitenSystem(A, b); @@ -165,7 +171,7 @@ public: } /** return the measurement */ - const Point2& measured() const { + const Measurement& measured() const { return measured_; } diff --git a/gtsam/slam/dataset.cpp b/gtsam/slam/dataset.cpp index 5ad1ff2c0..50516afe4 100644 --- a/gtsam/slam/dataset.cpp +++ b/gtsam/slam/dataset.cpp @@ -15,7 +15,7 @@ * @brief utility functions for loading datasets */ -#include +#include #include #include #include @@ -247,6 +247,7 @@ GraphAndValues load2D(const string& filename, SharedNoiseModel model, Key maxID, // Parse the pose constraints Key id1, id2; bool haveLandmark = false; + const bool useModelInFile = !model; while (!is.eof()) { if (!(is >> tag)) break; @@ -267,7 +268,7 @@ GraphAndValues load2D(const string& filename, SharedNoiseModel model, Key maxID, if (maxID && (id1 >= maxID || id2 >= maxID)) continue; - if (!model) + if (useModelInFile) model = modelInFile; if (addNoise) @@ -509,7 +510,7 @@ GraphAndValues load3D(const string& filename) { Key id; double x, y, z, roll, pitch, yaw; ls >> id >> x >> y >> z >> roll >> pitch >> yaw; - Rot3 R = Rot3::ypr(yaw,pitch,roll); + Rot3 R = Rot3::Ypr(yaw,pitch,roll); Point3 t = Point3(x, y, z); initial->insert(id, Pose3(R,t)); } @@ -517,7 +518,7 @@ GraphAndValues load3D(const string& filename) { Key id; double x, y, z, qx, qy, qz, qw; ls >> id >> x >> y >> z >> qx >> qy >> qz >> qw; - Rot3 R = Rot3::quaternion(qw, qx, qy, qz); + Rot3 R = Rot3::Quaternion(qw, qx, qy, qz); Point3 t = Point3(x, y, z); initial->insert(id, Pose3(R,t)); } @@ -536,7 +537,7 @@ GraphAndValues load3D(const string& filename) { Key id1, id2; double x, y, z, roll, pitch, yaw; ls >> id1 >> id2 >> x >> y >> z >> roll >> pitch >> yaw; - Rot3 R = Rot3::ypr(yaw,pitch,roll); + Rot3 R = Rot3::Ypr(yaw,pitch,roll); Point3 t = Point3(x, y, z); Matrix m = eye(6); for (int i = 0; i < 6; i++) @@ -552,7 +553,7 @@ GraphAndValues load3D(const string& filename) { Key id1, id2; double x, y, z, qx, qy, qz, qw; ls >> id1 >> id2 >> x >> y >> z >> qx >> qy >> qz >> qw; - Rot3 R = Rot3::quaternion(qw, qx, qy, qz); + Rot3 R = Rot3::Quaternion(qw, qx, qy, qz); Point3 t = Point3(x, y, z); for (int i = 0; i < 6; i++){ for (int j = i; j < 6; j++){ @@ -720,10 +721,10 @@ bool readBAL(const string& filename, SfM_data &data) { // Get the information for the camera poses for (size_t i = 0; i < nrPoses; i++) { - // Get the rodriguez vector + // Get the Rodrigues vector float wx, wy, wz; is >> wx >> wy >> wz; - Rot3 R = Rot3::rodriguez(wx, wy, wz); // BAL-OpenGL rotation matrix + Rot3 R = Rot3::Rodrigues(wx, wy, wz); // BAL-OpenGL rotation matrix // Get the translation vector float tx, ty, tz; diff --git a/gtsam/slam/expressions.h b/gtsam/slam/expressions.h index b819993ef..e81c76bd6 100644 --- a/gtsam/slam/expressions.h +++ b/gtsam/slam/expressions.h @@ -28,6 +28,7 @@ inline Point2_ transform_to(const Pose2_& x, const Point2_& p) { // 3D Geometry typedef Expression Point3_; +typedef Expression Unit3_; typedef Expression Rot3_; typedef Expression Pose3_; @@ -35,38 +36,61 @@ inline Point3_ transform_to(const Pose3_& x, const Point3_& p) { return Point3_(x, &Pose3::transform_to, p); } +inline Point3_ transform_from(const Pose3_& x, const Point3_& p) { + return Point3_(x, &Pose3::transform_from, p); +} + // Projection typedef Expression Cal3_S2_; typedef Expression Cal3Bundler_; +/// Expression version of PinholeBase::Project inline Point2_ project(const Point3_& p_cam) { - return Point2_(PinholeCamera::project_to_camera, p_cam); + Point2 (*f)(const Point3&, OptionalJacobian<2, 3>) = &PinholeBase::Project; + return Point2_(f, p_cam); } -template -Point2 project4(const CAMERA& camera, const Point3& p, - OptionalJacobian<2, CAMERA::dimension> Dcam, OptionalJacobian<2, 3> Dpoint) { +inline Point2_ project(const Unit3_& p_cam) { + Point2 (*f)(const Unit3&, OptionalJacobian<2, 2>) = &PinholeBase::Project; + return Point2_(f, p_cam); +} + +namespace internal { +// Helper template for project2 expression below +template +Point2 project4(const CAMERA& camera, const POINT& p, + OptionalJacobian<2, CAMERA::dimension> Dcam, + OptionalJacobian<2, FixedDimension::value> Dpoint) { return camera.project2(p, Dcam, Dpoint); } - -template -Point2_ project2(const Expression& camera_, const Point3_& p_) { - return Point2_(project4, camera_, p_); } +template +Point2_ project2(const Expression& camera_, + const Expression& p_) { + return Point2_(internal::project4, camera_, p_); +} + +namespace internal { +// Helper template for project3 expression below +template inline Point2 project6(const Pose3& x, const Point3& p, const Cal3_S2& K, - OptionalJacobian<2, 6> Dpose, OptionalJacobian<2, 3> Dpoint, OptionalJacobian<2, 5> Dcal) { + OptionalJacobian<2, 6> Dpose, OptionalJacobian<2, 3> Dpoint, + OptionalJacobian<2, 5> Dcal) { return PinholeCamera(x, K).project(p, Dpose, Dpoint, Dcal); } - -inline Point2_ project3(const Pose3_& x, const Point3_& p, const Cal3_S2_& K) { - return Point2_(project6, x, p, K); } -template -Point2_ uncalibrate(const Expression& K, const Point2_& xy_hat) { - return Point2_(K, &CAL::uncalibrate, xy_hat); +template +inline Point2_ project3(const Pose3_& x, const Expression& p, + const Expression& K) { + return Point2_(internal::project6, x, p, K); +} + +template +Point2_ uncalibrate(const Expression& K, const Point2_& xy_hat) { + return Point2_(K, &CALIBRATION::uncalibrate, xy_hat); } } // \namespace gtsam diff --git a/gtsam/slam/tests/smartFactorScenarios.h b/gtsam/slam/tests/smartFactorScenarios.h new file mode 100644 index 000000000..ccad83f01 --- /dev/null +++ b/gtsam/slam/tests/smartFactorScenarios.h @@ -0,0 +1,145 @@ +/* ---------------------------------------------------------------------------- + + * 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 SmartFactorScenarios.h + * @brief Scenarios for testSmart*.cpp + * @author Frank Dellaert + * @date Feb 2015 + */ + +#pragma once +#include +#include +#include +#include +#include + +using namespace std; +using namespace gtsam; + +// three landmarks ~5 meters infront of camera +Point3 landmark1(5, 0.5, 1.2); +Point3 landmark2(5, -0.5, 1.2); +Point3 landmark3(3, 0, 3.0); +Point3 landmark4(10, 0.5, 1.2); +Point3 landmark5(10, -0.5, 1.2); + +// First camera pose, looking along X-axis, 1 meter above ground plane (x-y) +Pose3 level_pose = Pose3(Rot3::Ypr(-M_PI / 2, 0., -M_PI / 2), Point3(0, 0, 1)); +// Second camera 1 meter to the right of first camera +Pose3 pose_right = level_pose * Pose3(Rot3(), Point3(1, 0, 0)); +// Third camera 1 meter above the first camera +Pose3 pose_above = level_pose * Pose3(Rot3(), Point3(0, -1, 0)); + +// Create a noise unit2 for the pixel error +static SharedNoiseModel unit2(noiseModel::Unit::Create(2)); + +static double fov = 60; // degrees +static size_t w = 640, h = 480; + +/* ************************************************************************* */ +// default Cal3_S2 cameras +namespace vanilla { +typedef PinholeCamera Camera; +typedef SmartProjectionFactor SmartFactor; +static Cal3_S2 K(fov, w, h); +static Cal3_S2 K2(1500, 1200, 0, w, h); +Camera level_camera(level_pose, K2); +Camera level_camera_right(pose_right, K2); +Point2 level_uv = level_camera.project(landmark1); +Point2 level_uv_right = level_camera_right.project(landmark1); +Camera cam1(level_pose, K2); +Camera cam2(pose_right, K2); +Camera cam3(pose_above, K2); +typedef GeneralSFMFactor SFMFactor; +SmartProjectionParams params; +} + +/* ************************************************************************* */ +// default Cal3_S2 poses +namespace vanillaPose { +typedef PinholePose Camera; +typedef SmartProjectionPoseFactor SmartFactor; +static Cal3_S2::shared_ptr sharedK(new Cal3_S2(fov, w, h)); +Camera level_camera(level_pose, sharedK); +Camera level_camera_right(pose_right, sharedK); +Camera cam1(level_pose, sharedK); +Camera cam2(pose_right, sharedK); +Camera cam3(pose_above, sharedK); +} + +/* ************************************************************************* */ +// default Cal3_S2 poses +namespace vanillaPose2 { +typedef PinholePose Camera; +typedef SmartProjectionPoseFactor SmartFactor; +static Cal3_S2::shared_ptr sharedK2(new Cal3_S2(1500, 1200, 0, 640, 480)); +Camera level_camera(level_pose, sharedK2); +Camera level_camera_right(pose_right, sharedK2); +Camera cam1(level_pose, sharedK2); +Camera cam2(pose_right, sharedK2); +Camera cam3(pose_above, sharedK2); +} + +/* *************************************************************************/ +// Cal3Bundler cameras +namespace bundler { +typedef PinholeCamera Camera; +typedef SmartProjectionFactor SmartFactor; +static Cal3Bundler K(500, 1e-3, 1e-3, 0, 0); +Camera level_camera(level_pose, K); +Camera level_camera_right(pose_right, K); +Point2 level_uv = level_camera.project(landmark1); +Point2 level_uv_right = level_camera_right.project(landmark1); +Pose3 pose1 = level_pose; +Camera cam1(level_pose, K); +Camera cam2(pose_right, K); +Camera cam3(pose_above, K); +typedef GeneralSFMFactor SFMFactor; +} +/* *************************************************************************/ +// Cal3Bundler poses +namespace bundlerPose { +typedef PinholePose Camera; +typedef SmartProjectionPoseFactor SmartFactor; +static boost::shared_ptr sharedBundlerK( + new Cal3Bundler(500, 1e-3, 1e-3, 1000, 2000)); +Camera level_camera(level_pose, sharedBundlerK); +Camera level_camera_right(pose_right, sharedBundlerK); +Camera cam1(level_pose, sharedBundlerK); +Camera cam2(pose_right, sharedBundlerK); +Camera cam3(pose_above, sharedBundlerK); +} +/* *************************************************************************/ + +template +CAMERA perturbCameraPose(const CAMERA& camera) { + Pose3 noise_pose = Pose3(Rot3::Ypr(-M_PI / 10, 0., -M_PI / 10), + Point3(0.5, 0.1, 0.3)); + Pose3 cameraPose = camera.pose(); + Pose3 perturbedCameraPose = cameraPose.compose(noise_pose); + return CAMERA(perturbedCameraPose, camera.calibration()); +} + +template +void projectToMultipleCameras(const CAMERA& cam1, const CAMERA& cam2, + const CAMERA& cam3, Point3 landmark, vector& measurements_cam) { + Point2 cam1_uv1 = cam1.project(landmark); + Point2 cam2_uv1 = cam2.project(landmark); + Point2 cam3_uv1 = cam3.project(landmark); + measurements_cam.push_back(cam1_uv1); + measurements_cam.push_back(cam2_uv1); + measurements_cam.push_back(cam3_uv1); +} + +/* ************************************************************************* */ + diff --git a/gtsam/slam/tests/testBetweenFactor.cpp b/gtsam/slam/tests/testBetweenFactor.cpp index adb759dc0..1e8b330c3 100644 --- a/gtsam/slam/tests/testBetweenFactor.cpp +++ b/gtsam/slam/tests/testBetweenFactor.cpp @@ -19,9 +19,9 @@ using namespace gtsam::noiseModel; * This TEST should fail. If you want it to pass, change noise to 0. */ TEST(BetweenFactor, Rot3) { - Rot3 R1 = Rot3::rodriguez(0.1, 0.2, 0.3); - Rot3 R2 = Rot3::rodriguez(0.4, 0.5, 0.6); - Rot3 noise = Rot3(); // Rot3::rodriguez(0.01, 0.01, 0.01); // Uncomment to make unit test fail + Rot3 R1 = Rot3::Rodrigues(0.1, 0.2, 0.3); + Rot3 R2 = Rot3::Rodrigues(0.4, 0.5, 0.6); + Rot3 noise = Rot3(); // Rot3::Rodrigues(0.01, 0.01, 0.01); // Uncomment to make unit test fail Rot3 measured = R1.between(R2)*noise ; BetweenFactor factor(R(1), R(2), measured, Isotropic::Sigma(3, 0.05)); diff --git a/gtsam/slam/tests/testDataset.cpp b/gtsam/slam/tests/testDataset.cpp index 0406c3d27..4e8e3dbf3 100644 --- a/gtsam/slam/tests/testDataset.cpp +++ b/gtsam/slam/tests/testDataset.cpp @@ -137,23 +137,23 @@ TEST( dataSet, readG2o3D) boost::tie(actualGraph, actualValues) = readG2o(g2oFile, is3D); Values expectedValues; - Rot3 R0 = Rot3::quaternion(1.000000, 0.000000, 0.000000, 0.000000 ); + Rot3 R0 = Rot3::Quaternion(1.000000, 0.000000, 0.000000, 0.000000 ); Point3 p0 = Point3(0.000000, 0.000000, 0.000000); expectedValues.insert(0, Pose3(R0, p0)); - Rot3 R1 = Rot3::quaternion(0.854230, 0.190253, 0.283162, -0.392318 ); + Rot3 R1 = Rot3::Quaternion(0.854230, 0.190253, 0.283162, -0.392318 ); Point3 p1 = Point3(1.001367, 0.015390, 0.004948); expectedValues.insert(1, Pose3(R1, p1)); - Rot3 R2 = Rot3::quaternion(0.421446, -0.351729, -0.597838, 0.584174 ); + Rot3 R2 = Rot3::Quaternion(0.421446, -0.351729, -0.597838, 0.584174 ); Point3 p2 = Point3(1.993500, 0.023275, 0.003793); expectedValues.insert(2, Pose3(R2, p2)); - Rot3 R3 = Rot3::quaternion(0.067024, 0.331798, -0.200659, 0.919323); + Rot3 R3 = Rot3::Quaternion(0.067024, 0.331798, -0.200659, 0.919323); Point3 p3 = Point3(2.004291, 1.024305, 0.018047); expectedValues.insert(3, Pose3(R3, p3)); - Rot3 R4 = Rot3::quaternion(0.765488, -0.035697, -0.462490, 0.445933); + Rot3 R4 = Rot3::Quaternion(0.765488, -0.035697, -0.462490, 0.445933); Point3 p4 = Point3(0.999908, 1.055073, 0.020212); expectedValues.insert(4, Pose3(R4, p4)); @@ -163,27 +163,27 @@ TEST( dataSet, readG2o3D) NonlinearFactorGraph expectedGraph; Point3 p01 = Point3(1.001367, 0.015390, 0.004948); - Rot3 R01 = Rot3::quaternion(0.854230, 0.190253, 0.283162, -0.392318 ); + Rot3 R01 = Rot3::Quaternion(0.854230, 0.190253, 0.283162, -0.392318 ); expectedGraph.add(BetweenFactor(0, 1, Pose3(R01,p01), model)); Point3 p12 = Point3(0.523923, 0.776654, 0.326659); - Rot3 R12 = Rot3::quaternion(0.105373 , 0.311512, 0.656877, -0.678505 ); + Rot3 R12 = Rot3::Quaternion(0.105373 , 0.311512, 0.656877, -0.678505 ); expectedGraph.add(BetweenFactor(1, 2, Pose3(R12,p12), model)); Point3 p23 = Point3(0.910927, 0.055169, -0.411761); - Rot3 R23 = Rot3::quaternion(0.568551 , 0.595795, -0.561677, 0.079353 ); + Rot3 R23 = Rot3::Quaternion(0.568551 , 0.595795, -0.561677, 0.079353 ); expectedGraph.add(BetweenFactor(2, 3, Pose3(R23,p23), model)); Point3 p34 = Point3(0.775288, 0.228798, -0.596923); - Rot3 R34 = Rot3::quaternion(0.542221 , -0.592077, 0.303380, -0.513226 ); + Rot3 R34 = Rot3::Quaternion(0.542221 , -0.592077, 0.303380, -0.513226 ); expectedGraph.add(BetweenFactor(3, 4, Pose3(R34,p34), model)); Point3 p14 = Point3(-0.577841, 0.628016, -0.543592); - Rot3 R14 = Rot3::quaternion(0.327419 , -0.125250, -0.534379, 0.769122 ); + Rot3 R14 = Rot3::Quaternion(0.327419 , -0.125250, -0.534379, 0.769122 ); expectedGraph.add(BetweenFactor(1, 4, Pose3(R14,p14), model)); Point3 p30 = Point3(-0.623267, 0.086928, 0.773222); - Rot3 R30 = Rot3::quaternion(0.083672 , 0.104639, 0.627755, 0.766795 ); + Rot3 R30 = Rot3::Quaternion(0.083672 , 0.104639, 0.627755, 0.766795 ); expectedGraph.add(BetweenFactor(3, 0, Pose3(R30,p30), model)); EXPECT(assert_equal(expectedGraph,*actualGraph,1e-5)); @@ -199,11 +199,11 @@ TEST( dataSet, readG2o3DNonDiagonalNoise) boost::tie(actualGraph, actualValues) = readG2o(g2oFile, is3D); Values expectedValues; - Rot3 R0 = Rot3::quaternion(1.000000, 0.000000, 0.000000, 0.000000 ); + Rot3 R0 = Rot3::Quaternion(1.000000, 0.000000, 0.000000, 0.000000 ); Point3 p0 = Point3(0.000000, 0.000000, 0.000000); expectedValues.insert(0, Pose3(R0, p0)); - Rot3 R1 = Rot3::quaternion(0.854230, 0.190253, 0.283162, -0.392318 ); + Rot3 R1 = Rot3::Quaternion(0.854230, 0.190253, 0.283162, -0.392318 ); Point3 p1 = Point3(1.001367, 0.015390, 0.004948); expectedValues.insert(1, Pose3(R1, p1)); @@ -223,7 +223,7 @@ TEST( dataSet, readG2o3DNonDiagonalNoise) noiseModel::Gaussian::shared_ptr model = noiseModel::Gaussian::Covariance(Info.inverse()); NonlinearFactorGraph expectedGraph; Point3 p01 = Point3(1.001367, 0.015390, 0.004948); - Rot3 R01 = Rot3::quaternion(0.854230, 0.190253, 0.283162, -0.392318 ); + Rot3 R01 = Rot3::Quaternion(0.854230, 0.190253, 0.283162, -0.392318 ); expectedGraph.add(BetweenFactor(0, 1, Pose3(R01,p01), model)); EXPECT(assert_equal(expectedGraph,*actualGraph,1e-2)); @@ -452,7 +452,7 @@ TEST( dataSet, writeBALfromValues_Dubrovnik){ SfM_data readData; readBAL(filenameToRead, readData); - Pose3 poseChange = Pose3(Rot3::ypr(-M_PI/10, 0., -M_PI/10), gtsam::Point3(0.3,0.1,0.3)); + Pose3 poseChange = Pose3(Rot3::Ypr(-M_PI/10, 0., -M_PI/10), gtsam::Point3(0.3,0.1,0.3)); Values value; for(size_t i=0; i < readData.number_cameras(); i++){ // for each camera diff --git a/gtsam/slam/tests/testEssentialMatrixFactor.cpp b/gtsam/slam/tests/testEssentialMatrixFactor.cpp index e0e26ecff..3bcc3eccd 100644 --- a/gtsam/slam/tests/testEssentialMatrixFactor.cpp +++ b/gtsam/slam/tests/testEssentialMatrixFactor.cpp @@ -160,7 +160,7 @@ TEST (EssentialMatrixFactor2, factor) { // Check evaluation Point3 P1 = data.tracks[i].p, P2 = data.cameras[1].pose().transform_to(P1); - const Point2 pi = SimpleCamera::project_to_camera(P2); + const Point2 pi = PinholeBase::Project(P2); Point2 reprojectionError(pi - pB(i)); Vector expected = reprojectionError.vector(); diff --git a/gtsam/slam/tests/testGeneralSFMFactor.cpp b/gtsam/slam/tests/testGeneralSFMFactor.cpp index 240b19a46..a634928dc 100644 --- a/gtsam/slam/tests/testGeneralSFMFactor.cpp +++ b/gtsam/slam/tests/testGeneralSFMFactor.cpp @@ -17,20 +17,22 @@ */ #include -#include +#include #include +#include +#include +#include #include -#include #include #include #include -#include -#include +#include #include +#include #include #include -using namespace boost; +using namespace boost::assign; #include #include @@ -49,7 +51,8 @@ typedef NonlinearEquality Point3Constraint; class Graph: public NonlinearFactorGraph { public: - void addMeasurement(int i, int j, const Point2& z, const SharedNoiseModel& model) { + void addMeasurement(int i, int j, const Point2& z, + const SharedNoiseModel& model) { push_back(boost::make_shared(z, model, X(i), L(j))); } @@ -65,98 +68,99 @@ public: }; -static double getGaussian() -{ - double S,V1,V2; - // Use Box-Muller method to create gauss noise from uniform noise - do - { - double U1 = rand() / (double)(RAND_MAX); - double U2 = rand() / (double)(RAND_MAX); - V1 = 2 * U1 - 1; /* V1=[-1,1] */ - V2 = 2 * U2 - 1; /* V2=[-1,1] */ - S = V1 * V1 + V2 * V2; - } while(S>=1); - return sqrt(-2.0f * (double)log(S) / S) * V1; +static double getGaussian() { + double S, V1, V2; + // Use Box-Muller method to create gauss noise from uniform noise + do { + double U1 = rand() / (double) (RAND_MAX); + double U2 = rand() / (double) (RAND_MAX); + V1 = 2 * U1 - 1; /* V1=[-1,1] */ + V2 = 2 * U2 - 1; /* V2=[-1,1] */ + S = V1 * V1 + V2 * V2; + } while (S >= 1); + return sqrt(-2.f * (double) log(S) / S) * V1; } static const SharedNoiseModel sigma1(noiseModel::Unit::Create(2)); +static const double baseline = 5.; /* ************************************************************************* */ -TEST( GeneralSFMFactor, equals ) -{ - // Create two identical factors and make sure they're equal - Point2 z(323.,240.); - const Symbol cameraFrameNumber('x',1), landmarkNumber('l',1); - const SharedNoiseModel sigma(noiseModel::Unit::Create(1)); - boost::shared_ptr - factor1(new Projection(z, sigma, cameraFrameNumber, landmarkNumber)); +static vector genPoint3() { + const double z = 5; + vector landmarks; + landmarks.push_back(Point3(-1., -1., z)); + landmarks.push_back(Point3(-1., 1., z)); + landmarks.push_back(Point3(1., 1., z)); + landmarks.push_back(Point3(1., -1., z)); + landmarks.push_back(Point3(-1.5, -1.5, 1.5 * z)); + landmarks.push_back(Point3(-1.5, 1.5, 1.5 * z)); + landmarks.push_back(Point3(1.5, 1.5, 1.5 * z)); + landmarks.push_back(Point3(1.5, -1.5, 1.5 * z)); + landmarks.push_back(Point3(-2., -2., 2 * z)); + landmarks.push_back(Point3(-2., 2., 2 * z)); + landmarks.push_back(Point3(2., 2., 2 * z)); + landmarks.push_back(Point3(2., -2., 2 * z)); + return landmarks; +} - boost::shared_ptr - factor2(new Projection(z, sigma, cameraFrameNumber, landmarkNumber)); +static vector genCameraDefaultCalibration() { + vector X; + X.push_back(GeneralCamera(Pose3(eye(3), Point3(-baseline / 2., 0., 0.)))); + X.push_back(GeneralCamera(Pose3(eye(3), Point3(baseline / 2., 0., 0.)))); + return X; +} + +static vector genCameraVariableCalibration() { + const Cal3_S2 K(640, 480, 0.1, 320, 240); + vector X; + X.push_back(GeneralCamera(Pose3(eye(3), Point3(-baseline / 2., 0., 0.)), K)); + X.push_back(GeneralCamera(Pose3(eye(3), Point3(baseline / 2., 0., 0.)), K)); + return X; +} + +static boost::shared_ptr getOrdering( + const vector& cameras, const vector& landmarks) { + boost::shared_ptr ordering(new Ordering); + for (size_t i = 0; i < landmarks.size(); ++i) + ordering->push_back(L(i)); + for (size_t i = 0; i < cameras.size(); ++i) + ordering->push_back(X(i)); + return ordering; +} + +/* ************************************************************************* */ +TEST( GeneralSFMFactor, equals ) { + // Create two identical factors and make sure they're equal + Point2 z(323., 240.); + const Symbol cameraFrameNumber('x', 1), landmarkNumber('l', 1); + const SharedNoiseModel sigma(noiseModel::Unit::Create(1)); + boost::shared_ptr factor1( + new Projection(z, sigma, cameraFrameNumber, landmarkNumber)); + + boost::shared_ptr factor2( + new Projection(z, sigma, cameraFrameNumber, landmarkNumber)); EXPECT(assert_equal(*factor1, *factor2)); } /* ************************************************************************* */ TEST( GeneralSFMFactor, error ) { - Point2 z(3.,0.); - const SharedNoiseModel sigma(noiseModel::Unit::Create(1)); - boost::shared_ptr factor(new Projection(z, sigma, X(1), L(1))); + Point2 z(3., 0.); + const SharedNoiseModel sigma(noiseModel::Unit::Create(2)); + Projection factor(z, sigma, X(1), L(1)); // For the following configuration, the factor predicts 320,240 Values values; Rot3 R; - Point3 t1(0,0,-6); - Pose3 x1(R,t1); + Point3 t1(0, 0, -6); + Pose3 x1(R, t1); values.insert(X(1), GeneralCamera(x1)); - Point3 l1; values.insert(L(1), l1); - EXPECT(assert_equal(((Vector) Vector2(-3.0, 0.0)), factor->unwhitenedError(values))); + Point3 l1; + values.insert(L(1), l1); + EXPECT( + assert_equal(((Vector ) Vector2(-3., 0.)), + factor.unwhitenedError(values))); } -static const double baseline = 5.0 ; - -/* ************************************************************************* */ -static vector genPoint3() { - const double z = 5; - vector landmarks ; - landmarks.push_back(Point3 (-1.0,-1.0, z)); - landmarks.push_back(Point3 (-1.0, 1.0, z)); - landmarks.push_back(Point3 ( 1.0, 1.0, z)); - landmarks.push_back(Point3 ( 1.0,-1.0, z)); - landmarks.push_back(Point3 (-1.5,-1.5, 1.5*z)); - landmarks.push_back(Point3 (-1.5, 1.5, 1.5*z)); - landmarks.push_back(Point3 ( 1.5, 1.5, 1.5*z)); - landmarks.push_back(Point3 ( 1.5,-1.5, 1.5*z)); - landmarks.push_back(Point3 (-2.0,-2.0, 2*z)); - landmarks.push_back(Point3 (-2.0, 2.0, 2*z)); - landmarks.push_back(Point3 ( 2.0, 2.0, 2*z)); - landmarks.push_back(Point3 ( 2.0,-2.0, 2*z)); - return landmarks ; -} - -static vector genCameraDefaultCalibration() { - vector X ; - X.push_back(GeneralCamera(Pose3(eye(3),Point3(-baseline/2.0, 0.0, 0.0)))); - X.push_back(GeneralCamera(Pose3(eye(3),Point3( baseline/2.0, 0.0, 0.0)))); - return X ; -} - -static vector genCameraVariableCalibration() { - const Cal3_S2 K(640,480,0.01,320,240); - vector X ; - X.push_back(GeneralCamera(Pose3(eye(3),Point3(-baseline/2.0, 0.0, 0.0)), K)); - X.push_back(GeneralCamera(Pose3(eye(3),Point3( baseline/2.0, 0.0, 0.0)), K)); - return X ; -} - -static boost::shared_ptr getOrdering(const vector& cameras, const vector& landmarks) { - boost::shared_ptr ordering(new Ordering); - for ( size_t i = 0 ; i < landmarks.size() ; ++i ) ordering->push_back(L(i)) ; - for ( size_t i = 0 ; i < cameras.size() ; ++i ) ordering->push_back(X(i)) ; - return ordering ; -} - - /* ************************************************************************* */ TEST( GeneralSFMFactor, optimize_defaultK ) { @@ -165,32 +169,32 @@ TEST( GeneralSFMFactor, optimize_defaultK ) { // add measurement with noise Graph graph; - for ( size_t j = 0 ; j < cameras.size() ; ++j) { - for ( size_t i = 0 ; i < landmarks.size() ; ++i) { - Point2 pt = cameras[j].project(landmarks[i]) ; + for (size_t j = 0; j < cameras.size(); ++j) { + for (size_t i = 0; i < landmarks.size(); ++i) { + Point2 pt = cameras[j].project(landmarks[i]); graph.addMeasurement(j, i, pt, sigma1); } } - const size_t nMeasurements = cameras.size()*landmarks.size() ; + const size_t nMeasurements = cameras.size() * landmarks.size(); // add initial - const double noise = baseline*0.1; + const double noise = baseline * 0.1; Values values; - for ( size_t i = 0 ; i < cameras.size() ; ++i ) - values.insert(X(i), cameras[i]) ; + for (size_t i = 0; i < cameras.size(); ++i) + values.insert(X(i), cameras[i]); - for ( size_t i = 0 ; i < landmarks.size() ; ++i ) { - Point3 pt(landmarks[i].x()+noise*getGaussian(), - landmarks[i].y()+noise*getGaussian(), - landmarks[i].z()+noise*getGaussian()); - values.insert(L(i), pt) ; + for (size_t i = 0; i < landmarks.size(); ++i) { + Point3 pt(landmarks[i].x() + noise * getGaussian(), + landmarks[i].y() + noise * getGaussian(), + landmarks[i].z() + noise * getGaussian()); + values.insert(L(i), pt); } graph.addCameraConstraint(0, cameras[0]); // Create an ordering of the variables - Ordering ordering = *getOrdering(cameras,landmarks); + Ordering ordering = *getOrdering(cameras, landmarks); LevenbergMarquardtOptimizer optimizer(graph, values, ordering); Values final = optimizer.optimize(); EXPECT(optimizer.error() < 0.5 * 1e-5 * nMeasurements); @@ -202,38 +206,37 @@ TEST( GeneralSFMFactor, optimize_varK_SingleMeasurementError ) { vector cameras = genCameraVariableCalibration(); // add measurement with noise Graph graph; - for ( size_t j = 0 ; j < cameras.size() ; ++j) { - for ( size_t i = 0 ; i < landmarks.size() ; ++i) { - Point2 pt = cameras[j].project(landmarks[i]) ; + for (size_t j = 0; j < cameras.size(); ++j) { + for (size_t i = 0; i < landmarks.size(); ++i) { + Point2 pt = cameras[j].project(landmarks[i]); graph.addMeasurement(j, i, pt, sigma1); } } - const size_t nMeasurements = cameras.size()*landmarks.size() ; + const size_t nMeasurements = cameras.size() * landmarks.size(); // add initial - const double noise = baseline*0.1; + const double noise = baseline * 0.1; Values values; - for ( size_t i = 0 ; i < cameras.size() ; ++i ) - values.insert(X(i), cameras[i]) ; + for (size_t i = 0; i < cameras.size(); ++i) + values.insert(X(i), cameras[i]); // add noise only to the first landmark - for ( size_t i = 0 ; i < landmarks.size() ; ++i ) { - if ( i == 0 ) { - Point3 pt(landmarks[i].x()+noise*getGaussian(), - landmarks[i].y()+noise*getGaussian(), - landmarks[i].z()+noise*getGaussian()); - values.insert(L(i), pt) ; - } - else { - values.insert(L(i), landmarks[i]) ; + for (size_t i = 0; i < landmarks.size(); ++i) { + if (i == 0) { + Point3 pt(landmarks[i].x() + noise * getGaussian(), + landmarks[i].y() + noise * getGaussian(), + landmarks[i].z() + noise * getGaussian()); + values.insert(L(i), pt); + } else { + values.insert(L(i), landmarks[i]); } } graph.addCameraConstraint(0, cameras[0]); const double reproj_error = 1e-5; - Ordering ordering = *getOrdering(cameras,landmarks); + Ordering ordering = *getOrdering(cameras, landmarks); LevenbergMarquardtOptimizer optimizer(graph, values, ordering); Values final = optimizer.optimize(); EXPECT(optimizer.error() < 0.5 * reproj_error * nMeasurements); @@ -246,35 +249,34 @@ TEST( GeneralSFMFactor, optimize_varK_FixCameras ) { vector cameras = genCameraVariableCalibration(); // add measurement with noise - const double noise = baseline*0.1; + const double noise = baseline * 0.1; Graph graph; - for ( size_t j = 0 ; j < cameras.size() ; ++j) { - for ( size_t i = 0 ; i < landmarks.size() ; ++i) { - Point2 pt = cameras[j].project(landmarks[i]) ; - graph.addMeasurement(j, i, pt, sigma1); + for (size_t i = 0; i < cameras.size(); ++i) { + for (size_t j = 0; j < landmarks.size(); ++j) { + Point2 z = cameras[i].project(landmarks[j]); + graph.addMeasurement(i, j, z, sigma1); } } - const size_t nMeasurements = landmarks.size()*cameras.size(); + const size_t nMeasurements = landmarks.size() * cameras.size(); Values values; - for ( size_t i = 0 ; i < cameras.size() ; ++i ) - values.insert(X(i), cameras[i]) ; + for (size_t i = 0; i < cameras.size(); ++i) + values.insert(X(i), cameras[i]); - for ( size_t i = 0 ; i < landmarks.size() ; ++i ) { - Point3 pt(landmarks[i].x()+noise*getGaussian(), - landmarks[i].y()+noise*getGaussian(), - landmarks[i].z()+noise*getGaussian()); - //Point3 pt(landmarks[i].x(), landmarks[i].y(), landmarks[i].z()); - values.insert(L(i), pt) ; + for (size_t j = 0; j < landmarks.size(); ++j) { + Point3 pt(landmarks[j].x() + noise * getGaussian(), + landmarks[j].y() + noise * getGaussian(), + landmarks[j].z() + noise * getGaussian()); + values.insert(L(j), pt); } - for ( size_t i = 0 ; i < cameras.size() ; ++i ) + for (size_t i = 0; i < cameras.size(); ++i) graph.addCameraConstraint(i, cameras[i]); - const double reproj_error = 1e-5 ; + const double reproj_error = 1e-5; - Ordering ordering = *getOrdering(cameras,landmarks); + Ordering ordering = *getOrdering(cameras, landmarks); LevenbergMarquardtOptimizer optimizer(graph, values, ordering); Values final = optimizer.optimize(); EXPECT(optimizer.error() < 0.5 * reproj_error * nMeasurements); @@ -288,50 +290,45 @@ TEST( GeneralSFMFactor, optimize_varK_FixLandmarks ) { // add measurement with noise Graph graph; - for ( size_t j = 0 ; j < cameras.size() ; ++j) { - for ( size_t i = 0 ; i < landmarks.size() ; ++i) { - Point2 pt = cameras[j].project(landmarks[i]) ; + for (size_t j = 0; j < cameras.size(); ++j) { + for (size_t i = 0; i < landmarks.size(); ++i) { + Point2 pt = cameras[j].project(landmarks[i]); graph.addMeasurement(j, i, pt, sigma1); } } - const size_t nMeasurements = landmarks.size()*cameras.size(); + const size_t nMeasurements = landmarks.size() * cameras.size(); Values values; - for ( size_t i = 0 ; i < cameras.size() ; ++i ) { - const double - rot_noise = 1e-5, - trans_noise = 1e-3, - focal_noise = 1, - skew_noise = 1e-5; - if ( i == 0 ) { - values.insert(X(i), cameras[i]) ; - } - else { + for (size_t i = 0; i < cameras.size(); ++i) { + const double rot_noise = 1e-5, trans_noise = 1e-3, focal_noise = 1, + skew_noise = 1e-5; + if (i == 0) { + values.insert(X(i), cameras[i]); + } else { - Vector delta = (Vector(11) << - rot_noise, rot_noise, rot_noise, // rotation - trans_noise, trans_noise, trans_noise, // translation - focal_noise, focal_noise, // f_x, f_y - skew_noise, // s - trans_noise, trans_noise // ux, uy + Vector delta = (Vector(11) << rot_noise, rot_noise, rot_noise, // rotation + trans_noise, trans_noise, trans_noise, // translation + focal_noise, focal_noise, // f_x, f_y + skew_noise, // s + trans_noise, trans_noise // ux, uy ).finished(); - values.insert(X(i), cameras[i].retract(delta)) ; + values.insert(X(i), cameras[i].retract(delta)); } } - for ( size_t i = 0 ; i < landmarks.size() ; ++i ) { - values.insert(L(i), landmarks[i]) ; + for (size_t i = 0; i < landmarks.size(); ++i) { + values.insert(L(i), landmarks[i]); } // fix X0 and all landmarks, allow only the cameras[1] to move graph.addCameraConstraint(0, cameras[0]); - for ( size_t i = 0 ; i < landmarks.size() ; ++i ) + for (size_t i = 0; i < landmarks.size(); ++i) graph.addPoint3Constraint(i, landmarks[i]); - const double reproj_error = 1e-5 ; + const double reproj_error = 1e-5; - Ordering ordering = *getOrdering(cameras,landmarks); + Ordering ordering = *getOrdering(cameras, landmarks); LevenbergMarquardtOptimizer optimizer(graph, values, ordering); Values final = optimizer.optimize(); EXPECT(optimizer.error() < 0.5 * reproj_error * nMeasurements); @@ -344,38 +341,40 @@ TEST( GeneralSFMFactor, optimize_varK_BA ) { // add measurement with noise Graph graph; - for ( size_t j = 0 ; j < cameras.size() ; ++j) { - for ( size_t i = 0 ; i < landmarks.size() ; ++i) { - Point2 pt = cameras[j].project(landmarks[i]) ; + for (size_t j = 0; j < cameras.size(); ++j) { + for (size_t i = 0; i < landmarks.size(); ++i) { + Point2 pt = cameras[j].project(landmarks[i]); graph.addMeasurement(j, i, pt, sigma1); } } - const size_t nMeasurements = cameras.size()*landmarks.size() ; + const size_t nMeasurements = cameras.size() * landmarks.size(); // add initial - const double noise = baseline*0.1; + const double noise = baseline * 0.1; Values values; - for ( size_t i = 0 ; i < cameras.size() ; ++i ) - values.insert(X(i), cameras[i]) ; + for (size_t i = 0; i < cameras.size(); ++i) + values.insert(X(i), cameras[i]); // add noise only to the first landmark - for ( size_t i = 0 ; i < landmarks.size() ; ++i ) { - Point3 pt(landmarks[i].x()+noise*getGaussian(), - landmarks[i].y()+noise*getGaussian(), - landmarks[i].z()+noise*getGaussian()); - values.insert(L(i), pt) ; + for (size_t i = 0; i < landmarks.size(); ++i) { + Point3 pt(landmarks[i].x() + noise * getGaussian(), + landmarks[i].y() + noise * getGaussian(), + landmarks[i].z() + noise * getGaussian()); + values.insert(L(i), pt); } // Constrain position of system with the first camera constrained to the origin graph.addCameraConstraint(0, cameras[0]); // Constrain the scale of the problem with a soft range factor of 1m between the cameras - graph.push_back(RangeFactor(X(0), X(1), 2.0, noiseModel::Isotropic::Sigma(1, 10.0))); + graph.push_back( + RangeFactor(X(0), X(1), 2., + noiseModel::Isotropic::Sigma(1, 10.))); - const double reproj_error = 1e-5 ; + const double reproj_error = 1e-5; - Ordering ordering = *getOrdering(cameras,landmarks); + Ordering ordering = *getOrdering(cameras, landmarks); LevenbergMarquardtOptimizer optimizer(graph, values, ordering); Values final = optimizer.optimize(); EXPECT(optimizer.error() < 0.5 * reproj_error * nMeasurements); @@ -386,17 +385,21 @@ TEST(GeneralSFMFactor, GeneralCameraPoseRange) { // Tests range factor between a GeneralCamera and a Pose3 Graph graph; graph.addCameraConstraint(0, GeneralCamera()); - graph.push_back(RangeFactor(X(0), X(1), 2.0, noiseModel::Isotropic::Sigma(1, 1.0))); - graph.push_back(PriorFactor(X(1), Pose3(Rot3(), Point3(1.0, 0.0, 0.0)), noiseModel::Isotropic::Sigma(6, 1.0))); + graph.push_back( + RangeFactor(X(0), X(1), 2., + noiseModel::Isotropic::Sigma(1, 1.))); + graph.push_back( + PriorFactor(X(1), Pose3(Rot3(), Point3(1., 0., 0.)), + noiseModel::Isotropic::Sigma(6, 1.))); Values init; init.insert(X(0), GeneralCamera()); - init.insert(X(1), Pose3(Rot3(), Point3(1.0,1.0,1.0))); + init.insert(X(1), Pose3(Rot3(), Point3(1., 1., 1.))); // The optimal value between the 2m range factor and 1m prior is 1.5m Values expected; expected.insert(X(0), GeneralCamera()); - expected.insert(X(1), Pose3(Rot3(), Point3(1.5,0.0,0.0))); + expected.insert(X(1), Pose3(Rot3(), Point3(1.5, 0., 0.))); LevenbergMarquardtParams params; params.absoluteErrorTol = 1e-9; @@ -410,16 +413,23 @@ TEST(GeneralSFMFactor, GeneralCameraPoseRange) { TEST(GeneralSFMFactor, CalibratedCameraPoseRange) { // Tests range factor between a CalibratedCamera and a Pose3 NonlinearFactorGraph graph; - graph.push_back(PriorFactor(X(0), CalibratedCamera(), noiseModel::Isotropic::Sigma(6, 1.0))); - graph.push_back(RangeFactor(X(0), X(1), 2.0, noiseModel::Isotropic::Sigma(1, 1.0))); - graph.push_back(PriorFactor(X(1), Pose3(Rot3(), Point3(1.0, 0.0, 0.0)), noiseModel::Isotropic::Sigma(6, 1.0))); + graph.push_back( + PriorFactor(X(0), CalibratedCamera(), + noiseModel::Isotropic::Sigma(6, 1.))); + graph.push_back( + RangeFactor(X(0), X(1), 2., + noiseModel::Isotropic::Sigma(1, 1.))); + graph.push_back( + PriorFactor(X(1), Pose3(Rot3(), Point3(1., 0., 0.)), + noiseModel::Isotropic::Sigma(6, 1.))); Values init; init.insert(X(0), CalibratedCamera()); - init.insert(X(1), Pose3(Rot3(), Point3(1.0,1.0,1.0))); + init.insert(X(1), Pose3(Rot3(), Point3(1., 1., 1.))); Values expected; - expected.insert(X(0), CalibratedCamera(Pose3(Rot3(), Point3(-0.333333333333, 0, 0)))); + expected.insert(X(0), + CalibratedCamera(Pose3(Rot3(), Point3(-0.333333333333, 0, 0)))); expected.insert(X(1), Pose3(Rot3(), Point3(1.333333333333, 0, 0))); LevenbergMarquardtParams params; @@ -431,5 +441,95 @@ TEST(GeneralSFMFactor, CalibratedCameraPoseRange) { } /* ************************************************************************* */ -int main() { TestResult tr; return TestRegistry::runAllTests(tr); } +// Frank created these tests after switching to a custom LinearizedFactor +TEST(GeneralSFMFactor, BinaryJacobianFactor) { + Point2 measurement(3., -1.); + + // Create Values + Values values; + Rot3 R; + Point3 t1(0, 0, -6); + Pose3 x1(R, t1); + values.insert(X(1), GeneralCamera(x1)); + Point3 l1; + values.insert(L(1), l1); + + vector models; + { + // Create various noise-models to test all cases + using namespace noiseModel; + Rot2 R = Rot2::fromAngle(0.3); + Matrix2 cov = R.matrix() * R.matrix().transpose(); + models += SharedNoiseModel(), Unit::Create(2), // + Isotropic::Sigma(2, 0.5), Constrained::All(2), Gaussian::Covariance(cov); + } + + // Now loop over all these noise models + BOOST_FOREACH(SharedNoiseModel model, models) { + Projection factor(measurement, model, X(1), L(1)); + + // Test linearize + GaussianFactor::shared_ptr expected = // + factor.NoiseModelFactor::linearize(values); + GaussianFactor::shared_ptr actual = factor.linearize(values); + EXPECT(assert_equal(*expected, *actual, 1e-9)); + + // Test methods that rely on updateHessian + if (model && !model->isConstrained()) { + // Construct HessianFactor from single JacobianFactor + HessianFactor expectedHessian(*expected), actualHessian(*actual); + EXPECT(assert_equal(expectedHessian, actualHessian, 1e-9)); + + // Convert back + JacobianFactor actualJacobian(actualHessian); + // Note we do not expect the actualJacobian to match *expected + // Just that they have the same information on the variable. + EXPECT( + assert_equal(expected->augmentedInformation(), + actualJacobian.augmentedInformation(), 1e-9)); + + // Construct from GaussianFactorGraph + GaussianFactorGraph gfg1; + gfg1 += expected; + GaussianFactorGraph gfg2; + gfg2 += actual; + HessianFactor hessian1(gfg1), hessian2(gfg2); + EXPECT(assert_equal(hessian1, hessian2, 1e-9)); + } + } +} + +/* ************************************************************************* */ +// Do a thorough test of BinaryJacobianFactor +TEST( GeneralSFMFactor, BinaryJacobianFactor2 ) { + + vector landmarks = genPoint3(); + vector cameras = genCameraVariableCalibration(); + + Values values; + for (size_t i = 0; i < cameras.size(); ++i) + values.insert(X(i), cameras[i]); + for (size_t j = 0; j < landmarks.size(); ++j) + values.insert(L(j), landmarks[j]); + + for (size_t i = 0; i < cameras.size(); ++i) { + for (size_t j = 0; j < landmarks.size(); ++j) { + Point2 z = cameras[i].project(landmarks[j]); + Projection::shared_ptr nonlinear = // + boost::make_shared(z, sigma1, X(i), L(j)); + GaussianFactor::shared_ptr factor = nonlinear->linearize(values); + HessianFactor hessian(*factor); + JacobianFactor jacobian(hessian); + EXPECT( + assert_equal(factor->augmentedInformation(), + jacobian.augmentedInformation(), 1e-9)); + } + } +} + +/* ************************************************************************* */ +int main() { + TestResult tr; + return TestRegistry::runAllTests(tr); +} /* ************************************************************************* */ diff --git a/gtsam/slam/tests/testGeneralSFMFactor_Cal3Bundler.cpp b/gtsam/slam/tests/testGeneralSFMFactor_Cal3Bundler.cpp index df56f5260..a349a4992 100644 --- a/gtsam/slam/tests/testGeneralSFMFactor_Cal3Bundler.cpp +++ b/gtsam/slam/tests/testGeneralSFMFactor_Cal3Bundler.cpp @@ -17,7 +17,7 @@ */ #include -#include +#include #include #include #include @@ -49,7 +49,8 @@ typedef NonlinearEquality Point3Constraint; /* ************************************************************************* */ class Graph: public NonlinearFactorGraph { public: - void addMeasurement(const int& i, const int& j, const Point2& z, const SharedNoiseModel& model) { + void addMeasurement(const int& i, const int& j, const Point2& z, + const SharedNoiseModel& model) { push_back(boost::make_shared(z, model, X(i), L(j))); } @@ -65,97 +66,101 @@ public: }; -static double getGaussian() -{ - double S,V1,V2; - // Use Box-Muller method to create gauss noise from uniform noise - do - { - double U1 = rand() / (double)(RAND_MAX); - double U2 = rand() / (double)(RAND_MAX); - V1 = 2 * U1 - 1; /* V1=[-1,1] */ - V2 = 2 * U2 - 1; /* V2=[-1,1] */ - S = V1 * V1 + V2 * V2; - } while(S>=1); - return sqrt(-2.0f * (double)log(S) / S) * V1; +static double getGaussian() { + double S, V1, V2; + // Use Box-Muller method to create gauss noise from uniform noise + do { + double U1 = rand() / (double) (RAND_MAX); + double U2 = rand() / (double) (RAND_MAX); + V1 = 2 * U1 - 1; /* V1=[-1,1] */ + V2 = 2 * U2 - 1; /* V2=[-1,1] */ + S = V1 * V1 + V2 * V2; + } while (S >= 1); + return sqrt(-2.f * (double) log(S) / S) * V1; } static const SharedNoiseModel sigma1(noiseModel::Unit::Create(2)); /* ************************************************************************* */ -TEST( GeneralSFMFactor_Cal3Bundler, equals ) -{ +TEST( GeneralSFMFactor_Cal3Bundler, equals ) { // Create two identical factors and make sure they're equal - Point2 z(323.,240.); - const Symbol cameraFrameNumber('x',1), landmarkNumber('l',1); + Point2 z(323., 240.); + const Symbol cameraFrameNumber('x', 1), landmarkNumber('l', 1); const SharedNoiseModel sigma(noiseModel::Unit::Create(1)); - boost::shared_ptr - factor1(new Projection(z, sigma, cameraFrameNumber, landmarkNumber)); + boost::shared_ptr factor1( + new Projection(z, sigma, cameraFrameNumber, landmarkNumber)); - boost::shared_ptr - factor2(new Projection(z, sigma, cameraFrameNumber, landmarkNumber)); + boost::shared_ptr factor2( + new Projection(z, sigma, cameraFrameNumber, landmarkNumber)); EXPECT(assert_equal(*factor1, *factor2)); } /* ************************************************************************* */ TEST( GeneralSFMFactor_Cal3Bundler, error ) { - Point2 z(3.,0.); + Point2 z(3., 0.); const SharedNoiseModel sigma(noiseModel::Unit::Create(1)); - boost::shared_ptr - factor(new Projection(z, sigma, X(1), L(1))); + boost::shared_ptr factor(new Projection(z, sigma, X(1), L(1))); // For the following configuration, the factor predicts 320,240 Values values; Rot3 R; - Point3 t1(0,0,-6); - Pose3 x1(R,t1); + Point3 t1(0, 0, -6); + Pose3 x1(R, t1); values.insert(X(1), GeneralCamera(x1)); - Point3 l1; values.insert(L(1), l1); - EXPECT(assert_equal(Vector2(-3.0, 0.0), factor->unwhitenedError(values))); + Point3 l1; + values.insert(L(1), l1); + EXPECT(assert_equal(Vector2(-3., 0.), factor->unwhitenedError(values))); } - -static const double baseline = 5.0 ; +static const double baseline = 5.; /* ************************************************************************* */ static vector genPoint3() { const double z = 5; - vector landmarks ; - landmarks.push_back(Point3 (-1.0,-1.0, z)); - landmarks.push_back(Point3 (-1.0, 1.0, z)); - landmarks.push_back(Point3 ( 1.0, 1.0, z)); - landmarks.push_back(Point3 ( 1.0,-1.0, z)); - landmarks.push_back(Point3 (-1.5,-1.5, 1.5*z)); - landmarks.push_back(Point3 (-1.5, 1.5, 1.5*z)); - landmarks.push_back(Point3 ( 1.5, 1.5, 1.5*z)); - landmarks.push_back(Point3 ( 1.5,-1.5, 1.5*z)); - landmarks.push_back(Point3 (-2.0,-2.0, 2*z)); - landmarks.push_back(Point3 (-2.0, 2.0, 2*z)); - landmarks.push_back(Point3 ( 2.0, 2.0, 2*z)); - landmarks.push_back(Point3 ( 2.0,-2.0, 2*z)); - return landmarks ; + vector landmarks; + landmarks.push_back(Point3(-1., -1., z)); + landmarks.push_back(Point3(-1., 1., z)); + landmarks.push_back(Point3(1., 1., z)); + landmarks.push_back(Point3(1., -1., z)); + landmarks.push_back(Point3(-1.5, -1.5, 1.5 * z)); + landmarks.push_back(Point3(-1.5, 1.5, 1.5 * z)); + landmarks.push_back(Point3(1.5, 1.5, 1.5 * z)); + landmarks.push_back(Point3(1.5, -1.5, 1.5 * z)); + landmarks.push_back(Point3(-2., -2., 2 * z)); + landmarks.push_back(Point3(-2., 2., 2 * z)); + landmarks.push_back(Point3(2., 2., 2 * z)); + landmarks.push_back(Point3(2., -2., 2 * z)); + return landmarks; } static vector genCameraDefaultCalibration() { - vector cameras ; - cameras.push_back(GeneralCamera(Pose3(eye(3),Point3(-baseline/2.0, 0.0, 0.0)))); - cameras.push_back(GeneralCamera(Pose3(eye(3),Point3( baseline/2.0, 0.0, 0.0)))); - return cameras ; + vector cameras; + cameras.push_back( + GeneralCamera(Pose3(Rot3(), Point3(-baseline / 2., 0., 0.)))); + cameras.push_back( + GeneralCamera(Pose3(Rot3(), Point3(baseline / 2., 0., 0.)))); + return cameras; } static vector genCameraVariableCalibration() { - const Cal3Bundler K(500,1e-3,1e-3); - vector cameras ; - cameras.push_back(GeneralCamera(Pose3(eye(3),Point3(-baseline/2.0, 0.0, 0.0)), K)); - cameras.push_back(GeneralCamera(Pose3(eye(3),Point3( baseline/2.0, 0.0, 0.0)), K)); - return cameras ; + const Cal3Bundler K(500, 1e-3, 1e-3); + vector cameras; + cameras.push_back( + GeneralCamera(Pose3(Rot3(), Point3(-baseline / 2., 0., 0.)), K)); + cameras.push_back( + GeneralCamera(Pose3(Rot3(), Point3(baseline / 2., 0., 0.)), K)); + return cameras; } -static boost::shared_ptr getOrdering(const std::vector& cameras, const std::vector& landmarks) { +static boost::shared_ptr getOrdering( + const std::vector& cameras, + const std::vector& landmarks) { boost::shared_ptr ordering(new Ordering); - for ( size_t i = 0 ; i < landmarks.size() ; ++i ) ordering->push_back(L(i)) ; - for ( size_t i = 0 ; i < cameras.size() ; ++i ) ordering->push_back(X(i)) ; - return ordering ; + for (size_t i = 0; i < landmarks.size(); ++i) + ordering->push_back(L(i)); + for (size_t i = 0; i < cameras.size(); ++i) + ordering->push_back(X(i)); + return ordering; } /* ************************************************************************* */ @@ -166,32 +171,32 @@ TEST( GeneralSFMFactor_Cal3Bundler, optimize_defaultK ) { // add measurement with noise Graph graph; - for ( size_t j = 0 ; j < cameras.size() ; ++j) { - for ( size_t i = 0 ; i < landmarks.size() ; ++i) { - Point2 pt = cameras[j].project(landmarks[i]) ; + for (size_t j = 0; j < cameras.size(); ++j) { + for (size_t i = 0; i < landmarks.size(); ++i) { + Point2 pt = cameras[j].project(landmarks[i]); graph.addMeasurement(j, i, pt, sigma1); } } - const size_t nMeasurements = cameras.size()*landmarks.size() ; + const size_t nMeasurements = cameras.size() * landmarks.size(); // add initial - const double noise = baseline*0.1; + const double noise = baseline * 0.1; Values values; - for ( size_t i = 0 ; i < cameras.size() ; ++i ) - values.insert(X(i), cameras[i]) ; + for (size_t i = 0; i < cameras.size(); ++i) + values.insert(X(i), cameras[i]); - for ( size_t i = 0 ; i < landmarks.size() ; ++i ) { - Point3 pt(landmarks[i].x()+noise*getGaussian(), - landmarks[i].y()+noise*getGaussian(), - landmarks[i].z()+noise*getGaussian()); - values.insert(L(i), pt) ; + for (size_t i = 0; i < landmarks.size(); ++i) { + Point3 pt(landmarks[i].x() + noise * getGaussian(), + landmarks[i].y() + noise * getGaussian(), + landmarks[i].z() + noise * getGaussian()); + values.insert(L(i), pt); } graph.addCameraConstraint(0, cameras[0]); // Create an ordering of the variables - Ordering ordering = *getOrdering(cameras,landmarks); + Ordering ordering = *getOrdering(cameras, landmarks); LevenbergMarquardtOptimizer optimizer(graph, values, ordering); Values final = optimizer.optimize(); EXPECT(optimizer.error() < 0.5 * 1e-5 * nMeasurements); @@ -203,38 +208,37 @@ TEST( GeneralSFMFactor_Cal3Bundler, optimize_varK_SingleMeasurementError ) { vector cameras = genCameraVariableCalibration(); // add measurement with noise Graph graph; - for ( size_t j = 0 ; j < cameras.size() ; ++j) { - for ( size_t i = 0 ; i < landmarks.size() ; ++i) { - Point2 pt = cameras[j].project(landmarks[i]) ; + for (size_t j = 0; j < cameras.size(); ++j) { + for (size_t i = 0; i < landmarks.size(); ++i) { + Point2 pt = cameras[j].project(landmarks[i]); graph.addMeasurement(j, i, pt, sigma1); } } - const size_t nMeasurements = cameras.size()*landmarks.size() ; + const size_t nMeasurements = cameras.size() * landmarks.size(); // add initial - const double noise = baseline*0.1; + const double noise = baseline * 0.1; Values values; - for ( size_t i = 0 ; i < cameras.size() ; ++i ) - values.insert(X(i), cameras[i]) ; + for (size_t i = 0; i < cameras.size(); ++i) + values.insert(X(i), cameras[i]); // add noise only to the first landmark - for ( size_t i = 0 ; i < landmarks.size() ; ++i ) { - if ( i == 0 ) { - Point3 pt(landmarks[i].x()+noise*getGaussian(), - landmarks[i].y()+noise*getGaussian(), - landmarks[i].z()+noise*getGaussian()); - values.insert(L(i), pt) ; - } - else { - values.insert(L(i), landmarks[i]) ; + for (size_t i = 0; i < landmarks.size(); ++i) { + if (i == 0) { + Point3 pt(landmarks[i].x() + noise * getGaussian(), + landmarks[i].y() + noise * getGaussian(), + landmarks[i].z() + noise * getGaussian()); + values.insert(L(i), pt); + } else { + values.insert(L(i), landmarks[i]); } } graph.addCameraConstraint(0, cameras[0]); const double reproj_error = 1e-5; - Ordering ordering = *getOrdering(cameras,landmarks); + Ordering ordering = *getOrdering(cameras, landmarks); LevenbergMarquardtOptimizer optimizer(graph, values, ordering); Values final = optimizer.optimize(); EXPECT(optimizer.error() < 0.5 * reproj_error * nMeasurements); @@ -247,35 +251,35 @@ TEST( GeneralSFMFactor_Cal3Bundler, optimize_varK_FixCameras ) { vector cameras = genCameraVariableCalibration(); // add measurement with noise - const double noise = baseline*0.1; + const double noise = baseline * 0.1; Graph graph; - for ( size_t j = 0 ; j < cameras.size() ; ++j) { - for ( size_t i = 0 ; i < landmarks.size() ; ++i) { - Point2 pt = cameras[j].project(landmarks[i]) ; + for (size_t j = 0; j < cameras.size(); ++j) { + for (size_t i = 0; i < landmarks.size(); ++i) { + Point2 pt = cameras[j].project(landmarks[i]); graph.addMeasurement(j, i, pt, sigma1); } } - const size_t nMeasurements = landmarks.size()*cameras.size(); + const size_t nMeasurements = landmarks.size() * cameras.size(); Values values; - for ( size_t i = 0 ; i < cameras.size() ; ++i ) - values.insert(X(i), cameras[i]) ; + for (size_t i = 0; i < cameras.size(); ++i) + values.insert(X(i), cameras[i]); - for ( size_t i = 0 ; i < landmarks.size() ; ++i ) { - Point3 pt(landmarks[i].x()+noise*getGaussian(), - landmarks[i].y()+noise*getGaussian(), - landmarks[i].z()+noise*getGaussian()); + for (size_t i = 0; i < landmarks.size(); ++i) { + Point3 pt(landmarks[i].x() + noise * getGaussian(), + landmarks[i].y() + noise * getGaussian(), + landmarks[i].z() + noise * getGaussian()); //Point3 pt(landmarks[i].x(), landmarks[i].y(), landmarks[i].z()); - values.insert(L(i), pt) ; + values.insert(L(i), pt); } - for ( size_t i = 0 ; i < cameras.size() ; ++i ) + for (size_t i = 0; i < cameras.size(); ++i) graph.addCameraConstraint(i, cameras[i]); - const double reproj_error = 1e-5 ; + const double reproj_error = 1e-5; - Ordering ordering = *getOrdering(cameras,landmarks); + Ordering ordering = *getOrdering(cameras, landmarks); LevenbergMarquardtOptimizer optimizer(graph, values, ordering); Values final = optimizer.optimize(); EXPECT(optimizer.error() < 0.5 * reproj_error * nMeasurements); @@ -289,46 +293,43 @@ TEST( GeneralSFMFactor_Cal3Bundler, optimize_varK_FixLandmarks ) { // add measurement with noise Graph graph; - for ( size_t j = 0 ; j < cameras.size() ; ++j) { - for ( size_t i = 0 ; i < landmarks.size() ; ++i) { - Point2 pt = cameras[j].project(landmarks[i]) ; + for (size_t j = 0; j < cameras.size(); ++j) { + for (size_t i = 0; i < landmarks.size(); ++i) { + Point2 pt = cameras[j].project(landmarks[i]); graph.addMeasurement(j, i, pt, sigma1); } } - const size_t nMeasurements = landmarks.size()*cameras.size(); + const size_t nMeasurements = landmarks.size() * cameras.size(); Values values; - for ( size_t i = 0 ; i < cameras.size() ; ++i ) { - const double - rot_noise = 1e-5, trans_noise = 1e-3, - focal_noise = 1, distort_noise = 1e-3; - if ( i == 0 ) { - values.insert(X(i), cameras[i]) ; - } - else { + for (size_t i = 0; i < cameras.size(); ++i) { + const double rot_noise = 1e-5, trans_noise = 1e-3, focal_noise = 1, + distort_noise = 1e-3; + if (i == 0) { + values.insert(X(i), cameras[i]); + } else { - Vector delta = (Vector(9) << - rot_noise, rot_noise, rot_noise, // rotation - trans_noise, trans_noise, trans_noise, // translation - focal_noise, distort_noise, distort_noise // f, k1, k2 + Vector delta = (Vector(9) << rot_noise, rot_noise, rot_noise, // rotation + trans_noise, trans_noise, trans_noise, // translation + focal_noise, distort_noise, distort_noise // f, k1, k2 ).finished(); - values.insert(X(i), cameras[i].retract(delta)) ; + values.insert(X(i), cameras[i].retract(delta)); } } - for ( size_t i = 0 ; i < landmarks.size() ; ++i ) { - values.insert(L(i), landmarks[i]) ; + for (size_t i = 0; i < landmarks.size(); ++i) { + values.insert(L(i), landmarks[i]); } // fix X0 and all landmarks, allow only the cameras[1] to move graph.addCameraConstraint(0, cameras[0]); - for ( size_t i = 0 ; i < landmarks.size() ; ++i ) + for (size_t i = 0; i < landmarks.size(); ++i) graph.addPoint3Constraint(i, landmarks[i]); - const double reproj_error = 1e-5 ; + const double reproj_error = 1e-5; - Ordering ordering = *getOrdering(cameras,landmarks); + Ordering ordering = *getOrdering(cameras, landmarks); LevenbergMarquardtOptimizer optimizer(graph, values, ordering); Values final = optimizer.optimize(); EXPECT(optimizer.error() < 0.5 * reproj_error * nMeasurements); @@ -341,43 +342,48 @@ TEST( GeneralSFMFactor_Cal3Bundler, optimize_varK_BA ) { // add measurement with noise Graph graph; - for ( size_t j = 0 ; j < cameras.size() ; ++j) { - for ( size_t i = 0 ; i < landmarks.size() ; ++i) { - Point2 pt = cameras[j].project(landmarks[i]) ; + for (size_t j = 0; j < cameras.size(); ++j) { + for (size_t i = 0; i < landmarks.size(); ++i) { + Point2 pt = cameras[j].project(landmarks[i]); graph.addMeasurement(j, i, pt, sigma1); } } - const size_t nMeasurements = cameras.size()*landmarks.size() ; + const size_t nMeasurements = cameras.size() * landmarks.size(); // add initial - const double noise = baseline*0.1; + const double noise = baseline * 0.1; Values values; - for ( size_t i = 0 ; i < cameras.size() ; ++i ) - values.insert(X(i), cameras[i]) ; + for (size_t i = 0; i < cameras.size(); ++i) + values.insert(X(i), cameras[i]); // add noise only to the first landmark - for ( size_t i = 0 ; i < landmarks.size() ; ++i ) { - Point3 pt(landmarks[i].x()+noise*getGaussian(), - landmarks[i].y()+noise*getGaussian(), - landmarks[i].z()+noise*getGaussian()); - values.insert(L(i), pt) ; + for (size_t i = 0; i < landmarks.size(); ++i) { + Point3 pt(landmarks[i].x() + noise * getGaussian(), + landmarks[i].y() + noise * getGaussian(), + landmarks[i].z() + noise * getGaussian()); + values.insert(L(i), pt); } // Constrain position of system with the first camera constrained to the origin graph.addCameraConstraint(0, cameras[0]); // Constrain the scale of the problem with a soft range factor of 1m between the cameras - graph.push_back(RangeFactor(X(0), X(1), 2.0, noiseModel::Isotropic::Sigma(1, 10.0))); + graph.push_back( + RangeFactor(X(0), X(1), 2., + noiseModel::Isotropic::Sigma(1, 10.))); - const double reproj_error = 1e-5 ; + const double reproj_error = 1e-5; - Ordering ordering = *getOrdering(cameras,landmarks); + Ordering ordering = *getOrdering(cameras, landmarks); LevenbergMarquardtOptimizer optimizer(graph, values, ordering); Values final = optimizer.optimize(); EXPECT(optimizer.error() < 0.5 * reproj_error * nMeasurements); } /* ************************************************************************* */ -int main() { TestResult tr; return TestRegistry::runAllTests(tr); } +int main() { + TestResult tr; + return TestRegistry::runAllTests(tr); +} /* ************************************************************************* */ diff --git a/gtsam/slam/tests/testInitializePose3.cpp b/gtsam/slam/tests/testInitializePose3.cpp index 61c4566bf..9fd8474eb 100644 --- a/gtsam/slam/tests/testInitializePose3.cpp +++ b/gtsam/slam/tests/testInitializePose3.cpp @@ -246,7 +246,7 @@ TEST( InitializePose3, initializePoses ) inputGraph->add(PriorFactor(0, Pose3(), priorModel)); Values initial = InitializePose3::initialize(*inputGraph); - EXPECT(assert_equal(*expectedValues,initial,1e-4)); + EXPECT(assert_equal(*expectedValues,initial,0.1)); // TODO(frank): very loose !! } diff --git a/gtsam/slam/tests/testOrientedPlane3Factor.cpp b/gtsam/slam/tests/testOrientedPlane3Factor.cpp index 4a7b4c3fe..f1e830d03 100644 --- a/gtsam/slam/tests/testOrientedPlane3Factor.cpp +++ b/gtsam/slam/tests/testOrientedPlane3Factor.cpp @@ -47,7 +47,7 @@ TEST (OrientedPlane3Factor, lm_translation_error) { // Init pose and prior. Pose Prior is needed since a single plane measurement does not fully constrain the pose Symbol init_sym('x', 0); - Pose3 init_pose(Rot3::ypr(0.0, 0.0, 0.0), Point3(0.0, 0.0, 0.0)); + Pose3 init_pose(Rot3::Ypr(0.0, 0.0, 0.0), Point3(0.0, 0.0, 0.0)); Vector sigmas(6); sigmas << 0.001, 0.001, 0.001, 0.001, 0.001, 0.001; PriorFactor pose_prior(init_sym, init_pose, @@ -94,7 +94,7 @@ TEST (OrientedPlane3Factor, lm_rotation_error) { // Init pose and prior. Pose Prior is needed since a single plane measurement does not fully constrain the pose Symbol init_sym('x', 0); - Pose3 init_pose(Rot3::ypr(0.0, 0.0, 0.0), Point3(0.0, 0.0, 0.0)); + Pose3 init_pose(Rot3::Ypr(0.0, 0.0, 0.0), Point3(0.0, 0.0, 0.0)); PriorFactor pose_prior(init_sym, init_pose, noiseModel::Diagonal::Sigmas( (Vector(6) << 0.001, 0.001, 0.001, 0.001, 0.001, 0.001).finished())); diff --git a/gtsam/slam/tests/testPoseRotationPrior.cpp b/gtsam/slam/tests/testPoseRotationPrior.cpp index db04a74eb..3c7d5f2b2 100644 --- a/gtsam/slam/tests/testPoseRotationPrior.cpp +++ b/gtsam/slam/tests/testPoseRotationPrior.cpp @@ -30,7 +30,7 @@ const gtsam::Key poseKey = 1; // Pose3 examples const Point3 point3A(1.0, 2.0, 3.0), point3B(4.0, 6.0, 8.0); -const Rot3 rot3A, rot3B = Rot3::pitch(-M_PI_2), rot3C = Rot3::Expmap(Vector3(0.1, 0.2, 0.3)); +const Rot3 rot3A, rot3B = Rot3::Pitch(-M_PI_2), rot3C = Rot3::Expmap(Vector3(0.1, 0.2, 0.3)); // Pose2 examples const Point2 point2A(1.0, 2.0), point2B(4.0, 6.0); diff --git a/gtsam/slam/tests/testPoseTranslationPrior.cpp b/gtsam/slam/tests/testPoseTranslationPrior.cpp index 2f39701f7..2fd471c9c 100644 --- a/gtsam/slam/tests/testPoseTranslationPrior.cpp +++ b/gtsam/slam/tests/testPoseTranslationPrior.cpp @@ -27,7 +27,7 @@ const gtsam::Key poseKey = 1; // Pose3 examples const Point3 point3A(1.0, 2.0, 3.0), point3B(4.0, 6.0, 8.0); -const Rot3 rot3A, rot3B = Rot3::pitch(-M_PI_2), rot3C = Rot3::RzRyRx(0.1, 0.2, 0.3); +const Rot3 rot3A, rot3B = Rot3::Pitch(-M_PI_2), rot3C = Rot3::RzRyRx(0.1, 0.2, 0.3); // Pose2 examples const Point2 point2A(1.0, 2.0), point2B(4.0, 6.0); diff --git a/gtsam/slam/tests/testRegularImplicitSchurFactor.cpp b/gtsam/slam/tests/testRegularImplicitSchurFactor.cpp index 8571a345d..77944da83 100644 --- a/gtsam/slam/tests/testRegularImplicitSchurFactor.cpp +++ b/gtsam/slam/tests/testRegularImplicitSchurFactor.cpp @@ -19,11 +19,13 @@ #include #include #include +#include +#include -#include #include #include #include +#include #include #include @@ -39,8 +41,8 @@ using namespace gtsam; const Matrix26 F0 = Matrix26::Ones(); const Matrix26 F1 = 2 * Matrix26::Ones(); const Matrix26 F3 = 3 * Matrix26::Ones(); -const vector > Fblocks = list_of > // - (make_pair(0, F0))(make_pair(1, F1))(make_pair(3, F3)); +const vector FBlocks = list_of(F0)(F1)(F3); +const FastVector keys = list_of(0)(1)(3); // RHS and sigmas const Vector b = (Vector(6) << 1., 2., 3., 4., 5., 6.).finished(); @@ -51,7 +53,7 @@ TEST( regularImplicitSchurFactor, creation ) { E.block<2,2>(0, 0) = eye(2); E.block<2,3>(2, 0) = 2 * ones(2, 3); Matrix3 P = (E.transpose() * E).inverse(); - RegularImplicitSchurFactor<6> expected(Fblocks, E, P, b); + RegularImplicitSchurFactor expected(keys, FBlocks, E, P, b); Matrix expectedP = expected.getPointCovariance(); EXPECT(assert_equal(expectedP, P)); } @@ -84,15 +86,15 @@ TEST( regularImplicitSchurFactor, addHessianMultiply ) { F << F0, zeros(2, d * 3), zeros(2, d), F1, zeros(2, d*2), zeros(2, d * 3), F3; // Calculate expected result F'*alpha*(I - E*P*E')*F*x - FastVector keys; - keys += 0,1,2,3; - Vector x = xvalues.vector(keys); + FastVector keys2; + keys2 += 0,1,2,3; + Vector x = xvalues.vector(keys2); Vector expected = zero(24); - RegularImplicitSchurFactor<6>::multiplyHessianAdd(F, E, P, alpha, x, expected); - EXPECT(assert_equal(expected, yExpected.vector(keys), 1e-8)); + RegularImplicitSchurFactor::multiplyHessianAdd(F, E, P, alpha, x, expected); + EXPECT(assert_equal(expected, yExpected.vector(keys2), 1e-8)); // Create ImplicitSchurFactor - RegularImplicitSchurFactor<6> implicitFactor(Fblocks, E, P, b); + RegularImplicitSchurFactor implicitFactor(keys, FBlocks, E, P, b); VectorValues zero = 0 * yExpected;// quick way to get zero w right structure { // First Version @@ -122,32 +124,34 @@ TEST( regularImplicitSchurFactor, addHessianMultiply ) { // Create JacobianFactor with same error const SharedDiagonal model; - JacobianFactorQ<6, 2> jf(Fblocks, E, P, b, model); + JacobianFactorQ<6, 2> jfQ(keys, FBlocks, E, P, b, model); - { // error - double expectedError = jf.error(xvalues); - double actualError = implicitFactor.errorJF(xvalues); - DOUBLES_EQUAL(expectedError,actualError,1e-7) + // error + double expectedError = 11875.083333333334; + { + EXPECT_DOUBLES_EQUAL(expectedError,jfQ.error(xvalues),1e-7) + EXPECT_DOUBLES_EQUAL(expectedError,implicitFactor.errorJF(xvalues),1e-7) + EXPECT_DOUBLES_EQUAL(11903.500000000007,implicitFactor.error(xvalues),1e-7) } - { // JacobianFactor with same error + { VectorValues yActual = zero; - jf.multiplyHessianAdd(alpha, xvalues, yActual); + jfQ.multiplyHessianAdd(alpha, xvalues, yActual); EXPECT(assert_equal(yExpected, yActual, 1e-8)); - jf.multiplyHessianAdd(alpha, xvalues, yActual); + jfQ.multiplyHessianAdd(alpha, xvalues, yActual); EXPECT(assert_equal(2 * yExpected, yActual, 1e-8)); - jf.multiplyHessianAdd(-1, xvalues, yActual); + jfQ.multiplyHessianAdd(-1, xvalues, yActual); EXPECT(assert_equal(zero, yActual, 1e-8)); } { // check hessian Diagonal - VectorValues diagExpected = jf.hessianDiagonal(); + VectorValues diagExpected = jfQ.hessianDiagonal(); VectorValues diagActual = implicitFactor.hessianDiagonal(); EXPECT(assert_equal(diagExpected, diagActual, 1e-8)); } { // check hessian Block Diagonal - map BD = jf.hessianBlockDiagonal(); + map BD = jfQ.hessianBlockDiagonal(); map actualBD = implicitFactor.hessianBlockDiagonal(); LONGS_EQUAL(3,actualBD.size()); EXPECT(assert_equal(BD[0],actualBD[0])); @@ -157,40 +161,46 @@ TEST( regularImplicitSchurFactor, addHessianMultiply ) { { // Raw memory Version std::fill(y, y + 24, 0);// zero y ! - jf.multiplyHessianAdd(alpha, xdata, y); + jfQ.multiplyHessianAdd(alpha, xdata, y); EXPECT(assert_equal(expected, XMap(y), 1e-8)); - jf.multiplyHessianAdd(alpha, xdata, y); + jfQ.multiplyHessianAdd(alpha, xdata, y); EXPECT(assert_equal(Vector(2 * expected), XMap(y), 1e-8)); - jf.multiplyHessianAdd(-1, xdata, y); + jfQ.multiplyHessianAdd(-1, xdata, y); EXPECT(assert_equal(Vector(0 * expected), XMap(y), 1e-8)); } + VectorValues expectedVV; + expectedVV.insert(0,-3.5*ones(6)); + expectedVV.insert(1,10*ones(6)/3); + expectedVV.insert(3,-19.5*ones(6)); { // Check gradientAtZero - VectorValues expected = jf.gradientAtZero(); VectorValues actual = implicitFactor.gradientAtZero(); - EXPECT(assert_equal(expected, actual, 1e-8)); + EXPECT(assert_equal(expectedVV, jfQ.gradientAtZero(), 1e-8)); + EXPECT(assert_equal(expectedVV, implicitFactor.gradientAtZero(), 1e-8)); } // Create JacobianFactorQR - JacobianFactorQR<6, 2> jfq(Fblocks, E, P, b, model); + JacobianFactorQR<6, 2> jfQR(keys, FBlocks, E, P, b, model); + EXPECT_DOUBLES_EQUAL(expectedError, jfQR.error(xvalues),1e-7) + EXPECT(assert_equal(expectedVV, jfQR.gradientAtZero(), 1e-8)); { const SharedDiagonal model; VectorValues yActual = zero; - jfq.multiplyHessianAdd(alpha, xvalues, yActual); + jfQR.multiplyHessianAdd(alpha, xvalues, yActual); EXPECT(assert_equal(yExpected, yActual, 1e-8)); - jfq.multiplyHessianAdd(alpha, xvalues, yActual); + jfQR.multiplyHessianAdd(alpha, xvalues, yActual); EXPECT(assert_equal(2 * yExpected, yActual, 1e-8)); - jfq.multiplyHessianAdd(-1, xvalues, yActual); + jfQR.multiplyHessianAdd(-1, xvalues, yActual); EXPECT(assert_equal(zero, yActual, 1e-8)); } { // Raw memory Version std::fill(y, y + 24, 0);// zero y ! - jfq.multiplyHessianAdd(alpha, xdata, y); + jfQR.multiplyHessianAdd(alpha, xdata, y); EXPECT(assert_equal(expected, XMap(y), 1e-8)); - jfq.multiplyHessianAdd(alpha, xdata, y); + jfQR.multiplyHessianAdd(alpha, xdata, y); EXPECT(assert_equal(Vector(2 * expected), XMap(y), 1e-8)); - jfq.multiplyHessianAdd(-1, xdata, y); + jfQR.multiplyHessianAdd(-1, xdata, y); EXPECT(assert_equal(Vector(0 * expected), XMap(y), 1e-8)); } delete [] y; @@ -214,7 +224,7 @@ TEST(regularImplicitSchurFactor, hessianDiagonal) E.block<2,3>(2, 0) << 1,2,3,4,5,6; E.block<2,3>(4, 0) << 0.5,1,2,3,4,5; Matrix3 P = (E.transpose() * E).inverse(); - RegularImplicitSchurFactor<6> factor(Fblocks, E, P, b); + RegularImplicitSchurFactor factor(keys, FBlocks, E, P, b); // hessianDiagonal VectorValues expected; @@ -255,6 +265,18 @@ TEST(regularImplicitSchurFactor, hessianDiagonal) EXPECT(assert_equal(F0t*(I2-E0*P*E0.transpose())*F0,actualBD[0])); EXPECT(assert_equal(F1.transpose()*F1-FtE1*P*FtE1.transpose(),actualBD[1])); EXPECT(assert_equal(F3.transpose()*F3-FtE3*P*FtE3.transpose(),actualBD[3])); + + // augmentedInformation (test just checks diagonals) + Matrix actualInfo = factor.augmentedInformation(); + EXPECT(assert_equal(actualBD[0],actualInfo.block<6,6>(0,0))); + EXPECT(assert_equal(actualBD[1],actualInfo.block<6,6>(6,6))); + EXPECT(assert_equal(actualBD[3],actualInfo.block<6,6>(12,12))); + + // information (test just checks diagonals) + Matrix actualInfo2 = factor.information(); + EXPECT(assert_equal(actualBD[0],actualInfo2.block<6,6>(0,0))); + EXPECT(assert_equal(actualBD[1],actualInfo2.block<6,6>(6,6))); + EXPECT(assert_equal(actualBD[3],actualInfo2.block<6,6>(12,12))); } /* ************************************************************************* */ diff --git a/gtsam/slam/tests/testRotateFactor.cpp b/gtsam/slam/tests/testRotateFactor.cpp index 9c99628e6..1283987d4 100644 --- a/gtsam/slam/tests/testRotateFactor.cpp +++ b/gtsam/slam/tests/testRotateFactor.cpp @@ -29,9 +29,9 @@ Rot3 iRc(cameraX, cameraY, cameraZ); // Now, let's create some rotations around IMU frame Unit3 p1(1, 0, 0), p2(0, 1, 0), p3(0, 0, 1); -Rot3 i1Ri2 = Rot3::rodriguez(p1, 1), // -i2Ri3 = Rot3::rodriguez(p2, 1), // -i3Ri4 = Rot3::rodriguez(p3, 1); +Rot3 i1Ri2 = Rot3::AxisAngle(p1, 1), // +i2Ri3 = Rot3::AxisAngle(p2, 1), // +i3Ri4 = Rot3::AxisAngle(p3, 1); // The corresponding rotations in the camera frame Rot3 c1Zc2 = iRc.inverse() * i1Ri2 * iRc, // @@ -47,9 +47,9 @@ typedef noiseModel::Isotropic::shared_ptr Model; //************************************************************************* TEST (RotateFactor, checkMath) { - EXPECT(assert_equal(c1Zc2, Rot3::rodriguez(z1, 1))); - EXPECT(assert_equal(c2Zc3, Rot3::rodriguez(z2, 1))); - EXPECT(assert_equal(c3Zc4, Rot3::rodriguez(z3, 1))); + EXPECT(assert_equal(c1Zc2, Rot3::AxisAngle(z1, 1))); + EXPECT(assert_equal(c2Zc3, Rot3::AxisAngle(z2, 1))); + EXPECT(assert_equal(c3Zc4, Rot3::AxisAngle(z3, 1))); } //************************************************************************* diff --git a/gtsam/slam/tests/testSmartFactorBase.cpp b/gtsam/slam/tests/testSmartFactorBase.cpp index b5ef18842..96052bd0f 100644 --- a/gtsam/slam/tests/testSmartFactorBase.cpp +++ b/gtsam/slam/tests/testSmartFactorBase.cpp @@ -16,17 +16,29 @@ * @date Feb 2015 */ -#include "../SmartFactorBase.h" +#include #include +#include #include using namespace std; using namespace gtsam; +static SharedNoiseModel unit2(noiseModel::Unit::Create(2)); +static SharedNoiseModel unit3(noiseModel::Unit::Create(3)); + /* ************************************************************************* */ #include #include -class PinholeFactor: public SmartFactorBase, 9> { + +namespace gtsam { + +class PinholeFactor: public SmartFactorBase > { +public: + typedef SmartFactorBase > Base; + PinholeFactor() {} + PinholeFactor(const SharedNoiseModel& sharedNoiseModel): Base(sharedNoiseModel) { + } virtual double error(const Values& values) const { return 0.0; } @@ -36,16 +48,29 @@ class PinholeFactor: public SmartFactorBase, 9> { } }; +/// traits +template<> +struct traits : public Testable {}; +} + TEST(SmartFactorBase, Pinhole) { - PinholeFactor f; - f.add(Point2(), 1, SharedNoiseModel()); - f.add(Point2(), 2, SharedNoiseModel()); + PinholeFactor f= PinholeFactor(unit2); + f.add(Point2(), 1); + f.add(Point2(), 2); EXPECT_LONGS_EQUAL(2 * 2, f.dim()); } /* ************************************************************************* */ #include -class StereoFactor: public SmartFactorBase { + +namespace gtsam { + +class StereoFactor: public SmartFactorBase { +public: + typedef SmartFactorBase Base; + StereoFactor() {} + StereoFactor(const SharedNoiseModel& sharedNoiseModel): Base(sharedNoiseModel) { + } virtual double error(const Values& values) const { return 0.0; } @@ -55,13 +80,36 @@ class StereoFactor: public SmartFactorBase { } }; +/// traits +template<> +struct traits : public Testable {}; +} + TEST(SmartFactorBase, Stereo) { - StereoFactor f; - f.add(StereoPoint2(), 1, SharedNoiseModel()); - f.add(StereoPoint2(), 2, SharedNoiseModel()); + StereoFactor f(unit3); + f.add(StereoPoint2(), 1); + f.add(StereoPoint2(), 2); EXPECT_LONGS_EQUAL(2 * 3, f.dim()); } +/* ************************************************************************* */ +BOOST_CLASS_EXPORT_GUID(gtsam::noiseModel::Constrained, "gtsam_noiseModel_Constrained"); +BOOST_CLASS_EXPORT_GUID(gtsam::noiseModel::Diagonal, "gtsam_noiseModel_Diagonal"); +BOOST_CLASS_EXPORT_GUID(gtsam::noiseModel::Gaussian, "gtsam_noiseModel_Gaussian"); +BOOST_CLASS_EXPORT_GUID(gtsam::noiseModel::Unit, "gtsam_noiseModel_Unit"); +BOOST_CLASS_EXPORT_GUID(gtsam::noiseModel::Isotropic, "gtsam_noiseModel_Isotropic"); +BOOST_CLASS_EXPORT_GUID(gtsam::SharedNoiseModel, "gtsam_SharedNoiseModel"); +BOOST_CLASS_EXPORT_GUID(gtsam::SharedDiagonal, "gtsam_SharedDiagonal"); + +TEST(SmartFactorBase, serialize) { + using namespace gtsam::serializationTestHelpers; + PinholeFactor factor(unit2); + + EXPECT(equalsObj(factor)); + EXPECT(equalsXML(factor)); + EXPECT(equalsBinary(factor)); +} + /* ************************************************************************* */ int main() { TestResult tr; diff --git a/gtsam/slam/tests/testSmartProjectionCameraFactor.cpp b/gtsam/slam/tests/testSmartProjectionCameraFactor.cpp new file mode 100644 index 000000000..467aefe91 --- /dev/null +++ b/gtsam/slam/tests/testSmartProjectionCameraFactor.cpp @@ -0,0 +1,873 @@ +/* ---------------------------------------------------------------------------- + + * 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 testSmartProjectionCameraFactor.cpp + * @brief Unit tests for SmartProjectionCameraFactor Class + * @author Chris Beall + * @author Luca Carlone + * @author Zsolt Kira + * @author Frank Dellaert + * @date Sept 2013 + */ + +#include "smartFactorScenarios.h" +#include +#include +#include +#include +#include +#include + +using namespace boost::assign; + +static bool isDebugTest = false; + +// Convenience for named keys +using symbol_shorthand::X; +using symbol_shorthand::L; + +static Key x1(1); +Symbol l1('l', 1), l2('l', 2), l3('l', 3); +Key c1 = 1, c2 = 2, c3 = 3; + +static Point2 measurement1(323.0, 240.0); + +static double rankTol = 1.0; + +template +PinholeCamera perturbCameraPoseAndCalibration( + const PinholeCamera& camera) { + GTSAM_CONCEPT_MANIFOLD_TYPE(CALIBRATION) + Pose3 noise_pose = Pose3(Rot3::Ypr(-M_PI / 10, 0., -M_PI / 10), + Point3(0.5, 0.1, 0.3)); + Pose3 cameraPose = camera.pose(); + Pose3 perturbedCameraPose = cameraPose.compose(noise_pose); + typename gtsam::traits::TangentVector d; + d.setRandom(); + d *= 0.1; + CALIBRATION perturbedCalibration = camera.calibration().retract(d); + return PinholeCamera(perturbedCameraPose, perturbedCalibration); +} + +/* ************************************************************************* */ +TEST( SmartProjectionCameraFactor, perturbCameraPose) { + using namespace vanilla; + Pose3 noise_pose = Pose3(Rot3::Ypr(-M_PI / 10, 0., -M_PI / 10), + Point3(0.5, 0.1, 0.3)); + Pose3 perturbed_level_pose = level_pose.compose(noise_pose); + Camera actualCamera(perturbed_level_pose, K2); + + Camera expectedCamera = perturbCameraPose(level_camera); + CHECK(assert_equal(expectedCamera, actualCamera)); +} + +/* ************************************************************************* */ +TEST( SmartProjectionCameraFactor, Constructor) { + using namespace vanilla; + SmartFactor::shared_ptr factor1(new SmartFactor(unit2)); +} + +/* ************************************************************************* */ +TEST( SmartProjectionCameraFactor, Constructor2) { + using namespace vanilla; + params.setRankTolerance(rankTol); + SmartFactor factor1(unit2, boost::none, params); +} + +/* ************************************************************************* */ +TEST( SmartProjectionCameraFactor, Constructor3) { + using namespace vanilla; + SmartFactor::shared_ptr factor1(new SmartFactor(unit2)); + factor1->add(measurement1, x1); +} + +/* ************************************************************************* */ +TEST( SmartProjectionCameraFactor, Constructor4) { + using namespace vanilla; + params.setRankTolerance(rankTol); + SmartFactor factor1(unit2, boost::none, params); + factor1.add(measurement1, x1); +} + +/* ************************************************************************* */ +TEST( SmartProjectionCameraFactor, Equals ) { + using namespace vanilla; + SmartFactor::shared_ptr factor1(new SmartFactor(unit2)); + factor1->add(measurement1, x1); + + SmartFactor::shared_ptr factor2(new SmartFactor(unit2)); + factor2->add(measurement1, x1); +} + +/* *************************************************************************/ +TEST( SmartProjectionCameraFactor, noiseless ) { + using namespace vanilla; + + Values values; + values.insert(c1, level_camera); + values.insert(c2, level_camera_right); + + SmartFactor::shared_ptr factor1(new SmartFactor(unit2)); + factor1->add(level_uv, c1); + factor1->add(level_uv_right, c2); + + double expectedError = 0.0; + DOUBLES_EQUAL(expectedError, factor1->error(values), 1e-7); + CHECK( + assert_equal(zero(4), + factor1->reprojectionErrorAfterTriangulation(values), 1e-7)); +} + +/* *************************************************************************/ +TEST( SmartProjectionCameraFactor, noisy ) { + + using namespace vanilla; + + // Project one landmark into two cameras and add noise on first + Point2 level_uv = level_camera.project(landmark1) + Point2(0.2, 0.2); + Point2 level_uv_right = level_camera_right.project(landmark1); + + Values values; + values.insert(c1, level_camera); + Camera perturbed_level_camera_right = perturbCameraPose(level_camera_right); + values.insert(c2, perturbed_level_camera_right); + + SmartFactor::shared_ptr factor1(new SmartFactor(unit2)); + factor1->add(level_uv, c1); + factor1->add(level_uv_right, c2); + + // Point is now uninitialized before a triangulation event + EXPECT(!factor1->point()); + + double expectedError = 58640; + double actualError1 = factor1->error(values); + EXPECT_DOUBLES_EQUAL(expectedError, actualError1, 1); + + // Check triangulated point + CHECK(factor1->point()); + EXPECT( + assert_equal(Point3(13.7587, 1.43851, -1.14274), *factor1->point(), 1e-4)); + + // Check whitened errors + Vector expected(4); + expected << -7, 235, 58, -242; + SmartFactor::Cameras cameras1 = factor1->cameras(values); + Point3 point1 = *factor1->point(); + Vector actual = factor1->whitenedError(cameras1, point1); + EXPECT(assert_equal(expected, actual, 1)); + + SmartFactor::shared_ptr factor2(new SmartFactor(unit2)); + vector measurements; + measurements.push_back(level_uv); + measurements.push_back(level_uv_right); + + vector views; + views.push_back(c1); + views.push_back(c2); + + factor2->add(measurements, views); + + double actualError2 = factor2->error(values); + EXPECT_DOUBLES_EQUAL(expectedError, actualError2, 1); +} + +/* *************************************************************************/ +TEST( SmartProjectionCameraFactor, perturbPoseAndOptimize ) { + + using namespace vanilla; + + // Project three landmarks into three cameras + vector measurements_cam1, measurements_cam2, measurements_cam3; + projectToMultipleCameras(cam1, cam2, cam3, landmark1, measurements_cam1); + projectToMultipleCameras(cam1, cam2, cam3, landmark2, measurements_cam2); + projectToMultipleCameras(cam1, cam2, cam3, landmark3, measurements_cam3); + + // Create and fill smartfactors + SmartFactor::shared_ptr smartFactor1(new SmartFactor(unit2)); + SmartFactor::shared_ptr smartFactor2(new SmartFactor(unit2)); + SmartFactor::shared_ptr smartFactor3(new SmartFactor(unit2)); + vector views; + views.push_back(c1); + views.push_back(c2); + views.push_back(c3); + smartFactor1->add(measurements_cam1, views); + smartFactor2->add(measurements_cam2, views); + smartFactor3->add(measurements_cam3, views); + + // Create factor graph and add priors on two cameras + NonlinearFactorGraph graph; + graph.push_back(smartFactor1); + graph.push_back(smartFactor2); + graph.push_back(smartFactor3); + const SharedDiagonal noisePrior = noiseModel::Isotropic::Sigma(6 + 5, 1e-5); + graph.push_back(PriorFactor(c1, cam1, noisePrior)); + graph.push_back(PriorFactor(c2, cam2, noisePrior)); + + // Create initial estimate + Values initial; + initial.insert(c1, cam1); + initial.insert(c2, cam2); + initial.insert(c3, perturbCameraPose(cam3)); + if (isDebugTest) + initial.at(c3).print("Smart: Pose3 before optimization: "); + + // Points are now uninitialized before a triangulation event + EXPECT(!smartFactor1->point()); + EXPECT(!smartFactor2->point()); + EXPECT(!smartFactor3->point()); + + EXPECT_DOUBLES_EQUAL(75711, smartFactor1->error(initial), 1); + EXPECT_DOUBLES_EQUAL(58524, smartFactor2->error(initial), 1); + EXPECT_DOUBLES_EQUAL(77564, smartFactor3->error(initial), 1); + + // Error should trigger this and initialize the points, abort if not so + CHECK(smartFactor1->point()); + CHECK(smartFactor2->point()); + CHECK(smartFactor3->point()); + + EXPECT( + assert_equal(Point3(2.57696, -0.182566, 1.04085), *smartFactor1->point(), + 1e-4)); + EXPECT( + assert_equal(Point3(2.80114, -0.702153, 1.06594), *smartFactor2->point(), + 1e-4)); + EXPECT( + assert_equal(Point3(1.82593, -0.289569, 2.13438), *smartFactor3->point(), + 1e-4)); + + // Check whitened errors + Vector expected(6); + expected << 256, 29, -26, 29, -206, -202; + Point3 point1 = *smartFactor1->point(); + SmartFactor::Cameras cameras1 = smartFactor1->cameras(initial); + Vector reprojectionError = cameras1.reprojectionError(point1, + measurements_cam1); + EXPECT(assert_equal(expected, reprojectionError, 1)); + Vector actual = smartFactor1->whitenedError(cameras1, point1); + EXPECT(assert_equal(expected, actual, 1)); + + // Optimize + LevenbergMarquardtParams lmParams; + if (isDebugTest) { + lmParams.verbosityLM = LevenbergMarquardtParams::TRYLAMBDA; + lmParams.verbosity = NonlinearOptimizerParams::ERROR; + } + LevenbergMarquardtOptimizer optimizer(graph, initial, lmParams); + Values result = optimizer.optimize(); + + EXPECT(assert_equal(landmark1, *smartFactor1->point(), 1e-5)); + EXPECT(assert_equal(landmark2, *smartFactor2->point(), 1e-5)); + EXPECT(assert_equal(landmark3, *smartFactor3->point(), 1e-5)); + + // GaussianFactorGraph::shared_ptr GFG = graph.linearize(initial); + // VectorValues delta = GFG->optimize(); + + if (isDebugTest) + result.at(c3).print("Smart: Pose3 after optimization: "); + EXPECT(assert_equal(cam1, result.at(c1))); + EXPECT(assert_equal(cam2, result.at(c2))); + EXPECT(assert_equal(result.at(c3).pose(), cam3.pose(), 1e-4)); + EXPECT( + assert_equal(result.at(c3).calibration(), cam3.calibration(), 2)); + if (isDebugTest) + tictoc_print_(); +} + +/* *************************************************************************/ +TEST( SmartProjectionCameraFactor, perturbPoseAndOptimizeFromSfM_tracks ) { + + using namespace vanilla; + + // Project three landmarks into three cameras + vector measurements_cam1, measurements_cam2, measurements_cam3; + projectToMultipleCameras(cam1, cam2, cam3, landmark1, measurements_cam1); + projectToMultipleCameras(cam1, cam2, cam3, landmark2, measurements_cam2); + projectToMultipleCameras(cam1, cam2, cam3, landmark3, measurements_cam3); + + vector views; + views.push_back(c1); + views.push_back(c2); + views.push_back(c3); + + SfM_Track track1; + for (size_t i = 0; i < 3; ++i) { + SfM_Measurement measures; + measures.first = i + 1; // cameras are from 1 to 3 + measures.second = measurements_cam1.at(i); + track1.measurements.push_back(measures); + } + SmartFactor::shared_ptr smartFactor1(new SmartFactor(unit2)); + smartFactor1->add(track1); + + SfM_Track track2; + for (size_t i = 0; i < 3; ++i) { + SfM_Measurement measures; + measures.first = i + 1; // cameras are from 1 to 3 + measures.second = measurements_cam2.at(i); + track2.measurements.push_back(measures); + } + SmartFactor::shared_ptr smartFactor2(new SmartFactor(unit2)); + smartFactor2->add(track2); + + SmartFactor::shared_ptr smartFactor3(new SmartFactor(unit2)); + smartFactor3->add(measurements_cam3, views); + + const SharedDiagonal noisePrior = noiseModel::Isotropic::Sigma(6 + 5, 1e-5); + + NonlinearFactorGraph graph; + graph.push_back(smartFactor1); + graph.push_back(smartFactor2); + graph.push_back(smartFactor3); + graph.push_back(PriorFactor(c1, cam1, noisePrior)); + graph.push_back(PriorFactor(c2, cam2, noisePrior)); + + Values values; + values.insert(c1, cam1); + values.insert(c2, cam2); + values.insert(c3, perturbCameraPose(cam3)); + if (isDebugTest) + values.at(c3).print("Smart: Pose3 before optimization: "); + + LevenbergMarquardtParams lmParams; + if (isDebugTest) + lmParams.verbosityLM = LevenbergMarquardtParams::TRYLAMBDA; + if (isDebugTest) + lmParams.verbosity = NonlinearOptimizerParams::ERROR; + + Values result; + LevenbergMarquardtOptimizer optimizer(graph, values, lmParams); + result = optimizer.optimize(); + + // GaussianFactorGraph::shared_ptr GFG = graph.linearize(values); + // VectorValues delta = GFG->optimize(); + + if (isDebugTest) + result.at(c3).print("Smart: Pose3 after optimization: "); + EXPECT(assert_equal(cam1, result.at(c1))); + EXPECT(assert_equal(cam2, result.at(c2))); + EXPECT(assert_equal(result.at(c3).pose(), cam3.pose(), 1e-4)); + EXPECT( + assert_equal(result.at(c3).calibration(), cam3.calibration(), 2)); + if (isDebugTest) + tictoc_print_(); +} + +/* *************************************************************************/ +TEST( SmartProjectionCameraFactor, perturbCamerasAndOptimize ) { + + using namespace vanilla; + + vector measurements_cam1, measurements_cam2, measurements_cam3, + measurements_cam4, measurements_cam5; + + // 1. Project three landmarks into three cameras and triangulate + projectToMultipleCameras(cam1, cam2, cam3, landmark1, measurements_cam1); + projectToMultipleCameras(cam1, cam2, cam3, landmark2, measurements_cam2); + projectToMultipleCameras(cam1, cam2, cam3, landmark3, measurements_cam3); + projectToMultipleCameras(cam1, cam2, cam3, landmark4, measurements_cam4); + projectToMultipleCameras(cam1, cam2, cam3, landmark5, measurements_cam5); + + vector views; + views.push_back(c1); + views.push_back(c2); + views.push_back(c3); + + SmartFactor::shared_ptr smartFactor1(new SmartFactor(unit2)); + smartFactor1->add(measurements_cam1, views); + + SmartFactor::shared_ptr smartFactor2(new SmartFactor(unit2)); + smartFactor2->add(measurements_cam2, views); + + SmartFactor::shared_ptr smartFactor3(new SmartFactor(unit2)); + smartFactor3->add(measurements_cam3, views); + + SmartFactor::shared_ptr smartFactor4(new SmartFactor(unit2)); + smartFactor4->add(measurements_cam4, views); + + SmartFactor::shared_ptr smartFactor5(new SmartFactor(unit2)); + smartFactor5->add(measurements_cam5, views); + + const SharedDiagonal noisePrior = noiseModel::Isotropic::Sigma(6 + 5, 1e-5); + + NonlinearFactorGraph graph; + graph.push_back(smartFactor1); + graph.push_back(smartFactor2); + graph.push_back(smartFactor3); + graph.push_back(smartFactor4); + graph.push_back(smartFactor5); + graph.push_back(PriorFactor(c1, cam1, noisePrior)); + graph.push_back(PriorFactor(c2, cam2, noisePrior)); + + Values values; + values.insert(c1, cam1); + values.insert(c2, cam2); + values.insert(c3, perturbCameraPoseAndCalibration(cam3)); + if (isDebugTest) + values.at(c3).print("Smart: Pose3 before optimization: "); + + LevenbergMarquardtParams lmParams; + lmParams.relativeErrorTol = 1e-8; + lmParams.absoluteErrorTol = 0; + lmParams.maxIterations = 20; + if (isDebugTest) + lmParams.verbosityLM = LevenbergMarquardtParams::TRYLAMBDA; + if (isDebugTest) + lmParams.verbosity = NonlinearOptimizerParams::ERROR; + + Values result; + LevenbergMarquardtOptimizer optimizer(graph, values, lmParams); + result = optimizer.optimize(); + + // GaussianFactorGraph::shared_ptr GFG = graph.linearize(values); + // VectorValues delta = GFG->optimize(); + + if (isDebugTest) + result.at(c3).print("Smart: Pose3 after optimization: "); + EXPECT(assert_equal(cam1, result.at(c1))); + EXPECT(assert_equal(cam2, result.at(c2))); + EXPECT(assert_equal(result.at(c3).pose(), cam3.pose(), 1e-1)); + EXPECT( + assert_equal(result.at(c3).calibration(), cam3.calibration(), 20)); + if (isDebugTest) + tictoc_print_(); +} + +/* *************************************************************************/ +TEST( SmartProjectionCameraFactor, Cal3Bundler ) { + + using namespace bundler; + + vector measurements_cam1, measurements_cam2, measurements_cam3, + measurements_cam4, measurements_cam5; + + // 1. Project three landmarks into three cameras and triangulate + projectToMultipleCameras(cam1, cam2, cam3, landmark1, measurements_cam1); + projectToMultipleCameras(cam1, cam2, cam3, landmark2, measurements_cam2); + projectToMultipleCameras(cam1, cam2, cam3, landmark3, measurements_cam3); + projectToMultipleCameras(cam1, cam2, cam3, landmark4, measurements_cam4); + projectToMultipleCameras(cam1, cam2, cam3, landmark5, measurements_cam5); + + vector views; + views.push_back(c1); + views.push_back(c2); + views.push_back(c3); + + SmartFactor::shared_ptr smartFactor1(new SmartFactor(unit2)); + smartFactor1->add(measurements_cam1, views); + + SmartFactor::shared_ptr smartFactor2(new SmartFactor(unit2)); + smartFactor2->add(measurements_cam2, views); + + SmartFactor::shared_ptr smartFactor3(new SmartFactor(unit2)); + smartFactor3->add(measurements_cam3, views); + + SmartFactor::shared_ptr smartFactor4(new SmartFactor(unit2)); + smartFactor4->add(measurements_cam4, views); + + SmartFactor::shared_ptr smartFactor5(new SmartFactor(unit2)); + smartFactor5->add(measurements_cam5, views); + + const SharedDiagonal noisePrior = noiseModel::Isotropic::Sigma(9, 1e-6); + + NonlinearFactorGraph graph; + graph.push_back(smartFactor1); + graph.push_back(smartFactor2); + graph.push_back(smartFactor3); + graph.push_back(PriorFactor(c1, cam1, noisePrior)); + graph.push_back(PriorFactor(c2, cam2, noisePrior)); + + Values values; + values.insert(c1, cam1); + values.insert(c2, cam2); + // initialize third pose with some noise, we expect it to move back to original pose3 + values.insert(c3, perturbCameraPose(cam3)); + if (isDebugTest) + values.at(c3).print("Smart: Pose3 before optimization: "); + + LevenbergMarquardtParams lmParams; + lmParams.relativeErrorTol = 1e-8; + lmParams.absoluteErrorTol = 0; + lmParams.maxIterations = 20; + if (isDebugTest) + lmParams.verbosityLM = LevenbergMarquardtParams::TRYLAMBDA; + if (isDebugTest) + lmParams.verbosity = NonlinearOptimizerParams::ERROR; + + Values result; + LevenbergMarquardtOptimizer optimizer(graph, values, lmParams); + result = optimizer.optimize(); + + if (isDebugTest) + result.at(c3).print("Smart: Pose3 after optimization: "); + EXPECT(assert_equal(cam1, result.at(c1), 1e-4)); + EXPECT(assert_equal(cam2, result.at(c2), 1e-4)); + EXPECT(assert_equal(result.at(c3).pose(), cam3.pose(), 1e-1)); + EXPECT( + assert_equal(result.at(c3).calibration(), cam3.calibration(), 1)); + if (isDebugTest) + tictoc_print_(); +} + +/* *************************************************************************/ +TEST( SmartProjectionCameraFactor, Cal3Bundler2 ) { + + using namespace bundler; + + vector measurements_cam1, measurements_cam2, measurements_cam3, + measurements_cam4, measurements_cam5; + + // 1. Project three landmarks into three cameras and triangulate + projectToMultipleCameras(cam1, cam2, cam3, landmark1, measurements_cam1); + projectToMultipleCameras(cam1, cam2, cam3, landmark2, measurements_cam2); + projectToMultipleCameras(cam1, cam2, cam3, landmark3, measurements_cam3); + projectToMultipleCameras(cam1, cam2, cam3, landmark4, measurements_cam4); + projectToMultipleCameras(cam1, cam2, cam3, landmark5, measurements_cam5); + + vector views; + views.push_back(c1); + views.push_back(c2); + views.push_back(c3); + + SmartFactor::shared_ptr smartFactor1(new SmartFactor(unit2)); + smartFactor1->add(measurements_cam1, views); + + SmartFactor::shared_ptr smartFactor2(new SmartFactor(unit2)); + smartFactor2->add(measurements_cam2, views); + + SmartFactor::shared_ptr smartFactor3(new SmartFactor(unit2)); + smartFactor3->add(measurements_cam3, views); + + SmartFactor::shared_ptr smartFactor4(new SmartFactor(unit2)); + smartFactor4->add(measurements_cam4, views); + + SmartFactor::shared_ptr smartFactor5(new SmartFactor(unit2)); + smartFactor5->add(measurements_cam5, views); + + const SharedDiagonal noisePrior = noiseModel::Isotropic::Sigma(9, 1e-6); + + NonlinearFactorGraph graph; + graph.push_back(smartFactor1); + graph.push_back(smartFactor2); + graph.push_back(smartFactor3); + graph.push_back(PriorFactor(c1, cam1, noisePrior)); + graph.push_back(PriorFactor(c2, cam2, noisePrior)); + + Values values; + values.insert(c1, cam1); + values.insert(c2, cam2); + // initialize third pose with some noise, we expect it to move back to original pose3 + values.insert(c3, perturbCameraPoseAndCalibration(cam3)); + if (isDebugTest) + values.at(c3).print("Smart: Pose3 before optimization: "); + + LevenbergMarquardtParams lmParams; + lmParams.relativeErrorTol = 1e-8; + lmParams.absoluteErrorTol = 0; + lmParams.maxIterations = 20; + if (isDebugTest) + lmParams.verbosityLM = LevenbergMarquardtParams::TRYLAMBDA; + if (isDebugTest) + lmParams.verbosity = NonlinearOptimizerParams::ERROR; + + Values result; + LevenbergMarquardtOptimizer optimizer(graph, values, lmParams); + result = optimizer.optimize(); + + if (isDebugTest) + result.at(c3).print("Smart: Pose3 after optimization: "); + EXPECT(assert_equal(cam1, result.at(c1), 1e-4)); + EXPECT(assert_equal(cam2, result.at(c2), 1e-4)); + EXPECT(assert_equal(result.at(c3).pose(), cam3.pose(), 1e-1)); + EXPECT( + assert_equal(result.at(c3).calibration(), cam3.calibration(), 2)); + if (isDebugTest) + tictoc_print_(); +} + +/* *************************************************************************/ +TEST( SmartProjectionCameraFactor, noiselessBundler ) { + + using namespace bundler; + Values values; + values.insert(c1, level_camera); + values.insert(c2, level_camera_right); + + SmartFactor::shared_ptr factor1(new SmartFactor(unit2)); + factor1->add(level_uv, c1); + factor1->add(level_uv_right, c2); + + double actualError = factor1->error(values); + + double expectedError = 0.0; + DOUBLES_EQUAL(expectedError, actualError, 1e-3); + + Point3 oldPoint; // this takes the point stored in the factor (we are not interested in this) + if (factor1->point()) + oldPoint = *(factor1->point()); + + Point3 expectedPoint; + if (factor1->point(values)) + expectedPoint = *(factor1->point(values)); + + EXPECT(assert_equal(expectedPoint, landmark1, 1e-3)); +} + +/* *************************************************************************/ +TEST( SmartProjectionCameraFactor, comparisonGeneralSfMFactor ) { + + using namespace bundler; + Values values; + values.insert(c1, level_camera); + values.insert(c2, level_camera_right); + + NonlinearFactorGraph smartGraph; + SmartFactor::shared_ptr factor1(new SmartFactor(unit2)); + factor1->add(level_uv, c1); + factor1->add(level_uv_right, c2); + smartGraph.push_back(factor1); + double expectedError = factor1->error(values); + double expectedErrorGraph = smartGraph.error(values); + Point3 expectedPoint; + if (factor1->point()) + expectedPoint = *(factor1->point()); + // cout << "expectedPoint " << expectedPoint.vector() << endl; + + // COMMENTS: + // 1) triangulation introduces small errors, then for a fair comparison we use expectedPoint as + // value in the generalGrap + NonlinearFactorGraph generalGraph; + SFMFactor sfm1(level_uv, unit2, c1, l1); + SFMFactor sfm2(level_uv_right, unit2, c2, l1); + generalGraph.push_back(sfm1); + generalGraph.push_back(sfm2); + values.insert(l1, expectedPoint); // note: we get rid of possible errors in the triangulation + Vector e1 = sfm1.evaluateError(values.at(c1), values.at(l1)); + Vector e2 = sfm2.evaluateError(values.at(c2), values.at(l1)); + double actualError = 0.5 + * (norm_2(e1) * norm_2(e1) + norm_2(e2) * norm_2(e2)); + double actualErrorGraph = generalGraph.error(values); + + DOUBLES_EQUAL(expectedErrorGraph, actualErrorGraph, 1e-7); + DOUBLES_EQUAL(expectedErrorGraph, expectedError, 1e-7); + DOUBLES_EQUAL(actualErrorGraph, actualError, 1e-7); + DOUBLES_EQUAL(expectedError, actualError, 1e-7); +} + +/* *************************************************************************/ +TEST( SmartProjectionCameraFactor, comparisonGeneralSfMFactor1 ) { + + using namespace bundler; + Values values; + values.insert(c1, level_camera); + values.insert(c2, level_camera_right); + + NonlinearFactorGraph smartGraph; + SmartFactor::shared_ptr factor1(new SmartFactor(unit2)); + factor1->add(level_uv, c1); + factor1->add(level_uv_right, c2); + smartGraph.push_back(factor1); + Matrix expectedHessian = smartGraph.linearize(values)->hessian().first; + Vector expectedInfoVector = smartGraph.linearize(values)->hessian().second; + Point3 expectedPoint; + if (factor1->point()) + expectedPoint = *(factor1->point()); + + // COMMENTS: + // 1) triangulation introduces small errors, then for a fair comparison we use expectedPoint as + // value in the generalGrap + NonlinearFactorGraph generalGraph; + SFMFactor sfm1(level_uv, unit2, c1, l1); + SFMFactor sfm2(level_uv_right, unit2, c2, l1); + generalGraph.push_back(sfm1); + generalGraph.push_back(sfm2); + values.insert(l1, expectedPoint); // note: we get rid of possible errors in the triangulation + Matrix actualFullHessian = generalGraph.linearize(values)->hessian().first; + Matrix actualFullInfoVector = generalGraph.linearize(values)->hessian().second; + Matrix actualHessian = actualFullHessian.block(0, 0, 18, 18) + - actualFullHessian.block(0, 18, 18, 3) + * (actualFullHessian.block(18, 18, 3, 3)).inverse() + * actualFullHessian.block(18, 0, 3, 18); + Vector actualInfoVector = actualFullInfoVector.block(0, 0, 18, 1) + - actualFullHessian.block(0, 18, 18, 3) + * (actualFullHessian.block(18, 18, 3, 3)).inverse() + * actualFullInfoVector.block(18, 0, 3, 1); + + EXPECT(assert_equal(expectedHessian, actualHessian, 1e-7)); + EXPECT(assert_equal(expectedInfoVector, actualInfoVector, 1e-7)); +} + +/* *************************************************************************/ +// Have to think about how to compare multiplyHessianAdd in generalSfMFactor and smartFactors +//TEST( SmartProjectionCameraFactor, comparisonGeneralSfMFactor2 ){ +// +// Values values; +// values.insert(c1, level_camera); +// values.insert(c2, level_camera_right); +// +// NonlinearFactorGraph smartGraph; +// SmartFactor::shared_ptr factor1(new SmartFactor()); +// factor1->add(level_uv, c1, unit2); +// factor1->add(level_uv_right, c2, unit2); +// smartGraph.push_back(factor1); +// GaussianFactorGraph::shared_ptr gfgSmart = smartGraph.linearize(values); +// +// Point3 expectedPoint; +// if(factor1->point()) +// expectedPoint = *(factor1->point()); +// +// // COMMENTS: +// // 1) triangulation introduces small errors, then for a fair comparison we use expectedPoint as +// // value in the generalGrap +// NonlinearFactorGraph generalGraph; +// SFMFactor sfm1(level_uv, unit2, c1, l1); +// SFMFactor sfm2(level_uv_right, unit2, c2, l1); +// generalGraph.push_back(sfm1); +// generalGraph.push_back(sfm2); +// values.insert(l1, expectedPoint); // note: we get rid of possible errors in the triangulation +// GaussianFactorGraph::shared_ptr gfg = generalGraph.linearize(values); +// +// double alpha = 1.0; +// +// VectorValues yExpected, yActual, ytmp; +// VectorValues xtmp = map_list_of +// (c1, (Vec(9) << 0,0,0,0,0,0,0,0,0)) +// (c2, (Vec(9) << 0,0,0,0,0,0,0,0,0)) +// (l1, (Vec(3) << 5.5, 0.5, 1.2)); +// gfg ->multiplyHessianAdd(alpha, xtmp, ytmp); +// +// VectorValues x = map_list_of +// (c1, (Vec(9) << 1,2,3,4,5,6,7,8,9)) +// (c2, (Vec(9) << 11,12,13,14,15,16,17,18,19)) +// (l1, (Vec(3) << 5.5, 0.5, 1.2)); +// +// gfgSmart->multiplyHessianAdd(alpha, ytmp + x, yActual); +// gfg ->multiplyHessianAdd(alpha, x, yExpected); +// +// EXPECT(assert_equal(yActual,yExpected, 1e-7)); +//} +/* *************************************************************************/ +TEST( SmartProjectionCameraFactor, computeImplicitJacobian ) { + + using namespace bundler; + Values values; + values.insert(c1, level_camera); + values.insert(c2, level_camera_right); + + SmartFactor::shared_ptr factor1(new SmartFactor(unit2)); + factor1->add(level_uv, c1); + factor1->add(level_uv_right, c2); + Matrix expectedE; + Vector expectedb; + + CameraSet cameras; + cameras.push_back(level_camera); + cameras.push_back(level_camera_right); + + factor1->error(values); // this is important to have a triangulation of the point + Point3 point; + if (factor1->point()) + point = *(factor1->point()); + vector Fblocks; + factor1->computeJacobians(Fblocks, expectedE, expectedb, cameras, point); + + NonlinearFactorGraph generalGraph; + SFMFactor sfm1(level_uv, unit2, c1, l1); + SFMFactor sfm2(level_uv_right, unit2, c2, l1); + generalGraph.push_back(sfm1); + generalGraph.push_back(sfm2); + values.insert(l1, point); // note: we get rid of possible errors in the triangulation + Matrix actualFullHessian = generalGraph.linearize(values)->hessian().first; + Matrix actualVinv = (actualFullHessian.block(18, 18, 3, 3)).inverse(); + + Matrix3 expectedVinv = factor1->PointCov(expectedE); + EXPECT(assert_equal(expectedVinv, actualVinv, 1e-7)); +} + +/* *************************************************************************/ +TEST( SmartProjectionCameraFactor, implicitJacobianFactor ) { + + using namespace bundler; + + Values values; + values.insert(c1, level_camera); + values.insert(c2, level_camera_right); + double rankTol = 1; + bool useEPI = false; + + // Hessian version + SmartProjectionParams params; + params.setRankTolerance(rankTol); + params.setLinearizationMode(gtsam::HESSIAN); + params.setDegeneracyMode(gtsam::IGNORE_DEGENERACY); + params.setEnableEPI(useEPI); + + SmartFactor::shared_ptr explicitFactor( + new SmartFactor(unit2, boost::none, params)); + explicitFactor->add(level_uv, c1); + explicitFactor->add(level_uv_right, c2); + + GaussianFactor::shared_ptr gaussianHessianFactor = explicitFactor->linearize( + values); + HessianFactor& hessianFactor = + dynamic_cast(*gaussianHessianFactor); + + // Implicit Schur version + params.setLinearizationMode(gtsam::IMPLICIT_SCHUR); + SmartFactor::shared_ptr implicitFactor( + new SmartFactor(unit2, boost::none, params)); + implicitFactor->add(level_uv, c1); + implicitFactor->add(level_uv_right, c2); + GaussianFactor::shared_ptr gaussianImplicitSchurFactor = + implicitFactor->linearize(values); + CHECK(gaussianImplicitSchurFactor); + typedef RegularImplicitSchurFactor Implicit9; + Implicit9& implicitSchurFactor = + dynamic_cast(*gaussianImplicitSchurFactor); + + VectorValues x = map_list_of(c1, + (Vector(9) << 1, 2, 3, 4, 5, 6, 7, 8, 9).finished())(c2, + (Vector(9) << 11, 12, 13, 14, 15, 16, 17, 18, 19).finished()); + + VectorValues yExpected, yActual; + double alpha = 1.0; + hessianFactor.multiplyHessianAdd(alpha, x, yActual); + implicitSchurFactor.multiplyHessianAdd(alpha, x, yExpected); + EXPECT(assert_equal(yActual, yExpected, 1e-7)); +} + + +/* ************************************************************************* */ +BOOST_CLASS_EXPORT_GUID(gtsam::noiseModel::Constrained, "gtsam_noiseModel_Constrained"); +BOOST_CLASS_EXPORT_GUID(gtsam::noiseModel::Diagonal, "gtsam_noiseModel_Diagonal"); +BOOST_CLASS_EXPORT_GUID(gtsam::noiseModel::Gaussian, "gtsam_noiseModel_Gaussian"); +BOOST_CLASS_EXPORT_GUID(gtsam::noiseModel::Unit, "gtsam_noiseModel_Unit"); +BOOST_CLASS_EXPORT_GUID(gtsam::noiseModel::Isotropic, "gtsam_noiseModel_Isotropic"); +BOOST_CLASS_EXPORT_GUID(gtsam::SharedNoiseModel, "gtsam_SharedNoiseModel"); +BOOST_CLASS_EXPORT_GUID(gtsam::SharedDiagonal, "gtsam_SharedDiagonal"); + +TEST( SmartProjectionCameraFactor, serialize) { + using namespace vanilla; + using namespace gtsam::serializationTestHelpers; + SmartFactor factor(unit2); + + EXPECT(equalsObj(factor)); + EXPECT(equalsXML(factor)); + EXPECT(equalsBinary(factor)); +} + +/* ************************************************************************* */ +int main() { + TestResult tr; + return TestRegistry::runAllTests(tr); +} +/* ************************************************************************* */ + diff --git a/gtsam/slam/tests/testSmartProjectionPoseFactor.cpp b/gtsam/slam/tests/testSmartProjectionPoseFactor.cpp index 07c49008d..1c1bc3c03 100644 --- a/gtsam/slam/tests/testSmartProjectionPoseFactor.cpp +++ b/gtsam/slam/tests/testSmartProjectionPoseFactor.cpp @@ -15,39 +15,26 @@ * @author Chris Beall * @author Luca Carlone * @author Zsolt Kira + * @author Frank Dellaert * @date Sept 2013 */ -#include "../SmartProjectionPoseFactor.h" - -#include +#include "smartFactorScenarios.h" #include +#include #include #include +#include #include -#include +#include #include -using namespace std; using namespace boost::assign; -using namespace gtsam; -static bool isDebugTest = false; - -// make a realistic calibration matrix -static double fov = 60; // degrees -static size_t w = 640, h = 480; - -static Cal3_S2::shared_ptr K(new Cal3_S2(fov, w, h)); -static Cal3_S2::shared_ptr K2(new Cal3_S2(1500, 1200, 0, 640, 480)); -static boost::shared_ptr Kbundler( - new Cal3Bundler(500, 1e-3, 1e-3, 1000, 2000)); - -static double rankTol = 1.0; -static double linThreshold = -1.0; -static bool manageDegeneracy = true; +static const double rankTol = 1.0; // Create a noise model for the pixel error -static SharedNoiseModel model(noiseModel::Isotropic::Sigma(2, 0.1)); +static const double sigma = 0.1; +static SharedIsotropic model(noiseModel::Isotropic::Sigma(2, sigma)); // Convenience for named keys using symbol_shorthand::X; @@ -58,94 +45,70 @@ static Symbol x1('X', 1); static Symbol x2('X', 2); static Symbol x3('X', 3); -static Key poseKey1(x1); static Point2 measurement1(323.0, 240.0); -static Pose3 body_P_sensor1(Rot3::RzRyRx(-M_PI_2, 0.0, -M_PI_2), - Point3(0.25, -0.10, 1.0)); -typedef SmartProjectionPoseFactor SmartFactor; -typedef SmartProjectionPoseFactor SmartFactorBundler; - -void projectToMultipleCameras(SimpleCamera cam1, SimpleCamera cam2, - SimpleCamera cam3, Point3 landmark, vector& measurements_cam) { - - Point2 cam1_uv1 = cam1.project(landmark); - Point2 cam2_uv1 = cam2.project(landmark); - Point2 cam3_uv1 = cam3.project(landmark); - measurements_cam.push_back(cam1_uv1); - measurements_cam.push_back(cam2_uv1); - measurements_cam.push_back(cam3_uv1); -} +LevenbergMarquardtParams lmParams; +// Make more verbose like so (in tests): +// params.verbosityLM = LevenbergMarquardtParams::SUMMARY; /* ************************************************************************* */ TEST( SmartProjectionPoseFactor, Constructor) { - SmartFactor::shared_ptr factor1(new SmartFactor()); + using namespace vanillaPose; + SmartFactor::shared_ptr factor1(new SmartFactor(model, sharedK)); } /* ************************************************************************* */ TEST( SmartProjectionPoseFactor, Constructor2) { - SmartFactor factor1(rankTol, linThreshold); + using namespace vanillaPose; + SmartProjectionParams params; + params.setRankTolerance(rankTol); + SmartFactor factor1(model, sharedK, boost::none, params); } /* ************************************************************************* */ TEST( SmartProjectionPoseFactor, Constructor3) { - SmartFactor::shared_ptr factor1(new SmartFactor()); - factor1->add(measurement1, poseKey1, model, K); + using namespace vanillaPose; + SmartFactor::shared_ptr factor1(new SmartFactor(model, sharedK)); + factor1->add(measurement1, x1); } /* ************************************************************************* */ TEST( SmartProjectionPoseFactor, Constructor4) { - SmartFactor factor1(rankTol, linThreshold); - factor1.add(measurement1, poseKey1, model, K); -} - -/* ************************************************************************* */ -TEST( SmartProjectionPoseFactor, ConstructorWithTransform) { - bool manageDegeneracy = true; - bool enableEPI = false; - SmartFactor factor1(rankTol, linThreshold, manageDegeneracy, enableEPI, - body_P_sensor1); - factor1.add(measurement1, poseKey1, model, K); + using namespace vanillaPose; + SmartProjectionParams params; + params.setRankTolerance(rankTol); + SmartFactor factor1(model, sharedK, boost::none, params); + factor1.add(measurement1, x1); } /* ************************************************************************* */ TEST( SmartProjectionPoseFactor, Equals ) { - SmartFactor::shared_ptr factor1(new SmartFactor()); - factor1->add(measurement1, poseKey1, model, K); + using namespace vanillaPose; + SmartFactor::shared_ptr factor1(new SmartFactor(model, sharedK)); + factor1->add(measurement1, x1); - SmartFactor::shared_ptr factor2(new SmartFactor()); - factor2->add(measurement1, poseKey1, model, K); + SmartFactor::shared_ptr factor2(new SmartFactor(model,sharedK)); + factor2->add(measurement1, x1); CHECK(assert_equal(*factor1, *factor2)); } /* *************************************************************************/ -TEST_UNSAFE( SmartProjectionPoseFactor, noiseless ) { - // cout << " ************************ SmartProjectionPoseFactor: noisy ****************************" << endl; +TEST( SmartProjectionPoseFactor, noiseless ) { - // create first camera. Looking along X-axis, 1 meter above ground plane (x-y) - Pose3 level_pose = Pose3(Rot3::ypr(-M_PI / 2, 0., -M_PI / 2), - Point3(0, 0, 1)); - SimpleCamera level_camera(level_pose, *K2); - - // create second camera 1 meter to the right of first camera - Pose3 level_pose_right = level_pose * Pose3(Rot3(), Point3(1, 0, 0)); - SimpleCamera level_camera_right(level_pose_right, *K2); - - // landmark ~5 meters infront of camera - Point3 landmark(5, 0.5, 1.2); + using namespace vanillaPose; // Project two landmarks into two cameras - Point2 level_uv = level_camera.project(landmark); - Point2 level_uv_right = level_camera_right.project(landmark); + Point2 level_uv = level_camera.project(landmark1); + Point2 level_uv_right = level_camera_right.project(landmark1); - Values values; - values.insert(x1, level_pose); - values.insert(x2, level_pose_right); + SmartFactor factor(model, sharedK); + factor.add(level_uv, x1); + factor.add(level_uv_right, x2); - SmartFactor factor; - factor.add(level_uv, x1, model, K); - factor.add(level_uv_right, x2, model, K); + Values values; // it's a pose factor, hence these are poses + values.insert(x1, cam1.pose()); + values.insert(x2, cam2.pose()); double actualError = factor.error(values); double expectedError = 0.0; @@ -155,192 +118,94 @@ TEST_UNSAFE( SmartProjectionPoseFactor, noiseless ) { double actualError2 = factor.totalReprojectionError(cameras); EXPECT_DOUBLES_EQUAL(expectedError, actualError2, 1e-7); - // test vector of errors - //Vector actual = factor.unwhitenedError(values); - //EXPECT(assert_equal(zero(4),actual,1e-8)); - - // Check derivatives - // Calculate expected derivative for point (easiest to check) boost::function f = // - boost::bind(&SmartFactor::whitenedError, factor, cameras, _1); - boost::optional point = factor.point(); - CHECK(point); - Matrix expectedE = numericalDerivative11(f, *point); + boost::bind(&SmartFactor::whitenedError, factor, cameras, _1); // Calculate using computeEP - Matrix actualE, PointCov; - factor.computeEP(actualE, PointCov, cameras); + Matrix actualE; + factor.triangulateAndComputeE(actualE, values); + + // get point + boost::optional point = factor.point(); + CHECK(point); + + // calculate numerical derivative with triangulated point + Matrix expectedE = sigma * numericalDerivative11(f, *point); EXPECT(assert_equal(expectedE, actualE, 1e-7)); - // Calculate using whitenedError - Matrix F, actualE2; - Vector actualErrors = factor.whitenedError(cameras, *point, F, actualE2); - EXPECT(assert_equal(expectedE, actualE2, 1e-7)); - EXPECT(assert_equal(f(*point), actualErrors, 1e-7)); + // Calculate using reprojectionError + SmartFactor::Cameras::FBlocks F; + Matrix E; + Vector actualErrors = factor.unwhitenedError(cameras, *point, F, E); + EXPECT(assert_equal(expectedE, E, 1e-7)); + + EXPECT(assert_equal(zero(4), actualErrors, 1e-7)); + + // Calculate using computeJacobians + Vector b; + vector Fblocks; + factor.computeJacobians(Fblocks, E, b, cameras, *point); + double actualError3 = b.squaredNorm(); + EXPECT(assert_equal(expectedE, E, 1e-7)); + EXPECT_DOUBLES_EQUAL(expectedError, actualError3, 1e-8); } /* *************************************************************************/ TEST( SmartProjectionPoseFactor, noisy ) { - // cout << " ************************ SmartProjectionPoseFactor: noisy ****************************" << endl; - // create first camera. Looking along X-axis, 1 meter above ground plane (x-y) - Pose3 level_pose = Pose3(Rot3::ypr(-M_PI / 2, 0., -M_PI / 2), - Point3(0, 0, 1)); - SimpleCamera level_camera(level_pose, *K2); + using namespace vanillaPose; - // create second camera 1 meter to the right of first camera - Pose3 level_pose_right = level_pose * Pose3(Rot3(), Point3(1, 0, 0)); - SimpleCamera level_camera_right(level_pose_right, *K2); - - // landmark ~5 meters infront of camera - Point3 landmark(5, 0.5, 1.2); - - // 1. Project two landmarks into two cameras and triangulate + // Project two landmarks into two cameras Point2 pixelError(0.2, 0.2); - Point2 level_uv = level_camera.project(landmark) + pixelError; - Point2 level_uv_right = level_camera_right.project(landmark); + Point2 level_uv = level_camera.project(landmark1) + pixelError; + Point2 level_uv_right = level_camera_right.project(landmark1); Values values; - values.insert(x1, level_pose); - Pose3 noise_pose = Pose3(Rot3::ypr(-M_PI / 10, 0., -M_PI / 10), + values.insert(x1, cam1.pose()); + Pose3 noise_pose = Pose3(Rot3::Ypr(-M_PI / 10, 0., -M_PI / 10), Point3(0.5, 0.1, 0.3)); - values.insert(x2, level_pose_right.compose(noise_pose)); + values.insert(x2, pose_right.compose(noise_pose)); - SmartFactor::shared_ptr factor(new SmartFactor()); - factor->add(level_uv, x1, model, K); - factor->add(level_uv_right, x2, model, K); + SmartFactor::shared_ptr factor(new SmartFactor(model, sharedK)); + factor->add(level_uv, x1); + factor->add(level_uv_right, x2); double actualError1 = factor->error(values); - SmartFactor::shared_ptr factor2(new SmartFactor()); + SmartFactor::shared_ptr factor2(new SmartFactor(model, sharedK)); vector measurements; measurements.push_back(level_uv); measurements.push_back(level_uv_right); - vector noises; - noises.push_back(model); - noises.push_back(model); - - vector > Ks; ///< shared pointer to calibration object (one for each camera) - Ks.push_back(K); - Ks.push_back(K); - vector views; views.push_back(x1); views.push_back(x2); - factor2->add(measurements, views, noises, Ks); - + factor2->add(measurements, views); double actualError2 = factor2->error(values); - DOUBLES_EQUAL(actualError1, actualError2, 1e-7); } /* *************************************************************************/ -TEST( SmartProjectionPoseFactor, 3poses_smart_projection_factor ) { - // cout << " ************************ SmartProjectionPoseFactor: 3 cams + 3 landmarks **********************" << endl; +TEST( SmartProjectionPoseFactor, smartFactorWithSensorBodyTransform ){ + // make a realistic calibration matrix + double fov = 60; // degrees + size_t w=640,h=480; + + Cal3_S2::shared_ptr K(new Cal3_S2(fov,w,h)); // create first camera. Looking along X-axis, 1 meter above ground plane (x-y) - Pose3 pose1 = Pose3(Rot3::ypr(-M_PI / 2, 0., -M_PI / 2), Point3(0, 0, 1)); - SimpleCamera cam1(pose1, *K2); - - // create second camera 1 meter to the right of first camera - Pose3 pose2 = pose1 * Pose3(Rot3(), Point3(1, 0, 0)); - SimpleCamera cam2(pose2, *K2); - - // create third camera 1 meter above the first camera - Pose3 pose3 = pose1 * Pose3(Rot3(), Point3(0, -1, 0)); - SimpleCamera cam3(pose3, *K2); - - // three landmarks ~5 meters infront of camera - Point3 landmark1(5, 0.5, 1.2); - Point3 landmark2(5, -0.5, 1.2); - Point3 landmark3(3, 0, 3.0); - - vector measurements_cam1, measurements_cam2, measurements_cam3; - - // 1. Project three landmarks into three cameras and triangulate - projectToMultipleCameras(cam1, cam2, cam3, landmark1, measurements_cam1); - projectToMultipleCameras(cam1, cam2, cam3, landmark2, measurements_cam2); - projectToMultipleCameras(cam1, cam2, cam3, landmark3, measurements_cam3); - - vector views; - views.push_back(x1); - views.push_back(x2); - views.push_back(x3); - - SmartFactor::shared_ptr smartFactor1(new SmartFactor()); - smartFactor1->add(measurements_cam1, views, model, K2); - - SmartFactor::shared_ptr smartFactor2(new SmartFactor()); - smartFactor2->add(measurements_cam2, views, model, K2); - - SmartFactor::shared_ptr smartFactor3(new SmartFactor()); - smartFactor3->add(measurements_cam3, views, model, K2); - - const SharedDiagonal noisePrior = noiseModel::Isotropic::Sigma(6, 0.10); - - NonlinearFactorGraph graph; - graph.push_back(smartFactor1); - graph.push_back(smartFactor2); - graph.push_back(smartFactor3); - graph.push_back(PriorFactor(x1, pose1, noisePrior)); - graph.push_back(PriorFactor(x2, pose2, noisePrior)); - - // Pose3 noise_pose = Pose3(Rot3::ypr(-M_PI/10, 0., -M_PI/10), Point3(0.5,0.1,0.3)); // noise from regular projection factor test below - Pose3 noise_pose = Pose3(Rot3::ypr(-M_PI / 100, 0., -M_PI / 100), - Point3(0.1, 0.1, 0.1)); // smaller noise - Values values; - values.insert(x1, pose1); - values.insert(x2, pose2); - // initialize third pose with some noise, we expect it to move back to original pose3 - values.insert(x3, pose3 * noise_pose); - EXPECT( - assert_equal( - Pose3( - Rot3(0, -0.0314107591, 0.99950656, -0.99950656, -0.0313952598, - -0.000986635786, 0.0314107591, -0.999013364, -0.0313952598), - Point3(0.1, -0.1, 1.9)), values.at(x3))); - - LevenbergMarquardtParams params; - if (isDebugTest) - params.verbosityLM = LevenbergMarquardtParams::TRYLAMBDA; - if (isDebugTest) - params.verbosity = NonlinearOptimizerParams::ERROR; - - Values result; - gttic_(SmartProjectionPoseFactor); - LevenbergMarquardtOptimizer optimizer(graph, values, params); - result = optimizer.optimize(); - gttoc_(SmartProjectionPoseFactor); - tictoc_finishedIteration_(); - -// GaussianFactorGraph::shared_ptr GFG = graph.linearize(values); -// VectorValues delta = GFG->optimize(); - - // result.print("results of 3 camera, 3 landmark optimization \n"); - EXPECT(assert_equal(pose3, result.at(x3), 1e-8)); - if (isDebugTest) - tictoc_print_(); -} - -/* *************************************************************************/ -TEST( SmartProjectionPoseFactor, smartFactorWithSensorBodyTransform ) { - - // create first camera. Looking along X-axis, 1 meter above ground plane (x-y) - Pose3 cameraPose1 = Pose3(Rot3::ypr(-M_PI / 2, 0., -M_PI / 2), - Point3(0, 0, 1)); // body poses - Pose3 cameraPose2 = cameraPose1 * Pose3(Rot3(), Point3(1, 0, 0)); - Pose3 cameraPose3 = cameraPose1 * Pose3(Rot3(), Point3(0, -1, 0)); + Pose3 cameraPose1 = Pose3(Rot3::Ypr(-M_PI/2, 0., -M_PI/2), gtsam::Point3(0,0,1)); // body poses + Pose3 cameraPose2 = cameraPose1 * Pose3(Rot3(), Point3(1,0,0)); + Pose3 cameraPose3 = cameraPose1 * Pose3(Rot3(), Point3(0,-1,0)); SimpleCamera cam1(cameraPose1, *K); // with camera poses SimpleCamera cam2(cameraPose2, *K); SimpleCamera cam3(cameraPose3, *K); // create arbitrary body_Pose_sensor (transforms from sensor to body) - Pose3 sensor_to_body = Pose3(Rot3::ypr(-M_PI / 2, 0., -M_PI / 2), - Point3(1, 1, 1)); // Pose3(); // + Pose3 sensor_to_body = Pose3(Rot3::Ypr(-M_PI/2, 0., -M_PI/2), gtsam::Point3(1, 1, 1)); // Pose3(); // // These are the poses we want to estimate, from camera measurements Pose3 bodyPose1 = cameraPose1.compose(sensor_to_body.inverse()); @@ -360,30 +225,24 @@ TEST( SmartProjectionPoseFactor, smartFactorWithSensorBodyTransform ) { projectToMultipleCameras(cam1, cam2, cam3, landmark3, measurements_cam3); // Create smart factors - vector views; + std::vector views; views.push_back(x1); views.push_back(x2); views.push_back(x3); - double rankTol = 1; - double linThreshold = -1; - bool manageDegeneracy = false; - bool enableEPI = false; + SmartProjectionParams params; + params.setRankTolerance(1.0); + params.setDegeneracyMode(gtsam::IGNORE_DEGENERACY); + params.setEnableEPI(false); - SmartFactor::shared_ptr smartFactor1( - new SmartFactor(rankTol, linThreshold, manageDegeneracy, enableEPI, - sensor_to_body)); - smartFactor1->add(measurements_cam1, views, model, K); + SmartProjectionPoseFactor smartFactor1(model, K, sensor_to_body, params); + smartFactor1.add(measurements_cam1, views); - SmartFactor::shared_ptr smartFactor2( - new SmartFactor(rankTol, linThreshold, manageDegeneracy, enableEPI, - sensor_to_body)); - smartFactor2->add(measurements_cam2, views, model, K); + SmartProjectionPoseFactor smartFactor2(model, K, sensor_to_body, params); + smartFactor2.add(measurements_cam2, views); - SmartFactor::shared_ptr smartFactor3( - new SmartFactor(rankTol, linThreshold, manageDegeneracy, enableEPI, - sensor_to_body)); - smartFactor3->add(measurements_cam3, views, model, K); + SmartProjectionPoseFactor smartFactor3(model, K, sensor_to_body, params); + smartFactor3.add(measurements_cam3, views); const SharedDiagonal noisePrior = noiseModel::Isotropic::Sigma(6, 0.10); @@ -404,56 +263,91 @@ TEST( SmartProjectionPoseFactor, smartFactorWithSensorBodyTransform ) { double expectedError = 0.0; DOUBLES_EQUAL(expectedError, actualError, 1e-7) - Pose3 noise_pose = Pose3(Rot3::ypr(-M_PI / 100, 0., -M_PI / 100), - Point3(0.1, 0.1, 0.1)); + Pose3 noise_pose = Pose3(Rot3::Ypr(-M_PI/100, 0., -M_PI/100), gtsam::Point3(0.1,0.1,0.1)); Values values; values.insert(x1, bodyPose1); values.insert(x2, bodyPose2); // initialize third pose with some noise, we expect it to move back to original pose3 - values.insert(x3, bodyPose3 * noise_pose); + values.insert(x3, bodyPose3*noise_pose); - LevenbergMarquardtParams params; + LevenbergMarquardtParams lmParams; Values result; - LevenbergMarquardtOptimizer optimizer(graph, values, params); + LevenbergMarquardtOptimizer optimizer(graph, values, lmParams); result = optimizer.optimize(); + EXPECT(assert_equal(bodyPose3,result.at(x3))); +} - // result.print("results of 3 camera, 3 landmark optimization \n"); - EXPECT(assert_equal(bodyPose3, result.at(x3))); +/* *************************************************************************/ +TEST( SmartProjectionPoseFactor, 3poses_smart_projection_factor ) { - // Check derivatives + using namespace vanillaPose2; + vector measurements_cam1, measurements_cam2, measurements_cam3; - // Calculate expected derivative for point (easiest to check) - SmartFactor::Cameras cameras = smartFactor1->cameras(values); - boost::function f = // - boost::bind(&SmartFactor::whitenedError, *smartFactor1, cameras, _1); - boost::optional point = smartFactor1->point(); - CHECK(point); - Matrix expectedE = numericalDerivative11(f, *point); + // Project three landmarks into three cameras + projectToMultipleCameras(cam1, cam2, cam3, landmark1, measurements_cam1); + projectToMultipleCameras(cam1, cam2, cam3, landmark2, measurements_cam2); + projectToMultipleCameras(cam1, cam2, cam3, landmark3, measurements_cam3); - // Calculate using computeEP - Matrix actualE, PointCov; - smartFactor1->computeEP(actualE, PointCov, cameras); - EXPECT(assert_equal(expectedE, actualE, 1e-7)); + vector views; + views.push_back(x1); + views.push_back(x2); + views.push_back(x3); - // Calculate using whitenedError - Matrix F, actualE2; - Vector actualErrors = smartFactor1->whitenedError(cameras, *point, F, - actualE2); - EXPECT(assert_equal(expectedE, actualE2, 1e-7)); + SmartFactor::shared_ptr smartFactor1(new SmartFactor(model, sharedK2)); + smartFactor1->add(measurements_cam1, views); - // TODO the derivatives agree with f, but returned errors are -f :-( - // TODO We should merge the two whitenedErrors functions and make derivatives optional - EXPECT(assert_equal(-f(*point), actualErrors, 1e-7)); + SmartFactor::shared_ptr smartFactor2(new SmartFactor(model, sharedK2)); + smartFactor2->add(measurements_cam2, views); + + SmartFactor::shared_ptr smartFactor3(new SmartFactor(model, sharedK2)); + smartFactor3->add(measurements_cam3, views); + + const SharedDiagonal noisePrior = noiseModel::Isotropic::Sigma(6, 0.10); + + NonlinearFactorGraph graph; + graph.push_back(smartFactor1); + graph.push_back(smartFactor2); + graph.push_back(smartFactor3); + graph.push_back(PriorFactor(x1, cam1.pose(), noisePrior)); + graph.push_back(PriorFactor(x2, cam2.pose(), noisePrior)); + + Values groundTruth; + groundTruth.insert(x1, cam1.pose()); + groundTruth.insert(x2, cam2.pose()); + groundTruth.insert(x3, cam3.pose()); + DOUBLES_EQUAL(0, graph.error(groundTruth), 1e-9); + + // Pose3 noise_pose = Pose3(Rot3::Ypr(-M_PI/10, 0., -M_PI/10), Point3(0.5,0.1,0.3)); // noise from regular projection factor test below + Pose3 noise_pose = Pose3(Rot3::Ypr(-M_PI / 100, 0., -M_PI / 100), + Point3(0.1, 0.1, 0.1)); // smaller noise + Values values; + values.insert(x1, cam1.pose()); + values.insert(x2, cam2.pose()); + // initialize third pose with some noise, we expect it to move back to original pose_above + values.insert(x3, pose_above * noise_pose); + EXPECT( + assert_equal( + Pose3( + Rot3(0, -0.0314107591, 0.99950656, -0.99950656, -0.0313952598, + -0.000986635786, 0.0314107591, -0.999013364, -0.0313952598), + Point3(0.1, -0.1, 1.9)), values.at(x3))); + + Values result; + LevenbergMarquardtOptimizer optimizer(graph, values, lmParams); + result = optimizer.optimize(); + EXPECT(assert_equal(pose_above, result.at(x3), 1e-8)); } /* *************************************************************************/ TEST( SmartProjectionPoseFactor, Factors ) { + using namespace vanillaPose; + // Default cameras for simple derivatives Rot3 R; - static Cal3_S2::shared_ptr K(new Cal3_S2(100, 100, 0, 0, 0)); - SimpleCamera cam1(Pose3(R, Point3(0, 0, 0)), *K), cam2( - Pose3(R, Point3(1, 0, 0)), *K); + static Cal3_S2::shared_ptr sharedK(new Cal3_S2(100, 100, 0, 0, 0)); + Camera cam1(Pose3(R, Point3(0, 0, 0)), sharedK), cam2( + Pose3(R, Point3(1, 0, 0)), sharedK); // one landmarks 1m in front of camera Point3 landmark1(0, 0, 10); @@ -465,29 +359,44 @@ TEST( SmartProjectionPoseFactor, Factors ) { measurements_cam1.push_back(cam2.project(landmark1)); // Create smart factors - std::vector views; + vector views; views.push_back(x1); views.push_back(x2); - SmartFactor::shared_ptr smartFactor1 = boost::make_shared(); - smartFactor1->add(measurements_cam1, views, model, K); + SmartFactor::shared_ptr smartFactor1 = boost::make_shared(model, sharedK); + smartFactor1->add(measurements_cam1, views); SmartFactor::Cameras cameras; cameras.push_back(cam1); cameras.push_back(cam2); // Make sure triangulation works - LONGS_EQUAL(2, smartFactor1->triangulateSafe(cameras)); + CHECK(smartFactor1->triangulateSafe(cameras)); CHECK(!smartFactor1->isDegenerate()); CHECK(!smartFactor1->isPointBehindCamera()); boost::optional p = smartFactor1->point(); CHECK(p); EXPECT(assert_equal(landmark1, *p)); + VectorValues zeroDelta; + Vector6 delta; + delta.setZero(); + zeroDelta.insert(x1, delta); + zeroDelta.insert(x2, delta); + + VectorValues perturbedDelta; + delta.setOnes(); + perturbedDelta.insert(x1, delta); + perturbedDelta.insert(x2, delta); + double expectedError = 2500; + // After eliminating the point, A1 and A2 contain 2-rank information on cameras: Matrix16 A1, A2; - A1 << -1000, 0, 0, 0, 100, 0; - A2 << 1000, 0, 100, 0, -100, 0; + A1 << -10, 0, 0, 0, 1, 0; + A2 << 10, 0, 1, 0, -1, 0; + A1 *= 10. / sigma; + A2 *= 10. / sigma; + Matrix expectedInformation; // filled below { // createHessianFactor Matrix66 G11 = 0.5 * A1.transpose() * A1; @@ -502,11 +411,14 @@ TEST( SmartProjectionPoseFactor, Factors ) { double f = 0; RegularHessianFactor<6> expected(x1, x2, G11, G12, g1, G22, g2, f); + expectedInformation = expected.information(); boost::shared_ptr > actual = smartFactor1->createHessianFactor(cameras, 0.0); - CHECK(assert_equal(expected.information(), actual->information(), 1e-8)); - CHECK(assert_equal(expected, *actual, 1e-8)); + EXPECT(assert_equal(expectedInformation, actual->information(), 1e-8)); + EXPECT(assert_equal(expected, *actual, 1e-8)); + EXPECT_DOUBLES_EQUAL(0, actual->error(zeroDelta), 1e-8); + EXPECT_DOUBLES_EQUAL(expectedError, actual->error(perturbedDelta), 1e-8); } { @@ -524,91 +436,99 @@ TEST( SmartProjectionPoseFactor, Factors ) { F2(1, 0) = 100; F2(1, 2) = 10; F2(1, 4) = -10; - Matrix43 E; + Matrix E(4, 3); E.setZero(); - E(0, 0) = 100; - E(1, 1) = 100; - E(2, 0) = 100; - E(2, 2) = 10; - E(3, 1) = 100; - const vector > Fblocks = list_of > // - (make_pair(x1, 10 * F1))(make_pair(x2, 10 * F2)); - Matrix3 P = (E.transpose() * E).inverse(); - Vector4 b; + E(0, 0) = 10; + E(1, 1) = 10; + E(2, 0) = 10; + E(2, 2) = 1; + E(3, 1) = 10; + vector Fblocks = list_of(F1)(F2); + Vector b(4); b.setZero(); - // createRegularImplicitSchurFactor - RegularImplicitSchurFactor<6> expected(Fblocks, E, P, b); - - boost::shared_ptr > actual = - smartFactor1->createRegularImplicitSchurFactor(cameras, 0.0); - CHECK(actual); - CHECK(assert_equal(expected, *actual)); + // Create smart factors + FastVector keys; + keys.push_back(x1); + keys.push_back(x2); // createJacobianQFactor - JacobianFactorQ<6, 2> expectedQ(Fblocks, E, P, b); + SharedIsotropic n = noiseModel::Isotropic::Sigma(4, sigma); + Matrix3 P = (E.transpose() * E).inverse(); + JacobianFactorQ<6, 2> expectedQ(keys, Fblocks, E, P, b, n); + EXPECT(assert_equal(expectedInformation, expectedQ.information(), 1e-8)); boost::shared_ptr > actualQ = smartFactor1->createJacobianQFactor(cameras, 0.0); + CHECK(actualQ); + EXPECT(assert_equal(expectedInformation, actualQ->information(), 1e-8)); + EXPECT(assert_equal(expectedQ, *actualQ)); + EXPECT_DOUBLES_EQUAL(0, actualQ->error(zeroDelta), 1e-8); + EXPECT_DOUBLES_EQUAL(expectedError, actualQ->error(perturbedDelta), 1e-8); + + // Whiten for RegularImplicitSchurFactor (does not have noise model) + model->WhitenSystem(E, b); + Matrix3 whiteP = (E.transpose() * E).inverse(); + Fblocks[0] = model->Whiten(Fblocks[0]); + Fblocks[1] = model->Whiten(Fblocks[1]); + + // createRegularImplicitSchurFactor + RegularImplicitSchurFactor expected(keys, Fblocks, E, whiteP, b); + + boost::shared_ptr > actual = + smartFactor1->createRegularImplicitSchurFactor(cameras, 0.0); CHECK(actual); - CHECK(assert_equal(expectedQ, *actualQ)); + EXPECT(assert_equal(expectedInformation, expected.information(), 1e-8)); + EXPECT(assert_equal(expectedInformation, actual->information(), 1e-8)); + EXPECT(assert_equal(expected, *actual)); + EXPECT_DOUBLES_EQUAL(0, actual->error(zeroDelta), 1e-8); + EXPECT_DOUBLES_EQUAL(expectedError, actual->error(perturbedDelta), 1e-8); } { // createJacobianSVDFactor Vector1 b; b.setZero(); - double s = sin(M_PI_4); - JacobianFactor expected(x1, s * A1, x2, s * A2, b); + double s = sigma * sin(M_PI_4); + SharedIsotropic n = noiseModel::Isotropic::Sigma(4 - 3, sigma); + JacobianFactor expected(x1, s * A1, x2, s * A2, b, n); + EXPECT(assert_equal(expectedInformation, expected.information(), 1e-8)); boost::shared_ptr actual = smartFactor1->createJacobianSVDFactor(cameras, 0.0); CHECK(actual); - CHECK(assert_equal(expected, *actual)); + EXPECT(assert_equal(expectedInformation, actual->information(), 1e-8)); + EXPECT(assert_equal(expected, *actual)); + EXPECT_DOUBLES_EQUAL(0, actual->error(zeroDelta), 1e-8); + EXPECT_DOUBLES_EQUAL(expectedError, actual->error(perturbedDelta), 1e-8); } } /* *************************************************************************/ TEST( SmartProjectionPoseFactor, 3poses_iterative_smart_projection_factor ) { - // cout << " ************************ SmartProjectionPoseFactor: 3 cams + 3 landmarks **********************" << endl; + + using namespace vanillaPose; vector views; views.push_back(x1); views.push_back(x2); views.push_back(x3); - // create first camera. Looking along X-axis, 1 meter above ground plane (x-y) - Pose3 pose1 = Pose3(Rot3::ypr(-M_PI / 2, 0., -M_PI / 2), Point3(0, 0, 1)); - SimpleCamera cam1(pose1, *K); - - // create second camera 1 meter to the right of first camera - Pose3 pose2 = pose1 * Pose3(Rot3(), Point3(1, 0, 0)); - SimpleCamera cam2(pose2, *K); - - // create third camera 1 meter above the first camera - Pose3 pose3 = pose1 * Pose3(Rot3(), Point3(0, -1, 0)); - SimpleCamera cam3(pose3, *K); - - // three landmarks ~5 meters infront of camera - Point3 landmark1(5, 0.5, 1.2); - Point3 landmark2(5, -0.5, 1.2); - Point3 landmark3(3, 0, 3.0); - vector measurements_cam1, measurements_cam2, measurements_cam3; - // 1. Project three landmarks into three cameras and triangulate + // Project three landmarks into three cameras projectToMultipleCameras(cam1, cam2, cam3, landmark1, measurements_cam1); projectToMultipleCameras(cam1, cam2, cam3, landmark2, measurements_cam2); projectToMultipleCameras(cam1, cam2, cam3, landmark3, measurements_cam3); - SmartFactor::shared_ptr smartFactor1(new SmartFactor()); - smartFactor1->add(measurements_cam1, views, model, K); + SmartFactor::shared_ptr smartFactor1(new SmartFactor(model, sharedK)); + smartFactor1->add(measurements_cam1, views); - SmartFactor::shared_ptr smartFactor2(new SmartFactor()); - smartFactor2->add(measurements_cam2, views, model, K); + SmartFactor::shared_ptr smartFactor2(new SmartFactor(model, sharedK)); + smartFactor2->add(measurements_cam2, views); - SmartFactor::shared_ptr smartFactor3(new SmartFactor()); - smartFactor3->add(measurements_cam3, views, model, K); + SmartFactor::shared_ptr smartFactor3(new SmartFactor(model, sharedK)); + smartFactor3->add(measurements_cam3, views); const SharedDiagonal noisePrior = noiseModel::Isotropic::Sigma(6, 0.10); @@ -616,17 +536,17 @@ TEST( SmartProjectionPoseFactor, 3poses_iterative_smart_projection_factor ) { graph.push_back(smartFactor1); graph.push_back(smartFactor2); graph.push_back(smartFactor3); - graph.push_back(PriorFactor(x1, pose1, noisePrior)); - graph.push_back(PriorFactor(x2, pose2, noisePrior)); + graph.push_back(PriorFactor(x1, cam1.pose(), noisePrior)); + graph.push_back(PriorFactor(x2, cam2.pose(), noisePrior)); - // Pose3 noise_pose = Pose3(Rot3::ypr(-M_PI/10, 0., -M_PI/10), Point3(0.5,0.1,0.3)); // noise from regular projection factor test below - Pose3 noise_pose = Pose3(Rot3::ypr(-M_PI / 100, 0., -M_PI / 100), + // Pose3 noise_pose = Pose3(Rot3::Ypr(-M_PI/10, 0., -M_PI/10), Point3(0.5,0.1,0.3)); // noise from regular projection factor test below + Pose3 noise_pose = Pose3(Rot3::Ypr(-M_PI / 100, 0., -M_PI / 100), Point3(0.1, 0.1, 0.1)); // smaller noise Values values; - values.insert(x1, pose1); - values.insert(x2, pose2); - // initialize third pose with some noise, we expect it to move back to original pose3 - values.insert(x3, pose3 * noise_pose); + values.insert(x1, cam1.pose()); + values.insert(x2, cam2.pose()); + // initialize third pose with some noise, we expect it to move back to original pose_above + values.insert(x3, pose_above * noise_pose); EXPECT( assert_equal( Pose3( @@ -635,66 +555,47 @@ TEST( SmartProjectionPoseFactor, 3poses_iterative_smart_projection_factor ) { -0.0313952598), Point3(0.1, -0.1, 1.9)), values.at(x3))); - LevenbergMarquardtParams params; - if (isDebugTest) - params.verbosityLM = LevenbergMarquardtParams::TRYLAMBDA; - if (isDebugTest) - params.verbosity = NonlinearOptimizerParams::ERROR; - Values result; - gttic_(SmartProjectionPoseFactor); - LevenbergMarquardtOptimizer optimizer(graph, values, params); + LevenbergMarquardtOptimizer optimizer(graph, values, lmParams); result = optimizer.optimize(); - gttoc_(SmartProjectionPoseFactor); - tictoc_finishedIteration_(); - - // result.print("results of 3 camera, 3 landmark optimization \n"); - EXPECT(assert_equal(pose3, result.at(x3), 1e-7)); - if (isDebugTest) - tictoc_print_(); + EXPECT(assert_equal(pose_above, result.at(x3), 1e-7)); } /* *************************************************************************/ TEST( SmartProjectionPoseFactor, jacobianSVD ) { + using namespace vanillaPose; + vector views; views.push_back(x1); views.push_back(x2); views.push_back(x3); - // create first camera. Looking along X-axis, 1 meter above ground plane (x-y) - Pose3 pose1 = Pose3(Rot3::ypr(-M_PI / 2, 0., -M_PI / 2), Point3(0, 0, 1)); - SimpleCamera cam1(pose1, *K); - // create second camera 1 meter to the right of first camera - Pose3 pose2 = pose1 * Pose3(Rot3(), Point3(1, 0, 0)); - SimpleCamera cam2(pose2, *K); - // create third camera 1 meter above the first camera - Pose3 pose3 = pose1 * Pose3(Rot3(), Point3(0, -1, 0)); - SimpleCamera cam3(pose3, *K); - - // three landmarks ~5 meters infront of camera - Point3 landmark1(5, 0.5, 1.2); - Point3 landmark2(5, -0.5, 1.2); - Point3 landmark3(3, 0, 3.0); - vector measurements_cam1, measurements_cam2, measurements_cam3; - // 1. Project three landmarks into three cameras and triangulate + // Project three landmarks into three cameras projectToMultipleCameras(cam1, cam2, cam3, landmark1, measurements_cam1); projectToMultipleCameras(cam1, cam2, cam3, landmark2, measurements_cam2); projectToMultipleCameras(cam1, cam2, cam3, landmark3, measurements_cam3); + SmartProjectionParams params; + params.setRankTolerance(1.0); + params.setLinearizationMode(gtsam::JACOBIAN_SVD); + params.setDegeneracyMode(gtsam::IGNORE_DEGENERACY); + params.setEnableEPI(false); + SmartFactor factor1(model, sharedK, boost::none, params); + SmartFactor::shared_ptr smartFactor1( - new SmartFactor(1, -1, false, false, boost::none, JACOBIAN_SVD)); - smartFactor1->add(measurements_cam1, views, model, K); + new SmartFactor(model, sharedK, boost::none, params)); + smartFactor1->add(measurements_cam1, views); SmartFactor::shared_ptr smartFactor2( - new SmartFactor(1, -1, false, false, boost::none, JACOBIAN_SVD)); - smartFactor2->add(measurements_cam2, views, model, K); + new SmartFactor(model, sharedK, boost::none, params)); + smartFactor2->add(measurements_cam2, views); SmartFactor::shared_ptr smartFactor3( - new SmartFactor(1, -1, false, false, boost::none, JACOBIAN_SVD)); - smartFactor3->add(measurements_cam3, views, model, K); + new SmartFactor(model, sharedK, boost::none, params)); + smartFactor3->add(measurements_cam3, views); const SharedDiagonal noisePrior = noiseModel::Isotropic::Sigma(6, 0.10); @@ -702,27 +603,28 @@ TEST( SmartProjectionPoseFactor, jacobianSVD ) { graph.push_back(smartFactor1); graph.push_back(smartFactor2); graph.push_back(smartFactor3); - graph.push_back(PriorFactor(x1, pose1, noisePrior)); - graph.push_back(PriorFactor(x2, pose2, noisePrior)); + graph.push_back(PriorFactor(x1, cam1.pose(), noisePrior)); + graph.push_back(PriorFactor(x2, cam2.pose(), noisePrior)); - // Pose3 noise_pose = Pose3(Rot3::ypr(-M_PI/10, 0., -M_PI/10), Point3(0.5,0.1,0.3)); // noise from regular projection factor test below - Pose3 noise_pose = Pose3(Rot3::ypr(-M_PI / 100, 0., -M_PI / 100), + // Pose3 noise_pose = Pose3(Rot3::Ypr(-M_PI/10, 0., -M_PI/10), Point3(0.5,0.1,0.3)); // noise from regular projection factor test below + Pose3 noise_pose = Pose3(Rot3::Ypr(-M_PI / 100, 0., -M_PI / 100), Point3(0.1, 0.1, 0.1)); // smaller noise Values values; - values.insert(x1, pose1); - values.insert(x2, pose2); - values.insert(x3, pose3 * noise_pose); + values.insert(x1, cam1.pose()); + values.insert(x2, cam2.pose()); + values.insert(x3, pose_above * noise_pose); - LevenbergMarquardtParams params; Values result; - LevenbergMarquardtOptimizer optimizer(graph, values, params); + LevenbergMarquardtOptimizer optimizer(graph, values, lmParams); result = optimizer.optimize(); - EXPECT(assert_equal(pose3, result.at(x3), 1e-8)); + EXPECT(assert_equal(pose_above, result.at(x3), 1e-8)); } /* *************************************************************************/ TEST( SmartProjectionPoseFactor, landmarkDistance ) { + using namespace vanillaPose; + double excludeLandmarksFutherThanDist = 2; vector views; @@ -730,42 +632,31 @@ TEST( SmartProjectionPoseFactor, landmarkDistance ) { views.push_back(x2); views.push_back(x3); - // create first camera. Looking along X-axis, 1 meter above ground plane (x-y) - Pose3 pose1 = Pose3(Rot3::ypr(-M_PI / 2, 0., -M_PI / 2), Point3(0, 0, 1)); - SimpleCamera cam1(pose1, *K); - // create second camera 1 meter to the right of first camera - Pose3 pose2 = pose1 * Pose3(Rot3(), Point3(1, 0, 0)); - SimpleCamera cam2(pose2, *K); - // create third camera 1 meter above the first camera - Pose3 pose3 = pose1 * Pose3(Rot3(), Point3(0, -1, 0)); - SimpleCamera cam3(pose3, *K); - - // three landmarks ~5 meters infront of camera - Point3 landmark1(5, 0.5, 1.2); - Point3 landmark2(5, -0.5, 1.2); - Point3 landmark3(3, 0, 3.0); - vector measurements_cam1, measurements_cam2, measurements_cam3; - // 1. Project three landmarks into three cameras and triangulate + // Project three landmarks into three cameras projectToMultipleCameras(cam1, cam2, cam3, landmark1, measurements_cam1); projectToMultipleCameras(cam1, cam2, cam3, landmark2, measurements_cam2); projectToMultipleCameras(cam1, cam2, cam3, landmark3, measurements_cam3); + SmartProjectionParams params; + params.setRankTolerance(1.0); + params.setLinearizationMode(gtsam::JACOBIAN_SVD); + params.setDegeneracyMode(gtsam::IGNORE_DEGENERACY); + params.setLandmarkDistanceThreshold(excludeLandmarksFutherThanDist); + params.setEnableEPI(false); + SmartFactor::shared_ptr smartFactor1( - new SmartFactor(1, -1, false, false, boost::none, JACOBIAN_SVD, - excludeLandmarksFutherThanDist)); - smartFactor1->add(measurements_cam1, views, model, K); + new SmartFactor(model, sharedK, boost::none, params)); + smartFactor1->add(measurements_cam1, views); SmartFactor::shared_ptr smartFactor2( - new SmartFactor(1, -1, false, false, boost::none, JACOBIAN_SVD, - excludeLandmarksFutherThanDist)); - smartFactor2->add(measurements_cam2, views, model, K); + new SmartFactor(model, sharedK, boost::none, params)); + smartFactor2->add(measurements_cam2, views); SmartFactor::shared_ptr smartFactor3( - new SmartFactor(1, -1, false, false, boost::none, JACOBIAN_SVD, - excludeLandmarksFutherThanDist)); - smartFactor3->add(measurements_cam3, views, model, K); + new SmartFactor(model, sharedK, boost::none, params)); + smartFactor3->add(measurements_cam3, views); const SharedDiagonal noisePrior = noiseModel::Isotropic::Sigma(6, 0.10); @@ -773,21 +664,20 @@ TEST( SmartProjectionPoseFactor, landmarkDistance ) { graph.push_back(smartFactor1); graph.push_back(smartFactor2); graph.push_back(smartFactor3); - graph.push_back(PriorFactor(x1, pose1, noisePrior)); - graph.push_back(PriorFactor(x2, pose2, noisePrior)); + graph.push_back(PriorFactor(x1, cam1.pose(), noisePrior)); + graph.push_back(PriorFactor(x2, cam2.pose(), noisePrior)); - // Pose3 noise_pose = Pose3(Rot3::ypr(-M_PI/10, 0., -M_PI/10), Point3(0.5,0.1,0.3)); // noise from regular projection factor test below - Pose3 noise_pose = Pose3(Rot3::ypr(-M_PI / 100, 0., -M_PI / 100), + // Pose3 noise_pose = Pose3(Rot3::Ypr(-M_PI/10, 0., -M_PI/10), Point3(0.5,0.1,0.3)); // noise from regular projection factor test below + Pose3 noise_pose = Pose3(Rot3::Ypr(-M_PI / 100, 0., -M_PI / 100), Point3(0.1, 0.1, 0.1)); // smaller noise Values values; - values.insert(x1, pose1); - values.insert(x2, pose2); - values.insert(x3, pose3 * noise_pose); + values.insert(x1, cam1.pose()); + values.insert(x2, cam2.pose()); + values.insert(x3, pose_above * noise_pose); // All factors are disabled and pose should remain where it is - LevenbergMarquardtParams params; Values result; - LevenbergMarquardtOptimizer optimizer(graph, values, params); + LevenbergMarquardtOptimizer optimizer(graph, values, lmParams); result = optimizer.optimize(); EXPECT(assert_equal(values.at(x3), result.at(x3))); } @@ -795,6 +685,8 @@ TEST( SmartProjectionPoseFactor, landmarkDistance ) { /* *************************************************************************/ TEST( SmartProjectionPoseFactor, dynamicOutlierRejection ) { + using namespace vanillaPose; + double excludeLandmarksFutherThanDist = 1e10; double dynamicOutlierRejectionThreshold = 1; // max 1 pixel of average reprojection error @@ -803,51 +695,39 @@ TEST( SmartProjectionPoseFactor, dynamicOutlierRejection ) { views.push_back(x2); views.push_back(x3); - // create first camera. Looking along X-axis, 1 meter above ground plane (x-y) - Pose3 pose1 = Pose3(Rot3::ypr(-M_PI / 2, 0., -M_PI / 2), Point3(0, 0, 1)); - SimpleCamera cam1(pose1, *K); - // create second camera 1 meter to the right of first camera - Pose3 pose2 = pose1 * Pose3(Rot3(), Point3(1, 0, 0)); - SimpleCamera cam2(pose2, *K); - // create third camera 1 meter above the first camera - Pose3 pose3 = pose1 * Pose3(Rot3(), Point3(0, -1, 0)); - SimpleCamera cam3(pose3, *K); - - // three landmarks ~5 meters infront of camera - Point3 landmark1(5, 0.5, 1.2); - Point3 landmark2(5, -0.5, 1.2); - Point3 landmark3(3, 0, 3.0); + // add fourth landmark Point3 landmark4(5, -0.5, 1); vector measurements_cam1, measurements_cam2, measurements_cam3, measurements_cam4; - // 1. Project three landmarks into three cameras and triangulate + // Project 4 landmarks into three cameras projectToMultipleCameras(cam1, cam2, cam3, landmark1, measurements_cam1); projectToMultipleCameras(cam1, cam2, cam3, landmark2, measurements_cam2); projectToMultipleCameras(cam1, cam2, cam3, landmark3, measurements_cam3); projectToMultipleCameras(cam1, cam2, cam3, landmark4, measurements_cam4); measurements_cam4.at(0) = measurements_cam4.at(0) + Point2(10, 10); // add outlier + SmartProjectionParams params; + params.setLinearizationMode(gtsam::JACOBIAN_SVD); + params.setLandmarkDistanceThreshold(excludeLandmarksFutherThanDist); + params.setDynamicOutlierRejectionThreshold(dynamicOutlierRejectionThreshold); + SmartFactor::shared_ptr smartFactor1( - new SmartFactor(1, -1, false, false, boost::none, JACOBIAN_SVD, - excludeLandmarksFutherThanDist, dynamicOutlierRejectionThreshold)); - smartFactor1->add(measurements_cam1, views, model, K); + new SmartFactor(model, sharedK, boost::none, params)); + smartFactor1->add(measurements_cam1, views); SmartFactor::shared_ptr smartFactor2( - new SmartFactor(1, -1, false, false, boost::none, JACOBIAN_SVD, - excludeLandmarksFutherThanDist, dynamicOutlierRejectionThreshold)); - smartFactor2->add(measurements_cam2, views, model, K); + new SmartFactor(model, sharedK, boost::none, params)); + smartFactor2->add(measurements_cam2, views); SmartFactor::shared_ptr smartFactor3( - new SmartFactor(1, -1, false, false, boost::none, JACOBIAN_SVD, - excludeLandmarksFutherThanDist, dynamicOutlierRejectionThreshold)); - smartFactor3->add(measurements_cam3, views, model, K); + new SmartFactor(model, sharedK, boost::none, params)); + smartFactor3->add(measurements_cam3, views); SmartFactor::shared_ptr smartFactor4( - new SmartFactor(1, -1, false, false, boost::none, JACOBIAN_SVD, - excludeLandmarksFutherThanDist, dynamicOutlierRejectionThreshold)); - smartFactor4->add(measurements_cam4, views, model, K); + new SmartFactor(model, sharedK, boost::none, params)); + smartFactor4->add(measurements_cam4, views); const SharedDiagonal noisePrior = noiseModel::Isotropic::Sigma(6, 0.10); @@ -856,65 +736,52 @@ TEST( SmartProjectionPoseFactor, dynamicOutlierRejection ) { graph.push_back(smartFactor2); graph.push_back(smartFactor3); graph.push_back(smartFactor4); - graph.push_back(PriorFactor(x1, pose1, noisePrior)); - graph.push_back(PriorFactor(x2, pose2, noisePrior)); + graph.push_back(PriorFactor(x1, cam1.pose(), noisePrior)); + graph.push_back(PriorFactor(x2, cam2.pose(), noisePrior)); - Pose3 noise_pose = Pose3(Rot3::ypr(-M_PI / 100, 0., -M_PI / 100), - Point3(0.1, 0.1, 0.1)); // smaller noise Values values; - values.insert(x1, pose1); - values.insert(x2, pose2); - values.insert(x3, pose3); + values.insert(x1, cam1.pose()); + values.insert(x2, cam2.pose()); + values.insert(x3, cam3.pose()); // All factors are disabled and pose should remain where it is - LevenbergMarquardtParams params; Values result; - LevenbergMarquardtOptimizer optimizer(graph, values, params); + LevenbergMarquardtOptimizer optimizer(graph, values, lmParams); result = optimizer.optimize(); - EXPECT(assert_equal(pose3, result.at(x3))); + EXPECT(assert_equal(cam3.pose(), result.at(x3))); } /* *************************************************************************/ TEST( SmartProjectionPoseFactor, jacobianQ ) { + using namespace vanillaPose; + vector views; views.push_back(x1); views.push_back(x2); views.push_back(x3); - // create first camera. Looking along X-axis, 1 meter above ground plane (x-y) - Pose3 pose1 = Pose3(Rot3::ypr(-M_PI / 2, 0., -M_PI / 2), Point3(0, 0, 1)); - SimpleCamera cam1(pose1, *K); - // create second camera 1 meter to the right of first camera - Pose3 pose2 = pose1 * Pose3(Rot3(), Point3(1, 0, 0)); - SimpleCamera cam2(pose2, *K); - // create third camera 1 meter above the first camera - Pose3 pose3 = pose1 * Pose3(Rot3(), Point3(0, -1, 0)); - SimpleCamera cam3(pose3, *K); - - // three landmarks ~5 meters infront of camera - Point3 landmark1(5, 0.5, 1.2); - Point3 landmark2(5, -0.5, 1.2); - Point3 landmark3(3, 0, 3.0); - vector measurements_cam1, measurements_cam2, measurements_cam3; - // 1. Project three landmarks into three cameras and triangulate + // Project three landmarks into three cameras projectToMultipleCameras(cam1, cam2, cam3, landmark1, measurements_cam1); projectToMultipleCameras(cam1, cam2, cam3, landmark2, measurements_cam2); projectToMultipleCameras(cam1, cam2, cam3, landmark3, measurements_cam3); + SmartProjectionParams params; + params.setLinearizationMode(gtsam::JACOBIAN_Q); + SmartFactor::shared_ptr smartFactor1( - new SmartFactor(1, -1, false, false, boost::none, JACOBIAN_Q)); - smartFactor1->add(measurements_cam1, views, model, K); + new SmartFactor(model, sharedK, boost::none, params)); + smartFactor1->add(measurements_cam1, views); SmartFactor::shared_ptr smartFactor2( - new SmartFactor(1, -1, false, false, boost::none, JACOBIAN_Q)); - smartFactor2->add(measurements_cam2, views, model, K); + new SmartFactor(model, sharedK, boost::none, params)); + smartFactor2->add(measurements_cam2, views); SmartFactor::shared_ptr smartFactor3( - new SmartFactor(1, -1, false, false, boost::none, JACOBIAN_Q)); - smartFactor3->add(measurements_cam3, views, model, K); + new SmartFactor(model, sharedK, boost::none, params)); + smartFactor3->add(measurements_cam3, views); const SharedDiagonal noisePrior = noiseModel::Isotropic::Sigma(6, 0.10); @@ -922,102 +789,79 @@ TEST( SmartProjectionPoseFactor, jacobianQ ) { graph.push_back(smartFactor1); graph.push_back(smartFactor2); graph.push_back(smartFactor3); - graph.push_back(PriorFactor(x1, pose1, noisePrior)); - graph.push_back(PriorFactor(x2, pose2, noisePrior)); + graph.push_back(PriorFactor(x1, cam1.pose(), noisePrior)); + graph.push_back(PriorFactor(x2, cam2.pose(), noisePrior)); - // Pose3 noise_pose = Pose3(Rot3::ypr(-M_PI/10, 0., -M_PI/10), Point3(0.5,0.1,0.3)); // noise from regular projection factor test below - Pose3 noise_pose = Pose3(Rot3::ypr(-M_PI / 100, 0., -M_PI / 100), + Pose3 noise_pose = Pose3(Rot3::Ypr(-M_PI / 100, 0., -M_PI / 100), Point3(0.1, 0.1, 0.1)); // smaller noise Values values; - values.insert(x1, pose1); - values.insert(x2, pose2); - values.insert(x3, pose3 * noise_pose); + values.insert(x1, cam1.pose()); + values.insert(x2, cam2.pose()); + values.insert(x3, pose_above * noise_pose); - LevenbergMarquardtParams params; Values result; - LevenbergMarquardtOptimizer optimizer(graph, values, params); + LevenbergMarquardtOptimizer optimizer(graph, values, lmParams); result = optimizer.optimize(); - EXPECT(assert_equal(pose3, result.at(x3), 1e-8)); + EXPECT(assert_equal(pose_above, result.at(x3), 1e-8)); } /* *************************************************************************/ TEST( SmartProjectionPoseFactor, 3poses_projection_factor ) { - // cout << " ************************ Normal ProjectionFactor: 3 cams + 3 landmarks **********************" << endl; + + using namespace vanillaPose2; vector views; views.push_back(x1); views.push_back(x2); views.push_back(x3); - // create first camera. Looking along X-axis, 1 meter above ground plane (x-y) - Pose3 pose1 = Pose3(Rot3::ypr(-M_PI / 2, 0., -M_PI / 2), Point3(0, 0, 1)); - SimpleCamera cam1(pose1, *K2); - - // create second camera 1 meter to the right of first camera - Pose3 pose2 = pose1 * Pose3(Rot3(), Point3(1, 0, 0)); - SimpleCamera cam2(pose2, *K2); - - // create third camera 1 meter above the first camera - Pose3 pose3 = pose1 * Pose3(Rot3(), Point3(0, -1, 0)); - SimpleCamera cam3(pose3, *K2); - - // three landmarks ~5 meters infront of camera - Point3 landmark1(5, 0.5, 1.2); - Point3 landmark2(5, -0.5, 1.2); - Point3 landmark3(3, 0, 3.0); - typedef GenericProjectionFactor ProjectionFactor; NonlinearFactorGraph graph; - // 1. Project three landmarks into three cameras and triangulate + // Project three landmarks into three cameras graph.push_back( - ProjectionFactor(cam1.project(landmark1), model, x1, L(1), K2)); + ProjectionFactor(cam1.project(landmark1), model, x1, L(1), sharedK2)); graph.push_back( - ProjectionFactor(cam2.project(landmark1), model, x2, L(1), K2)); + ProjectionFactor(cam2.project(landmark1), model, x2, L(1), sharedK2)); graph.push_back( - ProjectionFactor(cam3.project(landmark1), model, x3, L(1), K2)); + ProjectionFactor(cam3.project(landmark1), model, x3, L(1), sharedK2)); graph.push_back( - ProjectionFactor(cam1.project(landmark2), model, x1, L(2), K2)); + ProjectionFactor(cam1.project(landmark2), model, x1, L(2), sharedK2)); graph.push_back( - ProjectionFactor(cam2.project(landmark2), model, x2, L(2), K2)); + ProjectionFactor(cam2.project(landmark2), model, x2, L(2), sharedK2)); graph.push_back( - ProjectionFactor(cam3.project(landmark2), model, x3, L(2), K2)); + ProjectionFactor(cam3.project(landmark2), model, x3, L(2), sharedK2)); graph.push_back( - ProjectionFactor(cam1.project(landmark3), model, x1, L(3), K2)); + ProjectionFactor(cam1.project(landmark3), model, x1, L(3), sharedK2)); graph.push_back( - ProjectionFactor(cam2.project(landmark3), model, x2, L(3), K2)); + ProjectionFactor(cam2.project(landmark3), model, x2, L(3), sharedK2)); graph.push_back( - ProjectionFactor(cam3.project(landmark3), model, x3, L(3), K2)); + ProjectionFactor(cam3.project(landmark3), model, x3, L(3), sharedK2)); const SharedDiagonal noisePrior = noiseModel::Isotropic::Sigma(6, 0.10); - graph.push_back(PriorFactor(x1, pose1, noisePrior)); - graph.push_back(PriorFactor(x2, pose2, noisePrior)); + graph.push_back(PriorFactor(x1, level_pose, noisePrior)); + graph.push_back(PriorFactor(x2, pose_right, noisePrior)); - Pose3 noise_pose = Pose3(Rot3::ypr(-M_PI / 10, 0., -M_PI / 10), + Pose3 noise_pose = Pose3(Rot3::Ypr(-M_PI / 10, 0., -M_PI / 10), Point3(0.5, 0.1, 0.3)); Values values; - values.insert(x1, pose1); - values.insert(x2, pose2); - values.insert(x3, pose3 * noise_pose); + values.insert(x1, level_pose); + values.insert(x2, pose_right); + values.insert(x3, pose_above * noise_pose); values.insert(L(1), landmark1); values.insert(L(2), landmark2); values.insert(L(3), landmark3); - if (isDebugTest) - values.at(x3).print("Pose3 before optimization: "); - LevenbergMarquardtParams params; - if (isDebugTest) - params.verbosityLM = LevenbergMarquardtParams::TRYLAMBDA; - if (isDebugTest) - params.verbosity = NonlinearOptimizerParams::ERROR; - LevenbergMarquardtOptimizer optimizer(graph, values, params); + DOUBLES_EQUAL(48406055, graph.error(values), 1); + + LevenbergMarquardtOptimizer optimizer(graph, values, lmParams); Values result = optimizer.optimize(); - if (isDebugTest) - result.at(x3).print("Pose3 after optimization: "); - EXPECT(assert_equal(pose3, result.at(x3), 1e-7)); + DOUBLES_EQUAL(0, graph.error(result), 1e-9); + + EXPECT(assert_equal(pose_above, result.at(x3), 1e-7)); } /* *************************************************************************/ @@ -1028,53 +872,49 @@ TEST( SmartProjectionPoseFactor, CheckHessian) { views.push_back(x2); views.push_back(x3); - // create first camera. Looking along X-axis, 1 meter above ground plane (x-y) - Pose3 pose1 = Pose3(Rot3::ypr(-M_PI / 2, 0., -M_PI / 2), Point3(0, 0, 1)); - SimpleCamera cam1(pose1, *K); + using namespace vanillaPose; - // create second camera 1 meter to the right of first camera - Pose3 pose2 = pose1 * Pose3(Rot3::RzRyRx(-0.05, 0.0, -0.05), Point3(0, 0, 0)); - SimpleCamera cam2(pose2, *K); - - // create third camera 1 meter above the first camera + // Two slightly different cameras + Pose3 pose2 = level_pose + * Pose3(Rot3::RzRyRx(-0.05, 0.0, -0.05), Point3(0, 0, 0)); Pose3 pose3 = pose2 * Pose3(Rot3::RzRyRx(-0.05, 0.0, -0.05), Point3(0, 0, 0)); - SimpleCamera cam3(pose3, *K); - - // three landmarks ~5 meters infront of camera - Point3 landmark1(5, 0.5, 1.2); - Point3 landmark2(5, -0.5, 1.2); - Point3 landmark3(3, 0, 3.0); + Camera cam2(pose2, sharedK); + Camera cam3(pose3, sharedK); vector measurements_cam1, measurements_cam2, measurements_cam3; - // 1. Project three landmarks into three cameras and triangulate + // Project three landmarks into three cameras projectToMultipleCameras(cam1, cam2, cam3, landmark1, measurements_cam1); projectToMultipleCameras(cam1, cam2, cam3, landmark2, measurements_cam2); projectToMultipleCameras(cam1, cam2, cam3, landmark3, measurements_cam3); - double rankTol = 10; + SmartProjectionParams params; + params.setRankTolerance(10); - SmartFactor::shared_ptr smartFactor1(new SmartFactor(rankTol)); - smartFactor1->add(measurements_cam1, views, model, K); + SmartFactor::shared_ptr smartFactor1( + new SmartFactor(model, sharedK, boost::none, params)); // HESSIAN, by default + smartFactor1->add(measurements_cam1, views); - SmartFactor::shared_ptr smartFactor2(new SmartFactor(rankTol)); - smartFactor2->add(measurements_cam2, views, model, K); + SmartFactor::shared_ptr smartFactor2( + new SmartFactor(model, sharedK, boost::none, params)); // HESSIAN, by default + smartFactor2->add(measurements_cam2, views); - SmartFactor::shared_ptr smartFactor3(new SmartFactor(rankTol)); - smartFactor3->add(measurements_cam3, views, model, K); + SmartFactor::shared_ptr smartFactor3( + new SmartFactor(model, sharedK, boost::none, params)); // HESSIAN, by default + smartFactor3->add(measurements_cam3, views); NonlinearFactorGraph graph; graph.push_back(smartFactor1); graph.push_back(smartFactor2); graph.push_back(smartFactor3); - // Pose3 noise_pose = Pose3(Rot3::ypr(-M_PI/10, 0., -M_PI/10), Point3(0.5,0.1,0.3)); // noise from regular projection factor test below - Pose3 noise_pose = Pose3(Rot3::ypr(-M_PI / 100, 0., -M_PI / 100), + // Pose3 noise_pose = Pose3(Rot3::Ypr(-M_PI/10, 0., -M_PI/10), Point3(0.5,0.1,0.3)); // noise from regular projection factor test below + Pose3 noise_pose = Pose3(Rot3::Ypr(-M_PI / 100, 0., -M_PI / 100), Point3(0.1, 0.1, 0.1)); // smaller noise Values values; - values.insert(x1, pose1); - values.insert(x2, pose2); - // initialize third pose with some noise, we expect it to move back to original pose3 + values.insert(x1, cam1.pose()); + values.insert(x2, cam2.pose()); + // initialize third pose with some noise, we expect it to move back to original pose_above values.insert(x3, pose3 * noise_pose); EXPECT( assert_equal( @@ -1085,15 +925,12 @@ TEST( SmartProjectionPoseFactor, CheckHessian) { Point3(0.0897734171, -0.110201006, 0.901022872)), values.at(x3))); - boost::shared_ptr hessianFactor1 = smartFactor1->linearize( - values); - boost::shared_ptr hessianFactor2 = smartFactor2->linearize( - values); - boost::shared_ptr hessianFactor3 = smartFactor3->linearize( - values); + boost::shared_ptr factor1 = smartFactor1->linearize(values); + boost::shared_ptr factor2 = smartFactor2->linearize(values); + boost::shared_ptr factor3 = smartFactor3->linearize(values); - Matrix CumulativeInformation = hessianFactor1->information() - + hessianFactor2->information() + hessianFactor3->information(); + Matrix CumulativeInformation = factor1->information() + factor2->information() + + factor3->information(); boost::shared_ptr GaussianGraph = graph.linearize( values); @@ -1102,12 +939,10 @@ TEST( SmartProjectionPoseFactor, CheckHessian) { // Check Hessian EXPECT(assert_equal(GraphInformation, CumulativeInformation, 1e-8)); - Matrix AugInformationMatrix = hessianFactor1->augmentedInformation() - + hessianFactor2->augmentedInformation() - + hessianFactor3->augmentedInformation(); + Matrix AugInformationMatrix = factor1->augmentedInformation() + + factor2->augmentedInformation() + factor3->augmentedInformation(); // Check Information vector - // cout << AugInformationMatrix.size() << endl; Vector InfoVector = AugInformationMatrix.block(0, 18, 18, 1); // 18x18 Hessian + information vector // Check Hessian @@ -1116,149 +951,102 @@ TEST( SmartProjectionPoseFactor, CheckHessian) { /* *************************************************************************/ TEST( SmartProjectionPoseFactor, 3poses_2land_rotation_only_smart_projection_factor ) { - // cout << " ************************ SmartProjectionPoseFactor: 3 cams + 2 landmarks: Rotation Only**********************" << endl; + using namespace vanillaPose2; vector views; views.push_back(x1); views.push_back(x2); views.push_back(x3); - // create first camera. Looking along X-axis, 1 meter above ground plane (x-y) - Pose3 pose1 = Pose3(Rot3::ypr(-M_PI / 2, 0., -M_PI / 2), Point3(0, 0, 1)); - SimpleCamera cam1(pose1, *K2); + // Two different cameras, at the same position, but different rotations + Pose3 pose2 = level_pose * Pose3(Rot3::RzRyRx(-0.05, 0.0, -0.05), Point3()); + Pose3 pose3 = pose2 * Pose3(Rot3::RzRyRx(-0.05, 0.0, -0.05), Point3()); + Camera cam2(pose2, sharedK2); + Camera cam3(pose3, sharedK2); - // create second camera 1 meter to the right of first camera - Pose3 pose2 = pose1 * Pose3(Rot3::RzRyRx(-0.05, 0.0, -0.05), Point3(0, 0, 0)); - SimpleCamera cam2(pose2, *K2); + vector measurements_cam1, measurements_cam2; - // create third camera 1 meter above the first camera - Pose3 pose3 = pose2 * Pose3(Rot3::RzRyRx(-0.05, 0.0, -0.05), Point3(0, 0, 0)); - SimpleCamera cam3(pose3, *K2); - - // three landmarks ~5 meters infront of camera - Point3 landmark1(5, 0.5, 1.2); - Point3 landmark2(5, -0.5, 1.2); - - vector measurements_cam1, measurements_cam2, measurements_cam3; - - // 1. Project three landmarks into three cameras and triangulate + // Project three landmarks into three cameras projectToMultipleCameras(cam1, cam2, cam3, landmark1, measurements_cam1); projectToMultipleCameras(cam1, cam2, cam3, landmark2, measurements_cam2); - double rankTol = 50; + SmartProjectionParams params; + params.setRankTolerance(50); + params.setDegeneracyMode(gtsam::HANDLE_INFINITY); + SmartFactor::shared_ptr smartFactor1( - new SmartFactor(rankTol, linThreshold, manageDegeneracy)); - smartFactor1->add(measurements_cam1, views, model, K2); + new SmartFactor(model, sharedK2, boost::none, params)); + smartFactor1->add(measurements_cam1, views); SmartFactor::shared_ptr smartFactor2( - new SmartFactor(rankTol, linThreshold, manageDegeneracy)); - smartFactor2->add(measurements_cam2, views, model, K2); + new SmartFactor(model, sharedK2, boost::none, params)); + smartFactor2->add(measurements_cam2, views); const SharedDiagonal noisePrior = noiseModel::Isotropic::Sigma(6, 0.10); - const SharedDiagonal noisePriorTranslation = noiseModel::Isotropic::Sigma(3, - 0.10); + const SharedDiagonal noisePriorTranslation = noiseModel::Isotropic::Sigma(3, 0.10); Point3 positionPrior = Point3(0, 0, 1); NonlinearFactorGraph graph; graph.push_back(smartFactor1); graph.push_back(smartFactor2); - graph.push_back(PriorFactor(x1, pose1, noisePrior)); + graph.push_back(PriorFactor(x1, cam1.pose(), noisePrior)); graph.push_back( PoseTranslationPrior(x2, positionPrior, noisePriorTranslation)); graph.push_back( PoseTranslationPrior(x3, positionPrior, noisePriorTranslation)); - Pose3 noise_pose = Pose3(Rot3::ypr(-M_PI / 10, 0., -M_PI / 10), + Pose3 noise_pose = Pose3(Rot3::Ypr(-M_PI / 100, 0., -M_PI / 100), Point3(0.1, 0.1, 0.1)); // smaller noise Values values; - values.insert(x1, pose1); + values.insert(x1, cam1.pose()); values.insert(x2, pose2 * noise_pose); - // initialize third pose with some noise, we expect it to move back to original pose3 - values.insert(x3, pose3 * noise_pose * noise_pose); - EXPECT( - assert_equal( - Pose3( - Rot3(0.154256096, -0.632754061, 0.75883289, -0.753276814, - -0.572308662, -0.324093872, 0.639358349, -0.521617766, - -0.564921063), - Point3(0.145118171, -0.252907438, 0.819956033)), - values.at(x3))); + values.insert(x3, pose3 * noise_pose); - LevenbergMarquardtParams params; - if (isDebugTest) - params.verbosityLM = LevenbergMarquardtParams::TRYDELTA; - if (isDebugTest) - params.verbosity = NonlinearOptimizerParams::ERROR; - - Values result; - gttic_(SmartProjectionPoseFactor); - LevenbergMarquardtOptimizer optimizer(graph, values, params); - result = optimizer.optimize(); - gttoc_(SmartProjectionPoseFactor); - tictoc_finishedIteration_(); - - // result.print("results of 3 camera, 3 landmark optimization \n"); - cout - << "TEST COMMENTED: rotation only version of smart factors has been deprecated " - << endl; - EXPECT( - assert_equal( - Pose3( - Rot3(0.154256096, -0.632754061, 0.75883289, -0.753276814, - -0.572308662, -0.324093872, 0.639358349, -0.521617766, - -0.564921063), - Point3(0.145118171, -0.252907438, 0.819956033)), - result.at(x3))); - if (isDebugTest) - tictoc_print_(); + // params.verbosityLM = LevenbergMarquardtParams::SUMMARY; + LevenbergMarquardtOptimizer optimizer(graph, values, lmParams); + Values result = optimizer.optimize(); + EXPECT(assert_equal(pose3, result.at(x3))); } /* *************************************************************************/ TEST( SmartProjectionPoseFactor, 3poses_rotation_only_smart_projection_factor ) { - // cout << " ************************ SmartProjectionPoseFactor: 3 cams + 3 landmarks: Rotation Only**********************" << endl; + + using namespace vanillaPose; vector views; views.push_back(x1); views.push_back(x2); views.push_back(x3); - // create first camera. Looking along X-axis, 1 meter above ground plane (x-y) - Pose3 pose1 = Pose3(Rot3::ypr(-M_PI / 2, 0., -M_PI / 2), Point3(0, 0, 1)); - SimpleCamera cam1(pose1, *K); - - // create second camera 1 meter to the right of first camera - Pose3 pose2 = pose1 * Pose3(Rot3::RzRyRx(-0.05, 0.0, -0.05), Point3(0, 0, 0)); - SimpleCamera cam2(pose2, *K); - - // create third camera 1 meter above the first camera + // Two different cameras, at the same position, but different rotations + Pose3 pose2 = level_pose + * Pose3(Rot3::RzRyRx(-0.05, 0.0, -0.05), Point3(0, 0, 0)); Pose3 pose3 = pose2 * Pose3(Rot3::RzRyRx(-0.05, 0.0, -0.05), Point3(0, 0, 0)); - SimpleCamera cam3(pose3, *K); - - // three landmarks ~5 meters infront of camera - Point3 landmark1(5, 0.5, 1.2); - Point3 landmark2(5, -0.5, 1.2); - Point3 landmark3(3, 0, 3.0); + Camera cam2(pose2, sharedK); + Camera cam3(pose3, sharedK); vector measurements_cam1, measurements_cam2, measurements_cam3; - // 1. Project three landmarks into three cameras and triangulate + // Project three landmarks into three cameras projectToMultipleCameras(cam1, cam2, cam3, landmark1, measurements_cam1); projectToMultipleCameras(cam1, cam2, cam3, landmark2, measurements_cam2); projectToMultipleCameras(cam1, cam2, cam3, landmark3, measurements_cam3); - double rankTol = 10; + SmartProjectionParams params; + params.setRankTolerance(10); + params.setDegeneracyMode(gtsam::ZERO_ON_DEGENERACY); SmartFactor::shared_ptr smartFactor1( - new SmartFactor(rankTol, linThreshold, manageDegeneracy)); - smartFactor1->add(measurements_cam1, views, model, K); + new SmartFactor(model, sharedK, boost::none, params)); + smartFactor1->add(measurements_cam1, views); SmartFactor::shared_ptr smartFactor2( - new SmartFactor(rankTol, linThreshold, manageDegeneracy)); - smartFactor2->add(measurements_cam2, views, model, K); + new SmartFactor(model, sharedK, boost::none, params)); + smartFactor2->add(measurements_cam2, views); SmartFactor::shared_ptr smartFactor3( - new SmartFactor(rankTol, linThreshold, manageDegeneracy)); - smartFactor3->add(measurements_cam3, views, model, K); + new SmartFactor(model, sharedK, boost::none, params)); + smartFactor3->add(measurements_cam3, views); const SharedDiagonal noisePrior = noiseModel::Isotropic::Sigma(6, 0.10); const SharedDiagonal noisePriorTranslation = noiseModel::Isotropic::Sigma(3, @@ -1269,19 +1057,18 @@ TEST( SmartProjectionPoseFactor, 3poses_rotation_only_smart_projection_factor ) graph.push_back(smartFactor1); graph.push_back(smartFactor2); graph.push_back(smartFactor3); - graph.push_back(PriorFactor(x1, pose1, noisePrior)); + graph.push_back(PriorFactor(x1, cam1.pose(), noisePrior)); graph.push_back( PoseTranslationPrior(x2, positionPrior, noisePriorTranslation)); graph.push_back( PoseTranslationPrior(x3, positionPrior, noisePriorTranslation)); - // Pose3 noise_pose = Pose3(Rot3::ypr(-M_PI/10, 0., -M_PI/10), Point3(0.5,0.1,0.3)); // noise from regular projection factor test below - Pose3 noise_pose = Pose3(Rot3::ypr(-M_PI / 100, 0., -M_PI / 100), + // Pose3 noise_pose = Pose3(Rot3::Ypr(-M_PI/10, 0., -M_PI/10), Point3(0.5,0.1,0.3)); // noise from regular projection factor test below + Pose3 noise_pose = Pose3(Rot3::Ypr(-M_PI / 100, 0., -M_PI / 100), Point3(0.1, 0.1, 0.1)); // smaller noise Values values; - values.insert(x1, pose1); - values.insert(x2, pose2); - // initialize third pose with some noise, we expect it to move back to original pose3 + values.insert(x1, cam1.pose()); + values.insert(x2, cam2.pose()); values.insert(x3, pose3 * noise_pose); EXPECT( assert_equal( @@ -1292,78 +1079,46 @@ TEST( SmartProjectionPoseFactor, 3poses_rotation_only_smart_projection_factor ) Point3(0.0897734171, -0.110201006, 0.901022872)), values.at(x3))); - LevenbergMarquardtParams params; - if (isDebugTest) - params.verbosityLM = LevenbergMarquardtParams::TRYDELTA; - if (isDebugTest) - params.verbosity = NonlinearOptimizerParams::ERROR; - Values result; - gttic_(SmartProjectionPoseFactor); - LevenbergMarquardtOptimizer optimizer(graph, values, params); + LevenbergMarquardtOptimizer optimizer(graph, values, lmParams); result = optimizer.optimize(); - gttoc_(SmartProjectionPoseFactor); - tictoc_finishedIteration_(); - // result.print("results of 3 camera, 3 landmark optimization \n"); - cout - << "TEST COMMENTED: rotation only version of smart factors has been deprecated " - << endl; - EXPECT( - assert_equal( - Pose3( - Rot3(0.00563056869, -0.130848107, 0.991386438, -0.991390265, - -0.130426831, -0.0115837907, 0.130819108, -0.98278564, - -0.130455917), - Point3(0.0897734171, -0.110201006, 0.901022872)), - result.at(x3))); - if (isDebugTest) - tictoc_print_(); + // Since we do not do anything on degenerate instances (ZERO_ON_DEGENERACY) + // rotation remains the same as the initial guess, but position is fixed by PoseTranslationPrior + EXPECT(assert_equal(Pose3(values.at(x3).rotation(), + Point3(0,0,1)), result.at(x3))); } /* *************************************************************************/ TEST( SmartProjectionPoseFactor, Hessian ) { - // cout << " ************************ SmartProjectionPoseFactor: Hessian **********************" << endl; + + using namespace vanillaPose2; vector views; views.push_back(x1); views.push_back(x2); - // create first camera. Looking along X-axis, 1 meter above ground plane (x-y) - Pose3 pose1 = Pose3(Rot3::ypr(-M_PI / 2, 0., -M_PI / 2), Point3(0, 0, 1)); - SimpleCamera cam1(pose1, *K2); - - // create second camera 1 meter to the right of first camera - Pose3 pose2 = pose1 * Pose3(Rot3(), Point3(1, 0, 0)); - SimpleCamera cam2(pose2, *K2); - - // three landmarks ~5 meters infront of camera - Point3 landmark1(5, 0.5, 1.2); - - // 1. Project three landmarks into three cameras and triangulate + // Project three landmarks into 2 cameras Point2 cam1_uv1 = cam1.project(landmark1); Point2 cam2_uv1 = cam2.project(landmark1); vector measurements_cam1; measurements_cam1.push_back(cam1_uv1); measurements_cam1.push_back(cam2_uv1); - SmartFactor::shared_ptr smartFactor1(new SmartFactor()); - smartFactor1->add(measurements_cam1, views, model, K2); + SmartFactor::shared_ptr smartFactor1(new SmartFactor(model, sharedK2)); + smartFactor1->add(measurements_cam1, views); - Pose3 noise_pose = Pose3(Rot3::ypr(-M_PI / 10, 0., -M_PI / 10), + Pose3 noise_pose = Pose3(Rot3::Ypr(-M_PI / 10, 0., -M_PI / 10), Point3(0.5, 0.1, 0.3)); Values values; - values.insert(x1, pose1); - values.insert(x2, pose2); + values.insert(x1, cam1.pose()); + values.insert(x2, cam2.pose()); - boost::shared_ptr hessianFactor = smartFactor1->linearize( - values); - if (isDebugTest) - hessianFactor->print("Hessian factor \n"); + boost::shared_ptr factor = smartFactor1->linearize(values); // compute triangulation from linearization point // compute reprojection errors (sum squared) - // compare with hessianFactor.info(): the bottom right element is the squared sum of the reprojection errors (normalized by the covariance) + // compare with factor.info(): the bottom right element is the squared sum of the reprojection errors (normalized by the covariance) // check that it is correctly scaled when using noiseProjection = [1/4 0; 0 1/4] } @@ -1371,214 +1126,148 @@ TEST( SmartProjectionPoseFactor, Hessian ) { TEST( SmartProjectionPoseFactor, HessianWithRotation ) { // cout << " ************************ SmartProjectionPoseFactor: rotated Hessian **********************" << endl; + using namespace vanillaPose; + vector views; views.push_back(x1); views.push_back(x2); views.push_back(x3); - // create first camera. Looking along X-axis, 1 meter above ground plane (x-y) - Pose3 pose1 = Pose3(Rot3::ypr(-M_PI / 2, 0., -M_PI / 2), Point3(0, 0, 1)); - SimpleCamera cam1(pose1, *K); - - // create second camera 1 meter to the right of first camera - Pose3 pose2 = pose1 * Pose3(Rot3(), Point3(1, 0, 0)); - SimpleCamera cam2(pose2, *K); - - // create third camera 1 meter above the first camera - Pose3 pose3 = pose1 * Pose3(Rot3(), Point3(0, -1, 0)); - SimpleCamera cam3(pose3, *K); - - Point3 landmark1(5, 0.5, 1.2); - vector measurements_cam1, measurements_cam2, measurements_cam3; projectToMultipleCameras(cam1, cam2, cam3, landmark1, measurements_cam1); - SmartFactor::shared_ptr smartFactorInstance(new SmartFactor()); - smartFactorInstance->add(measurements_cam1, views, model, K); + SmartFactor::shared_ptr smartFactorInstance(new SmartFactor(model, sharedK)); + smartFactorInstance->add(measurements_cam1, views); Values values; - values.insert(x1, pose1); - values.insert(x2, pose2); - values.insert(x3, pose3); + values.insert(x1, cam1.pose()); + values.insert(x2, cam2.pose()); + values.insert(x3, cam3.pose()); - boost::shared_ptr hessianFactor = - smartFactorInstance->linearize(values); - // hessianFactor->print("Hessian factor \n"); + boost::shared_ptr factor = smartFactorInstance->linearize( + values); - Pose3 poseDrift = Pose3(Rot3::ypr(-M_PI / 2, 0., -M_PI / 2), Point3(0, 0, 0)); + Pose3 poseDrift = Pose3(Rot3::Ypr(-M_PI / 2, 0., -M_PI / 2), Point3(0, 0, 0)); Values rotValues; - rotValues.insert(x1, poseDrift.compose(pose1)); - rotValues.insert(x2, poseDrift.compose(pose2)); - rotValues.insert(x3, poseDrift.compose(pose3)); + rotValues.insert(x1, poseDrift.compose(level_pose)); + rotValues.insert(x2, poseDrift.compose(pose_right)); + rotValues.insert(x3, poseDrift.compose(pose_above)); - boost::shared_ptr hessianFactorRot = - smartFactorInstance->linearize(rotValues); - // hessianFactorRot->print("Hessian factor \n"); + boost::shared_ptr factorRot = smartFactorInstance->linearize( + rotValues); // Hessian is invariant to rotations in the nondegenerate case - EXPECT( - assert_equal(hessianFactor->information(), - hessianFactorRot->information(), 1e-7)); + EXPECT(assert_equal(factor->information(), factorRot->information(), 1e-7)); - Pose3 poseDrift2 = Pose3(Rot3::ypr(-M_PI / 2, -M_PI / 3, -M_PI / 2), + Pose3 poseDrift2 = Pose3(Rot3::Ypr(-M_PI / 2, -M_PI / 3, -M_PI / 2), Point3(10, -4, 5)); Values tranValues; - tranValues.insert(x1, poseDrift2.compose(pose1)); - tranValues.insert(x2, poseDrift2.compose(pose2)); - tranValues.insert(x3, poseDrift2.compose(pose3)); + tranValues.insert(x1, poseDrift2.compose(level_pose)); + tranValues.insert(x2, poseDrift2.compose(pose_right)); + tranValues.insert(x3, poseDrift2.compose(pose_above)); - boost::shared_ptr hessianFactorRotTran = + boost::shared_ptr factorRotTran = smartFactorInstance->linearize(tranValues); // Hessian is invariant to rotations and translations in the nondegenerate case - EXPECT( - assert_equal(hessianFactor->information(), - hessianFactorRotTran->information(), 1e-7)); + EXPECT(assert_equal(factor->information(), factorRotTran->information(), 1e-7)); } /* *************************************************************************/ TEST( SmartProjectionPoseFactor, HessianWithRotationDegenerate ) { - // cout << " ************************ SmartProjectionPoseFactor: rotated Hessian (degenerate) **********************" << endl; + + using namespace vanillaPose2; vector views; views.push_back(x1); views.push_back(x2); views.push_back(x3); - // create first camera. Looking along X-axis, 1 meter above ground plane (x-y) - Pose3 pose1 = Pose3(Rot3::ypr(-M_PI / 2, 0., -M_PI / 2), Point3(0, 0, 1)); - SimpleCamera cam1(pose1, *K2); - - // create second camera 1 meter to the right of first camera - Pose3 pose2 = pose1 * Pose3(Rot3(), Point3(0, 0, 0)); - SimpleCamera cam2(pose2, *K2); - - // create third camera 1 meter above the first camera - Pose3 pose3 = pose1 * Pose3(Rot3(), Point3(0, 0, 0)); - SimpleCamera cam3(pose3, *K2); - - Point3 landmark1(5, 0.5, 1.2); - - vector measurements_cam1, measurements_cam2, measurements_cam3; + // All cameras have the same pose so will be degenerate ! + Camera cam2(level_pose, sharedK2); + Camera cam3(level_pose, sharedK2); + vector measurements_cam1; projectToMultipleCameras(cam1, cam2, cam3, landmark1, measurements_cam1); - SmartFactor::shared_ptr smartFactor(new SmartFactor()); - smartFactor->add(measurements_cam1, views, model, K2); + SmartFactor::shared_ptr smartFactor(new SmartFactor(model, sharedK2)); + smartFactor->add(measurements_cam1, views); Values values; - values.insert(x1, pose1); - values.insert(x2, pose2); - values.insert(x3, pose3); + values.insert(x1, cam1.pose()); + values.insert(x2, cam2.pose()); + values.insert(x3, cam3.pose()); - boost::shared_ptr hessianFactor = smartFactor->linearize( - values); - if (isDebugTest) - hessianFactor->print("Hessian factor \n"); + boost::shared_ptr factor = smartFactor->linearize(values); - Pose3 poseDrift = Pose3(Rot3::ypr(-M_PI / 2, 0., -M_PI / 2), Point3(0, 0, 0)); + Pose3 poseDrift = Pose3(Rot3::Ypr(-M_PI / 2, 0., -M_PI / 2), Point3(0, 0, 0)); Values rotValues; - rotValues.insert(x1, poseDrift.compose(pose1)); - rotValues.insert(x2, poseDrift.compose(pose2)); - rotValues.insert(x3, poseDrift.compose(pose3)); + rotValues.insert(x1, poseDrift.compose(level_pose)); + rotValues.insert(x2, poseDrift.compose(level_pose)); + rotValues.insert(x3, poseDrift.compose(level_pose)); - boost::shared_ptr hessianFactorRot = smartFactor->linearize( - rotValues); - if (isDebugTest) - hessianFactorRot->print("Hessian factor \n"); + boost::shared_ptr factorRot = // + smartFactor->linearize(rotValues); // Hessian is invariant to rotations in the nondegenerate case - EXPECT( - assert_equal(hessianFactor->information(), - hessianFactorRot->information(), 1e-8)); + EXPECT(assert_equal(factor->information(), factorRot->information(), 1e-7)); - Pose3 poseDrift2 = Pose3(Rot3::ypr(-M_PI / 2, -M_PI / 3, -M_PI / 2), + Pose3 poseDrift2 = Pose3(Rot3::Ypr(-M_PI / 2, -M_PI / 3, -M_PI / 2), Point3(10, -4, 5)); Values tranValues; - tranValues.insert(x1, poseDrift2.compose(pose1)); - tranValues.insert(x2, poseDrift2.compose(pose2)); - tranValues.insert(x3, poseDrift2.compose(pose3)); + tranValues.insert(x1, poseDrift2.compose(level_pose)); + tranValues.insert(x2, poseDrift2.compose(level_pose)); + tranValues.insert(x3, poseDrift2.compose(level_pose)); - boost::shared_ptr hessianFactorRotTran = - smartFactor->linearize(tranValues); + boost::shared_ptr factorRotTran = smartFactor->linearize( + tranValues); // Hessian is invariant to rotations and translations in the nondegenerate case - EXPECT( - assert_equal(hessianFactor->information(), - hessianFactorRotTran->information(), 1e-8)); + EXPECT(assert_equal(factor->information(), factorRotTran->information(), 1e-7)); } /* ************************************************************************* */ TEST( SmartProjectionPoseFactor, ConstructorWithCal3Bundler) { - SmartFactorBundler factor(rankTol, linThreshold); - boost::shared_ptr Kbundler( - new Cal3Bundler(500, 1e-3, 1e-3, 1000, 2000)); - factor.add(measurement1, poseKey1, model, Kbundler); + using namespace bundlerPose; + SmartProjectionParams params; + params.setDegeneracyMode(gtsam::ZERO_ON_DEGENERACY); + SmartFactor factor(model, sharedBundlerK, boost::none, params); + factor.add(measurement1, x1); } /* *************************************************************************/ TEST( SmartProjectionPoseFactor, Cal3Bundler ) { - // cout << " ************************ SmartProjectionPoseFactor: Cal3Bundler **********************" << endl; - // create first camera. Looking along X-axis, 1 meter above ground plane (x-y) - Pose3 pose1 = Pose3(Rot3::ypr(-M_PI / 2, 0., -M_PI / 2), Point3(0, 0, 1)); - PinholeCamera cam1(pose1, *Kbundler); + using namespace bundlerPose; - // create second camera 1 meter to the right of first camera - Pose3 pose2 = pose1 * Pose3(Rot3(), Point3(1, 0, 0)); - PinholeCamera cam2(pose2, *Kbundler); - - // create third camera 1 meter above the first camera - Pose3 pose3 = pose1 * Pose3(Rot3(), Point3(0, -1, 0)); - PinholeCamera cam3(pose3, *Kbundler); - - // three landmarks ~5 meters infront of camera - Point3 landmark1(5, 0.5, 1.2); - Point3 landmark2(5, -0.5, 1.2); + // three landmarks ~5 meters in front of camera Point3 landmark3(3, 0, 3.0); vector measurements_cam1, measurements_cam2, measurements_cam3; - // 1. Project three landmarks into three cameras and triangulate - Point2 cam1_uv1 = cam1.project(landmark1); - Point2 cam2_uv1 = cam2.project(landmark1); - Point2 cam3_uv1 = cam3.project(landmark1); - measurements_cam1.push_back(cam1_uv1); - measurements_cam1.push_back(cam2_uv1); - measurements_cam1.push_back(cam3_uv1); - - Point2 cam1_uv2 = cam1.project(landmark2); - Point2 cam2_uv2 = cam2.project(landmark2); - Point2 cam3_uv2 = cam3.project(landmark2); - measurements_cam2.push_back(cam1_uv2); - measurements_cam2.push_back(cam2_uv2); - measurements_cam2.push_back(cam3_uv2); - - Point2 cam1_uv3 = cam1.project(landmark3); - Point2 cam2_uv3 = cam2.project(landmark3); - Point2 cam3_uv3 = cam3.project(landmark3); - measurements_cam3.push_back(cam1_uv3); - measurements_cam3.push_back(cam2_uv3); - measurements_cam3.push_back(cam3_uv3); + // Project three landmarks into three cameras + projectToMultipleCameras(cam1, cam2, cam3, landmark1, measurements_cam1); + projectToMultipleCameras(cam1, cam2, cam3, landmark2, measurements_cam2); + projectToMultipleCameras(cam1, cam2, cam3, landmark3, measurements_cam3); vector views; views.push_back(x1); views.push_back(x2); views.push_back(x3); - SmartFactorBundler::shared_ptr smartFactor1(new SmartFactorBundler()); - smartFactor1->add(measurements_cam1, views, model, Kbundler); + SmartFactor::shared_ptr smartFactor1(new SmartFactor(model, sharedBundlerK)); + smartFactor1->add(measurements_cam1, views); - SmartFactorBundler::shared_ptr smartFactor2(new SmartFactorBundler()); - smartFactor2->add(measurements_cam2, views, model, Kbundler); + SmartFactor::shared_ptr smartFactor2(new SmartFactor(model, sharedBundlerK)); + smartFactor2->add(measurements_cam2, views); - SmartFactorBundler::shared_ptr smartFactor3(new SmartFactorBundler()); - smartFactor3->add(measurements_cam3, views, model, Kbundler); + SmartFactor::shared_ptr smartFactor3(new SmartFactor(model, sharedBundlerK)); + smartFactor3->add(measurements_cam3, views); const SharedDiagonal noisePrior = noiseModel::Isotropic::Sigma(6, 0.10); @@ -1586,103 +1275,72 @@ TEST( SmartProjectionPoseFactor, Cal3Bundler ) { graph.push_back(smartFactor1); graph.push_back(smartFactor2); graph.push_back(smartFactor3); - graph.push_back(PriorFactor(x1, pose1, noisePrior)); - graph.push_back(PriorFactor(x2, pose2, noisePrior)); + graph.push_back(PriorFactor(x1, cam1.pose(), noisePrior)); + graph.push_back(PriorFactor(x2, cam2.pose(), noisePrior)); - // Pose3 noise_pose = Pose3(Rot3::ypr(-M_PI/10, 0., -M_PI/10), Point3(0.5,0.1,0.3)); // noise from regular projection factor test below - Pose3 noise_pose = Pose3(Rot3::ypr(-M_PI / 100, 0., -M_PI / 100), + // Pose3 noise_pose = Pose3(Rot3::Ypr(-M_PI/10, 0., -M_PI/10), Point3(0.5,0.1,0.3)); // noise from regular projection factor test below + Pose3 noise_pose = Pose3(Rot3::Ypr(-M_PI / 100, 0., -M_PI / 100), Point3(0.1, 0.1, 0.1)); // smaller noise Values values; - values.insert(x1, pose1); - values.insert(x2, pose2); - // initialize third pose with some noise, we expect it to move back to original pose3 - values.insert(x3, pose3 * noise_pose); + values.insert(x1, cam1.pose()); + values.insert(x2, cam2.pose()); + // initialize third pose with some noise, we expect it to move back to original pose_above + values.insert(x3, pose_above * noise_pose); EXPECT( assert_equal( Pose3( Rot3(0, -0.0314107591, 0.99950656, -0.99950656, -0.0313952598, -0.000986635786, 0.0314107591, -0.999013364, -0.0313952598), Point3(0.1, -0.1, 1.9)), values.at(x3))); - LevenbergMarquardtParams params; - if (isDebugTest) - params.verbosityLM = LevenbergMarquardtParams::TRYLAMBDA; - if (isDebugTest) - params.verbosity = NonlinearOptimizerParams::ERROR; Values result; - gttic_(SmartProjectionPoseFactor); - LevenbergMarquardtOptimizer optimizer(graph, values, params); + LevenbergMarquardtOptimizer optimizer(graph, values, lmParams); result = optimizer.optimize(); - gttoc_(SmartProjectionPoseFactor); - tictoc_finishedIteration_(); - - EXPECT(assert_equal(pose3, result.at(x3), 1e-6)); - if (isDebugTest) - tictoc_print_(); + EXPECT(assert_equal(cam3.pose(), result.at(x3), 1e-6)); } /* *************************************************************************/ TEST( SmartProjectionPoseFactor, Cal3BundlerRotationOnly ) { + using namespace bundlerPose; + vector views; views.push_back(x1); views.push_back(x2); views.push_back(x3); - // create first camera. Looking along X-axis, 1 meter above ground plane (x-y) - Pose3 pose1 = Pose3(Rot3::ypr(-M_PI / 2, 0., -M_PI / 2), Point3(0, 0, 1)); - PinholeCamera cam1(pose1, *Kbundler); - - // create second camera 1 meter to the right of first camera - Pose3 pose2 = pose1 * Pose3(Rot3::RzRyRx(-0.05, 0.0, -0.05), Point3(0, 0, 0)); - PinholeCamera cam2(pose2, *Kbundler); - - // create third camera 1 meter above the first camera + // Two different cameras + Pose3 pose2 = level_pose + * Pose3(Rot3::RzRyRx(-0.05, 0.0, -0.05), Point3(0, 0, 0)); Pose3 pose3 = pose2 * Pose3(Rot3::RzRyRx(-0.05, 0.0, -0.05), Point3(0, 0, 0)); - PinholeCamera cam3(pose3, *Kbundler); + Camera cam2(pose2, sharedBundlerK); + Camera cam3(pose3, sharedBundlerK); - // three landmarks ~5 meters infront of camera - Point3 landmark1(5, 0.5, 1.2); - Point3 landmark2(5, -0.5, 1.2); + // landmark3 at 3 meters now Point3 landmark3(3, 0, 3.0); vector measurements_cam1, measurements_cam2, measurements_cam3; - // 1. Project three landmarks into three cameras and triangulate - Point2 cam1_uv1 = cam1.project(landmark1); - Point2 cam2_uv1 = cam2.project(landmark1); - Point2 cam3_uv1 = cam3.project(landmark1); - measurements_cam1.push_back(cam1_uv1); - measurements_cam1.push_back(cam2_uv1); - measurements_cam1.push_back(cam3_uv1); + // Project three landmarks into three cameras + projectToMultipleCameras(cam1, cam2, cam3, landmark1, measurements_cam1); + projectToMultipleCameras(cam1, cam2, cam3, landmark2, measurements_cam2); + projectToMultipleCameras(cam1, cam2, cam3, landmark3, measurements_cam3); - Point2 cam1_uv2 = cam1.project(landmark2); - Point2 cam2_uv2 = cam2.project(landmark2); - Point2 cam3_uv2 = cam3.project(landmark2); - measurements_cam2.push_back(cam1_uv2); - measurements_cam2.push_back(cam2_uv2); - measurements_cam2.push_back(cam3_uv2); + SmartProjectionParams params; + params.setRankTolerance(10); + params.setDegeneracyMode(gtsam::ZERO_ON_DEGENERACY); - Point2 cam1_uv3 = cam1.project(landmark3); - Point2 cam2_uv3 = cam2.project(landmark3); - Point2 cam3_uv3 = cam3.project(landmark3); - measurements_cam3.push_back(cam1_uv3); - measurements_cam3.push_back(cam2_uv3); - measurements_cam3.push_back(cam3_uv3); + SmartFactor::shared_ptr smartFactor1( + new SmartFactor(model, sharedBundlerK, boost::none, params)); + smartFactor1->add(measurements_cam1, views); - double rankTol = 10; + SmartFactor::shared_ptr smartFactor2( + new SmartFactor(model, sharedBundlerK, boost::none, params)); + smartFactor2->add(measurements_cam2, views); - SmartFactorBundler::shared_ptr smartFactor1( - new SmartFactorBundler(rankTol, linThreshold, manageDegeneracy)); - smartFactor1->add(measurements_cam1, views, model, Kbundler); - - SmartFactorBundler::shared_ptr smartFactor2( - new SmartFactorBundler(rankTol, linThreshold, manageDegeneracy)); - smartFactor2->add(measurements_cam2, views, model, Kbundler); - - SmartFactorBundler::shared_ptr smartFactor3( - new SmartFactorBundler(rankTol, linThreshold, manageDegeneracy)); - smartFactor3->add(measurements_cam3, views, model, Kbundler); + SmartFactor::shared_ptr smartFactor3( + new SmartFactor(model, sharedBundlerK, boost::none, params)); + smartFactor3->add(measurements_cam3, views); const SharedDiagonal noisePrior = noiseModel::Isotropic::Sigma(6, 0.10); const SharedDiagonal noisePriorTranslation = noiseModel::Isotropic::Sigma(3, @@ -1693,19 +1351,19 @@ TEST( SmartProjectionPoseFactor, Cal3BundlerRotationOnly ) { graph.push_back(smartFactor1); graph.push_back(smartFactor2); graph.push_back(smartFactor3); - graph.push_back(PriorFactor(x1, pose1, noisePrior)); + graph.push_back(PriorFactor(x1, cam1.pose(), noisePrior)); graph.push_back( PoseTranslationPrior(x2, positionPrior, noisePriorTranslation)); graph.push_back( PoseTranslationPrior(x3, positionPrior, noisePriorTranslation)); - // Pose3 noise_pose = Pose3(Rot3::ypr(-M_PI/10, 0., -M_PI/10), Point3(0.5,0.1,0.3)); // noise from regular projection factor test below - Pose3 noise_pose = Pose3(Rot3::ypr(-M_PI / 100, 0., -M_PI / 100), + // Pose3 noise_pose = Pose3(Rot3::Ypr(-M_PI/10, 0., -M_PI/10), Point3(0.5,0.1,0.3)); // noise from regular projection factor test below + Pose3 noise_pose = Pose3(Rot3::Ypr(-M_PI / 100, 0., -M_PI / 100), Point3(0.1, 0.1, 0.1)); // smaller noise Values values; - values.insert(x1, pose1); - values.insert(x2, pose2); - // initialize third pose with some noise, we expect it to move back to original pose3 + values.insert(x1, cam1.pose()); + values.insert(x2, cam2.pose()); + // initialize third pose with some noise, we expect it to move back to original pose_above values.insert(x3, pose3 * noise_pose); EXPECT( assert_equal( @@ -1716,20 +1374,10 @@ TEST( SmartProjectionPoseFactor, Cal3BundlerRotationOnly ) { Point3(0.0897734171, -0.110201006, 0.901022872)), values.at(x3))); - LevenbergMarquardtParams params; - if (isDebugTest) - params.verbosityLM = LevenbergMarquardtParams::TRYDELTA; - if (isDebugTest) - params.verbosity = NonlinearOptimizerParams::ERROR; - Values result; - gttic_(SmartProjectionPoseFactor); - LevenbergMarquardtOptimizer optimizer(graph, values, params); + LevenbergMarquardtOptimizer optimizer(graph, values, lmParams); result = optimizer.optimize(); - gttoc_(SmartProjectionPoseFactor); - tictoc_finishedIteration_(); - // result.print("results of 3 camera, 3 landmark optimization \n"); EXPECT( assert_equal( Pose3( @@ -1738,12 +1386,27 @@ TEST( SmartProjectionPoseFactor, Cal3BundlerRotationOnly ) { -0.130455917), Point3(0.0897734171, -0.110201006, 0.901022872)), values.at(x3))); - cout - << "TEST COMMENTED: rotation only version of smart factors has been deprecated " - << endl; - // EXPECT(assert_equal(pose3,result.at(x3))); - if (isDebugTest) - tictoc_print_(); +} + +/* ************************************************************************* */ +BOOST_CLASS_EXPORT_GUID(gtsam::noiseModel::Constrained, "gtsam_noiseModel_Constrained"); +BOOST_CLASS_EXPORT_GUID(gtsam::noiseModel::Diagonal, "gtsam_noiseModel_Diagonal"); +BOOST_CLASS_EXPORT_GUID(gtsam::noiseModel::Gaussian, "gtsam_noiseModel_Gaussian"); +BOOST_CLASS_EXPORT_GUID(gtsam::noiseModel::Unit, "gtsam_noiseModel_Unit"); +BOOST_CLASS_EXPORT_GUID(gtsam::noiseModel::Isotropic, "gtsam_noiseModel_Isotropic"); +BOOST_CLASS_EXPORT_GUID(gtsam::SharedNoiseModel, "gtsam_SharedNoiseModel"); +BOOST_CLASS_EXPORT_GUID(gtsam::SharedDiagonal, "gtsam_SharedDiagonal"); + +TEST(SmartProjectionPoseFactor, serialize) { + using namespace vanillaPose; + using namespace gtsam::serializationTestHelpers; + SmartProjectionParams params; + params.setRankTolerance(rankTol); + SmartFactor factor(model, sharedK, boost::none, params); + + EXPECT(equalsObj(factor)); + EXPECT(equalsXML(factor)); + EXPECT(equalsBinary(factor)); } /* ************************************************************************* */ diff --git a/gtsam/slam/tests/testTriangulationFactor.cpp b/gtsam/slam/tests/testTriangulationFactor.cpp index 6b79171df..1d2baefee 100644 --- a/gtsam/slam/tests/testTriangulationFactor.cpp +++ b/gtsam/slam/tests/testTriangulationFactor.cpp @@ -17,7 +17,11 @@ */ #include +#include +#include #include +#include +#include #include #include @@ -33,9 +37,9 @@ static const boost::shared_ptr sharedCal = // boost::make_shared(1500, 1200, 0, 640, 480); // Looking along X-axis, 1 meter above ground plane (x-y) -static const Rot3 upright = Rot3::ypr(-M_PI / 2, 0., -M_PI / 2); +static const Rot3 upright = Rot3::Ypr(-M_PI / 2, 0., -M_PI / 2); static const Pose3 pose1 = Pose3(upright, gtsam::Point3(0, 0, 1)); -PinholeCamera camera1(pose1, *sharedCal); +SimpleCamera camera1(pose1, *sharedCal); // landmark ~5 meters infront of camera static const Point3 landmark(5, 0.5, 1.2); @@ -45,10 +49,10 @@ Point2 z1 = camera1.project(landmark); //****************************************************************************** TEST( triangulation, TriangulationFactor ) { - // Create the factor with a measurement that is 3 pixels off in x + Key pointKey(1); SharedNoiseModel model; - typedef TriangulationFactor<> Factor; + typedef TriangulationFactor Factor; Factor factor(camera1, z1, model, pointKey); // Use the factor to calculate the Jacobians @@ -62,6 +66,46 @@ TEST( triangulation, TriangulationFactor ) { CHECK(assert_equal(HExpected, HActual, 1e-3)); } +//****************************************************************************** +TEST( triangulation, TriangulationFactorStereo ) { + + Key pointKey(1); + SharedNoiseModel model=noiseModel::Isotropic::Sigma(3,0.5); + Cal3_S2Stereo::shared_ptr stereoCal(new Cal3_S2Stereo(1500, 1200, 0, 640, 480, 0.5)); + StereoCamera camera2(pose1, stereoCal); + + StereoPoint2 z2 = camera2.project(landmark); + + typedef TriangulationFactor Factor; + Factor factor(camera2, z2, model, pointKey); + + // Use the factor to calculate the Jacobians + Matrix HActual; + factor.evaluateError(landmark, HActual); + + Matrix HExpected = numericalDerivative11( + boost::bind(&Factor::evaluateError, &factor, _1, boost::none), landmark); + + // Verify the Jacobians are correct + CHECK(assert_equal(HExpected, HActual, 1e-3)); + + // compare same problem against expression factor + Expression::UnaryFunction::type f = boost::bind(&StereoCamera::project2, camera2, _1, boost::none, _2); + Expression point_(pointKey); + Expression project2_(f, point_); + + ExpressionFactor eFactor(model, z2, project2_); + + Values values; + values.insert(pointKey, landmark); + + vector HActual1(1), HActual2(1); + Vector error1 = factor.unwhitenedError(values, HActual1); + Vector error2 = eFactor.unwhitenedError(values, HActual2); + EXPECT(assert_equal(error1, error2)); + EXPECT(assert_equal(HActual1[0], HActual2[0])); +} + //****************************************************************************** int main() { TestResult tr; diff --git a/gtsam/smart/CMakeLists.txt b/gtsam/smart/CMakeLists.txt new file mode 100644 index 000000000..53c18fe96 --- /dev/null +++ b/gtsam/smart/CMakeLists.txt @@ -0,0 +1,6 @@ +# Install headers +file(GLOB smart_headers "*.h") +install(FILES ${smart_headers} DESTINATION include/gtsam/smart) + +# Build tests +add_subdirectory(tests) diff --git a/gtsam/smart/tests/CMakeLists.txt b/gtsam/smart/tests/CMakeLists.txt new file mode 100644 index 000000000..caa3164fa --- /dev/null +++ b/gtsam/smart/tests/CMakeLists.txt @@ -0,0 +1 @@ +gtsamAddTestsGlob(smart "test*.cpp" "" "gtsam") diff --git a/gtsam/symbolic/SymbolicFactor-inst.h b/gtsam/symbolic/SymbolicFactor-inst.h index 56850e991..f1e2b48c2 100644 --- a/gtsam/symbolic/SymbolicFactor-inst.h +++ b/gtsam/symbolic/SymbolicFactor-inst.h @@ -17,15 +17,17 @@ #pragma once -#include +#include +#include +#include +#include +#include + #include #include #include -#include -#include -#include -#include +#include namespace gtsam { @@ -37,8 +39,10 @@ namespace gtsam std::pair, boost::shared_ptr > EliminateSymbolic(const FactorGraph& factors, const Ordering& keys) { + gttic(EliminateSymbolic); + // Gather all keys - FastSet allKeys; + KeySet allKeys; BOOST_FOREACH(const boost::shared_ptr& factor, factors) { allKeys.insert(factor->begin(), factor->end()); } @@ -50,7 +54,7 @@ namespace gtsam } // Sort frontal keys - FastSet frontals(keys); + KeySet frontals(keys); const size_t nFrontals = keys.size(); // Build a key vector with the frontals followed by the separator diff --git a/gtsam/symbolic/tests/testSymbolicBayesTree.cpp b/gtsam/symbolic/tests/testSymbolicBayesTree.cpp index 3c02f6dbd..93c38b324 100644 --- a/gtsam/symbolic/tests/testSymbolicBayesTree.cpp +++ b/gtsam/symbolic/tests/testSymbolicBayesTree.cpp @@ -691,6 +691,76 @@ TEST(SymbolicBayesTree, complicatedMarginal) } } + +/* ************************************************************************* */ +TEST(SymbolicBayesTree, COLAMDvsMETIS) { + + // create circular graph + SymbolicFactorGraph sfg; + sfg.push_factor(0, 1); + sfg.push_factor(1, 2); + sfg.push_factor(2, 3); + sfg.push_factor(3, 4); + sfg.push_factor(4, 5); + sfg.push_factor(0, 5); + + // COLAMD + { + Ordering ordering = Ordering::Create(Ordering::COLAMD, sfg); + EXPECT(assert_equal(Ordering(list_of(0)(5)(1)(4)(2)(3)), ordering)); + + // - P( 4 2 3) + // | - P( 1 | 2 4) + // | | - P( 5 | 1 4) + // | | | - P( 0 | 1 5) + SymbolicBayesTree expected; + expected.insertRoot( + MakeClique(list_of(4)(2)(3), 3, + list_of( + MakeClique(list_of(1)(2)(4), 1, + list_of( + MakeClique(list_of(5)(1)(4), 1, + list_of(MakeClique(list_of(0)(1)(5), 1)))))))); + + SymbolicBayesTree actual = *sfg.eliminateMultifrontal(ordering); + EXPECT(assert_equal(expected, actual)); + } + + // METIS + { + Ordering ordering = Ordering::Create(Ordering::METIS, sfg); +// Linux and Mac split differently when using mettis +#if !defined(__APPLE__) + EXPECT(assert_equal(Ordering(list_of(3)(2)(5)(0)(4)(1)), ordering)); +#else + EXPECT(assert_equal(Ordering(list_of(5)(4)(2)(1)(0)(3)), ordering)); +#endif + + // - P( 1 0 3) + // | - P( 4 | 0 3) + // | | - P( 5 | 0 4) + // | - P( 2 | 1 3) + SymbolicBayesTree expected; +#if !defined(__APPLE__) + expected.insertRoot( + MakeClique(list_of(2)(4)(1), 3, + list_of( + MakeClique(list_of(0)(1)(4), 1, + list_of(MakeClique(list_of(5)(0)(4), 1))))( + MakeClique(list_of(3)(2)(4), 1)))); +#else + expected.insertRoot( + MakeClique(list_of(1)(0)(3), 3, + list_of( + MakeClique(list_of(4)(0)(3), 1, + list_of(MakeClique(list_of(5)(0)(4), 1))))( + MakeClique(list_of(2)(1)(3), 1)))); +#endif + SymbolicBayesTree actual = *sfg.eliminateMultifrontal(ordering); + EXPECT(assert_equal(expected, actual)); + } +} + /* ************************************************************************* */ int main() { TestResult tr; diff --git a/gtsam/symbolic/tests/testSymbolicJunctionTree.cpp b/gtsam/symbolic/tests/testSymbolicJunctionTree.cpp index 49b14bc07..f2d891827 100644 --- a/gtsam/symbolic/tests/testSymbolicJunctionTree.cpp +++ b/gtsam/symbolic/tests/testSymbolicJunctionTree.cpp @@ -46,10 +46,10 @@ TEST( JunctionTree, constructor ) frontal1 = list_of(2)(3), frontal2 = list_of(0)(1), sep1, sep2 = list_of(2); - EXPECT(assert_container_equality(frontal1, actual.roots().front()->keys)); + EXPECT(assert_container_equality(frontal1, actual.roots().front()->orderedFrontalKeys)); //EXPECT(assert_equal(sep1, actual.roots().front()->separator)); LONGS_EQUAL(1, (long)actual.roots().front()->factors.size()); - EXPECT(assert_container_equality(frontal2, actual.roots().front()->children.front()->keys)); + EXPECT(assert_container_equality(frontal2, actual.roots().front()->children.front()->orderedFrontalKeys)); //EXPECT(assert_equal(sep2, actual.roots().front()->children.front()->separator)); LONGS_EQUAL(2, (long)actual.roots().front()->children.front()->factors.size()); EXPECT(assert_equal(*simpleChain[2], *actual.roots().front()->factors[0])); diff --git a/gtsam_unstable/discrete/tests/testLoopyBelief.cpp b/gtsam_unstable/discrete/tests/testLoopyBelief.cpp index b579364b6..37a4fe5a4 100644 --- a/gtsam_unstable/discrete/tests/testLoopyBelief.cpp +++ b/gtsam_unstable/discrete/tests/testLoopyBelief.cpp @@ -193,7 +193,7 @@ private: // add the belief factor for each neighbor variable to this star graph // also record the factor index for later modification - FastSet neighbors = star->keys(); + KeySet neighbors = star->keys(); neighbors.erase(key); CorrectedBeliefIndices correctedBeliefIndices; BOOST_FOREACH(Key neighbor, neighbors) { diff --git a/gtsam_unstable/dynamics/PoseRTV.cpp b/gtsam_unstable/dynamics/PoseRTV.cpp index 942e1ab55..1a7fdf3de 100644 --- a/gtsam_unstable/dynamics/PoseRTV.cpp +++ b/gtsam_unstable/dynamics/PoseRTV.cpp @@ -38,13 +38,14 @@ Vector PoseRTV::vector() const { Vector rtv(9); rtv.head(3) = rotation().xyz(); rtv.segment(3,3) = translation().vector(); - rtv.tail(3) = velocity().vector(); + rtv.tail(3) = velocity(); return rtv; } /* ************************************************************************* */ bool PoseRTV::equals(const PoseRTV& other, double tol) const { - return pose().equals(other.pose(), tol) && velocity().equals(other.velocity(), tol); + return pose().equals(other.pose(), tol) + && equal_with_abs_tol(velocity(), other.velocity(), tol); } /* ************************************************************************* */ @@ -52,7 +53,7 @@ void PoseRTV::print(const string& s) const { cout << s << ":" << endl; gtsam::print((Vector)R().xyz(), " R:rpy"); t().print(" T"); - velocity().print(" V"); + gtsam::print((Vector)velocity(), " V"); } /* ************************************************************************* */ @@ -99,7 +100,7 @@ PoseRTV PoseRTV::flyingDynamics( double pitch2 = r2.pitch(); double forward_accel = -thrust * sin(pitch2); // r2, pitch (in global frame?) controls forward force double loss_lift = lift*fabs(sin(pitch2)); - Rot3 yaw_correction_bn = Rot3::yaw(yaw2); + Rot3 yaw_correction_bn = Rot3::Yaw(yaw2); Point3 forward(forward_accel, 0.0, 0.0); Vector Acc_n = yaw_correction_bn.rotate(forward).vector() // applies locally forward force in the global frame @@ -137,7 +138,7 @@ Vector6 PoseRTV::imuPrediction(const PoseRTV& x2, double dt) const { Vector6 imu; // acceleration - Vector3 accel = (v2-v1).vector() / dt; + Vector3 accel = (v2-v1) / dt; imu.head<3>() = r2.transpose() * (accel - kGravity); // rotation rates @@ -160,7 +161,7 @@ Vector6 PoseRTV::imuPrediction(const PoseRTV& x2, double dt) const { Point3 PoseRTV::translationIntegration(const Rot3& r2, const Velocity3& v2, double dt) const { // predict point for constraint // NOTE: uses simple Euler approach for prediction - Point3 pred_t2 = t() + v2 * dt; + Point3 pred_t2 = t().retract(v2 * dt); return pred_t2; } @@ -187,7 +188,7 @@ PoseRTV PoseRTV::transformed_from(const Pose3& trans, ChartJacobian Dglobal, // Note that we rotate the velocity Matrix3 D_newvel_R, D_newvel_v; - Velocity3 newvel = trans.rotation().rotate(velocity(), D_newvel_R, D_newvel_v); + Velocity3 newvel = trans.rotation().rotate(Point3(velocity()), D_newvel_R, D_newvel_v).vector(); if (Dglobal) { Dglobal->setZero(); @@ -204,10 +205,10 @@ PoseRTV PoseRTV::transformed_from(const Pose3& trans, ChartJacobian Dglobal, } /* ************************************************************************* */ -Matrix PoseRTV::RRTMbn(const Vector& euler) { +Matrix PoseRTV::RRTMbn(const Vector3& euler) { assert(euler.size() == 3); - const double s1 = sin(euler(1-1)), c1 = cos(euler(1-1)); - const double t2 = tan(euler(2-1)), c2 = cos(euler(2-1)); + const double s1 = sin(euler.x()), c1 = cos(euler.x()); + const double t2 = tan(euler.y()), c2 = cos(euler.y()); Matrix Ebn(3,3); Ebn << 1.0, s1 * t2, c1 * t2, 0.0, c1, -s1, @@ -221,11 +222,10 @@ Matrix PoseRTV::RRTMbn(const Rot3& att) { } /* ************************************************************************* */ -Matrix PoseRTV::RRTMnb(const Vector& euler) { - assert(euler.size() == 3); +Matrix PoseRTV::RRTMnb(const Vector3& euler) { Matrix Enb(3,3); - const double s1 = sin(euler(1-1)), c1 = cos(euler(1-1)); - const double s2 = sin(euler(2-1)), c2 = cos(euler(2-1)); + const double s1 = sin(euler.x()), c1 = cos(euler.x()); + const double s2 = sin(euler.y()), c2 = cos(euler.y()); Enb << 1.0, 0.0, -s2, 0.0, c1, s1*c2, 0.0, -s1, c1*c2; diff --git a/gtsam_unstable/dynamics/PoseRTV.h b/gtsam_unstable/dynamics/PoseRTV.h index 78bd1fe6f..b59ea4614 100644 --- a/gtsam_unstable/dynamics/PoseRTV.h +++ b/gtsam_unstable/dynamics/PoseRTV.h @@ -13,11 +13,12 @@ namespace gtsam { /// Syntactic sugar to clarify components -typedef Point3 Velocity3; +typedef Vector3 Velocity3; /** * Robot state for use with IMU measurements * - contains translation, translational velocity and rotation + * TODO(frank): Alex should deprecate/move to project */ class GTSAM_UNSTABLE_EXPORT PoseRTV : public ProductLieGroup { protected: @@ -34,11 +35,11 @@ public: PoseRTV(const Rot3& rot, const Point3& t, const Velocity3& vel) : Base(Pose3(rot, t), vel) {} explicit PoseRTV(const Point3& t) - : Base(Pose3(Rot3(), t),Velocity3()) {} + : Base(Pose3(Rot3(), t),Vector3::Zero()) {} PoseRTV(const Pose3& pose, const Velocity3& vel) : Base(pose, vel) {} explicit PoseRTV(const Pose3& pose) - : Base(pose,Velocity3()) {} + : Base(pose,Vector3::Zero()) {} // Construct from Base PoseRTV(const Base& base) @@ -66,7 +67,7 @@ public: // and avoidance of Point3 Vector vector() const; Vector translationVec() const { return pose().translation().vector(); } - Vector velocityVec() const { return velocity().vector(); } + const Velocity3& velocityVec() const { return velocity(); } // testable bool equals(const PoseRTV& other, double tol=1e-6) const; @@ -145,14 +146,12 @@ public: /// RRTMbn - Function computes the rotation rate transformation matrix from /// body axis rates to euler angle (global) rates - static Matrix RRTMbn(const Vector& euler); - + static Matrix RRTMbn(const Vector3& euler); static Matrix RRTMbn(const Rot3& att); /// RRTMnb - Function computes the rotation rate transformation matrix from /// euler angle rates to body axis rates - static Matrix RRTMnb(const Vector& euler); - + static Matrix RRTMnb(const Vector3& euler); static Matrix RRTMnb(const Rot3& att); /// @} @@ -170,4 +169,10 @@ private: template<> struct traits : public internal::LieGroup {}; +// Define Range functor specializations that are used in RangeFactor +template struct Range; + +template<> +struct Range : HasRange {}; + } // \namespace gtsam diff --git a/gtsam_unstable/dynamics/VelocityConstraint.h b/gtsam_unstable/dynamics/VelocityConstraint.h index c9db449f9..c41ea220c 100644 --- a/gtsam_unstable/dynamics/VelocityConstraint.h +++ b/gtsam_unstable/dynamics/VelocityConstraint.h @@ -106,12 +106,13 @@ private: static gtsam::Vector evaluateError_(const PoseRTV& x1, const PoseRTV& x2, double dt, const dynamics::IntegrationMode& mode) { - const Velocity3& v1 = x1.v(), v2 = x2.v(), p1 = x1.t(), p2 = x2.t(); - Velocity3 hx; + const Velocity3& v1 = x1.v(), v2 = x2.v(); + const Point3& p1 = x1.t(), p2 = x2.t(); + Point3 hx; switch(mode) { - case dynamics::TRAPEZOIDAL: hx = p1 + (v1 + v2) * dt *0.5; break; - case dynamics::EULER_START: hx = p1 + v1 * dt; break; - case dynamics::EULER_END : hx = p1 + v2 * dt; break; + case dynamics::TRAPEZOIDAL: hx = p1.retract((v1 + v2) * dt *0.5); break; + case dynamics::EULER_START: hx = p1.retract(v1 * dt); break; + case dynamics::EULER_END : hx = p1.retract(v2 * dt); break; default: assert(false); break; } return (p2 - hx).vector(); diff --git a/gtsam_unstable/dynamics/tests/testIMUSystem.cpp b/gtsam_unstable/dynamics/tests/testIMUSystem.cpp index d97f185e7..3fc6a0197 100644 --- a/gtsam_unstable/dynamics/tests/testIMUSystem.cpp +++ b/gtsam_unstable/dynamics/tests/testIMUSystem.cpp @@ -9,7 +9,7 @@ #include #include -#include +#include #include #include #include @@ -56,9 +56,9 @@ TEST( testIMUSystem, optimize_chain ) { // create a simple chain of poses to generate IMU measurements const double dt = 1.0; PoseRTV pose1, - pose2(Point3(1.0, 1.0, 0.0), Rot3::ypr(0.1, 0.0, 0.0), Point3(2.0, 2.0, 0.0)), - pose3(Point3(2.0, 2.0, 0.0), Rot3::ypr(0.2, 0.0, 0.0), Point3(0.0, 0.0, 0.0)), - pose4(Point3(3.0, 3.0, 0.0), Rot3::ypr(0.3, 0.0, 0.0), Point3(2.0, 2.0, 0.0)); + pose2(Point3(1.0, 1.0, 0.0), Rot3::Ypr(0.1, 0.0, 0.0), Velocity3(2.0, 2.0, 0.0)), + pose3(Point3(2.0, 2.0, 0.0), Rot3::Ypr(0.2, 0.0, 0.0), Velocity3(0.0, 0.0, 0.0)), + pose4(Point3(3.0, 3.0, 0.0), Rot3::Ypr(0.3, 0.0, 0.0), Velocity3(2.0, 2.0, 0.0)); // create measurements SharedDiagonal model = noiseModel::Unit::Create(6); @@ -102,9 +102,9 @@ TEST( testIMUSystem, optimize_chain_fullfactor ) { // create a simple chain of poses to generate IMU measurements const double dt = 1.0; PoseRTV pose1, - pose2(Point3(1.0, 0.0, 0.0), Rot3::ypr(0.0, 0.0, 0.0), Point3(1.0, 0.0, 0.0)), - pose3(Point3(2.0, 0.0, 0.0), Rot3::ypr(0.0, 0.0, 0.0), Point3(1.0, 0.0, 0.0)), - pose4(Point3(3.0, 0.0, 0.0), Rot3::ypr(0.0, 0.0, 0.0), Point3(1.0, 0.0, 0.0)); + pose2(Point3(1.0, 0.0, 0.0), Rot3::Ypr(0.0, 0.0, 0.0), Velocity3(1.0, 0.0, 0.0)), + pose3(Point3(2.0, 0.0, 0.0), Rot3::Ypr(0.0, 0.0, 0.0), Velocity3(1.0, 0.0, 0.0)), + pose4(Point3(3.0, 0.0, 0.0), Rot3::Ypr(0.0, 0.0, 0.0), Velocity3(1.0, 0.0, 0.0)); // create measurements SharedDiagonal model = noiseModel::Isotropic::Sigma(9, 1.0); diff --git a/gtsam_unstable/dynamics/tests/testPoseRTV.cpp b/gtsam_unstable/dynamics/tests/testPoseRTV.cpp index 2ea582292..db2f8f7f8 100644 --- a/gtsam_unstable/dynamics/tests/testPoseRTV.cpp +++ b/gtsam_unstable/dynamics/tests/testPoseRTV.cpp @@ -15,44 +15,43 @@ using namespace gtsam; GTSAM_CONCEPT_TESTABLE_INST(PoseRTV) GTSAM_CONCEPT_LIE_INST(PoseRTV) -const double tol=1e-5; - -Rot3 rot = Rot3::RzRyRx(0.1, 0.2, 0.3); -Point3 pt(1.0, 2.0, 3.0); -Velocity3 vel(0.4, 0.5, 0.6); +static const Rot3 rot = Rot3::RzRyRx(0.1, 0.2, 0.3); +static const Point3 pt(1.0, 2.0, 3.0); +static const Velocity3 vel(0.4, 0.5, 0.6); +static const Vector3 kZero3 = Vector3::Zero(); /* ************************************************************************* */ TEST( testPoseRTV, constructors ) { PoseRTV state1(pt, rot, vel); - EXPECT(assert_equal(pt, state1.t(), tol)); - EXPECT(assert_equal(rot, state1.R(), tol)); - EXPECT(assert_equal(vel, state1.v(), tol)); - EXPECT(assert_equal(Pose3(rot, pt), state1.pose(), tol)); + EXPECT(assert_equal(pt, state1.t())); + EXPECT(assert_equal(rot, state1.R())); + EXPECT(assert_equal(vel, state1.v())); + EXPECT(assert_equal(Pose3(rot, pt), state1.pose())); PoseRTV state2; - EXPECT(assert_equal(Point3(), state2.t(), tol)); - EXPECT(assert_equal(Rot3(), state2.R(), tol)); - EXPECT(assert_equal(Velocity3(), state2.v(), tol)); - EXPECT(assert_equal(Pose3(), state2.pose(), tol)); + EXPECT(assert_equal(Point3(), state2.t())); + EXPECT(assert_equal(Rot3(), state2.R())); + EXPECT(assert_equal(kZero3, state2.v())); + EXPECT(assert_equal(Pose3(), state2.pose())); PoseRTV state3(Pose3(rot, pt), vel); - EXPECT(assert_equal(pt, state3.t(), tol)); - EXPECT(assert_equal(rot, state3.R(), tol)); - EXPECT(assert_equal(vel, state3.v(), tol)); - EXPECT(assert_equal(Pose3(rot, pt), state3.pose(), tol)); + EXPECT(assert_equal(pt, state3.t())); + EXPECT(assert_equal(rot, state3.R())); + EXPECT(assert_equal(vel, state3.v())); + EXPECT(assert_equal(Pose3(rot, pt), state3.pose())); PoseRTV state4(Pose3(rot, pt)); - EXPECT(assert_equal(pt, state4.t(), tol)); - EXPECT(assert_equal(rot, state4.R(), tol)); - EXPECT(assert_equal(Velocity3(), state4.v(), tol)); - EXPECT(assert_equal(Pose3(rot, pt), state4.pose(), tol)); + EXPECT(assert_equal(pt, state4.t())); + EXPECT(assert_equal(rot, state4.R())); + EXPECT(assert_equal(kZero3, state4.v())); + EXPECT(assert_equal(Pose3(rot, pt), state4.pose())); Vector vec_init = (Vector(9) << 0.1, 0.2, 0.3, 1.0, 2.0, 3.0, 0.4, 0.5, 0.6).finished(); PoseRTV state5(vec_init); - EXPECT(assert_equal(pt, state5.t(), tol)); - EXPECT(assert_equal(rot, state5.R(), tol)); - EXPECT(assert_equal(vel, state5.v(), tol)); - EXPECT(assert_equal(vec_init, state5.vector(), tol)); + EXPECT(assert_equal(pt, state5.t())); + EXPECT(assert_equal(rot, state5.R())); + EXPECT(assert_equal(vel, state5.v())); + EXPECT(assert_equal(vec_init, state5.vector())); } /* ************************************************************************* */ @@ -65,33 +64,44 @@ TEST( testPoseRTV, dim ) { /* ************************************************************************* */ TEST( testPoseRTV, equals ) { PoseRTV state1, state2(pt, rot, vel), state3(state2), state4(Pose3(rot, pt)); - EXPECT(assert_equal(state1, state1, tol)); - EXPECT(assert_equal(state2, state3, tol)); - EXPECT(assert_equal(state3, state2, tol)); - EXPECT(assert_inequal(state1, state2, tol)); - EXPECT(assert_inequal(state2, state1, tol)); - EXPECT(assert_inequal(state2, state4, tol)); + EXPECT(assert_equal(state1, state1)); + EXPECT(assert_equal(state2, state3)); + EXPECT(assert_equal(state3, state2)); + EXPECT(assert_inequal(state1, state2)); + EXPECT(assert_inequal(state2, state1)); + EXPECT(assert_inequal(state2, state4)); } /* ************************************************************************* */ TEST( testPoseRTV, Lie ) { // origin and zero deltas PoseRTV identity; - EXPECT(assert_equal(identity, (PoseRTV)identity.retract(zero(9)), tol)); - EXPECT(assert_equal(zero(9), identity.localCoordinates(identity), tol)); + EXPECT(assert_equal(identity, (PoseRTV)identity.retract(zero(9)))); + EXPECT(assert_equal(zero(9), identity.localCoordinates(identity))); PoseRTV state1(pt, rot, vel); - EXPECT(assert_equal(state1, (PoseRTV)state1.retract(zero(9)), tol)); - EXPECT(assert_equal(zero(9), state1.localCoordinates(state1), tol)); + EXPECT(assert_equal(state1, (PoseRTV)state1.retract(zero(9)))); + EXPECT(assert_equal(zero(9), state1.localCoordinates(state1))); - Vector delta = (Vector(9) << 0.1, 0.1, 0.1, 0.2, 0.3, 0.4,-0.1,-0.2,-0.3).finished(); - Rot3 rot2 = rot.retract(repeat(3, 0.1)); - Point3 pt2 = pt + rot * Point3(0.2, 0.3, 0.4); - Velocity3 vel2 = vel + rot * Velocity3(-0.1,-0.2,-0.3); - PoseRTV state2(pt2, rot2, vel2); - EXPECT(assert_equal(state2, (PoseRTV)state1.retract(delta), 1e-1)); - EXPECT(assert_equal(delta, state1.localCoordinates(state2), 1e-1)); - EXPECT(assert_equal(delta, -state2.localCoordinates(state1), 1e-1)); + Vector delta(9); + delta << 0.1, 0.1, 0.1, 0.2, 0.3, 0.4,-0.1,-0.2,-0.3; + Pose3 pose2 = Pose3(rot, pt).retract(delta.head<6>()); + Velocity3 vel2 = vel + Velocity3(-0.1, -0.2, -0.3); + PoseRTV state2(pose2.translation(), pose2.rotation(), vel2); + EXPECT(assert_equal(state2, (PoseRTV)state1.retract(delta))); + EXPECT(assert_equal(delta, state1.localCoordinates(state2))); + + // roundtrip from state2 to state3 and back + PoseRTV state3 = state2.retract(delta); + EXPECT(assert_equal(delta, state2.localCoordinates(state3))); + + // roundtrip from state3 to state4 and back, with expmap. + PoseRTV state4 = state3.expmap(delta); + EXPECT(assert_equal(delta, state3.logmap(state4))); + + // For the expmap/logmap (not necessarily retract/local) -delta goes other way + EXPECT(assert_equal(state3, (PoseRTV)state4.expmap(-delta))); + EXPECT(assert_equal(delta, -state4.logmap(state3))); } /* ************************************************************************* */ @@ -108,15 +118,15 @@ TEST( testPoseRTV, dynamics_identities ) { x3 = x2.generalDynamics(accel, gyro, dt); x4 = x3.generalDynamics(accel, gyro, dt); -// EXPECT(assert_equal(imu01, x0.imuPrediction(x1, dt).first, tol)); -// EXPECT(assert_equal(imu12, x1.imuPrediction(x2, dt).first, tol)); -// EXPECT(assert_equal(imu23, x2.imuPrediction(x3, dt).first, tol)); -// EXPECT(assert_equal(imu34, x3.imuPrediction(x4, dt).first, tol)); +// EXPECT(assert_equal(imu01, x0.imuPrediction(x1, dt).first)); +// EXPECT(assert_equal(imu12, x1.imuPrediction(x2, dt).first)); +// EXPECT(assert_equal(imu23, x2.imuPrediction(x3, dt).first)); +// EXPECT(assert_equal(imu34, x3.imuPrediction(x4, dt).first)); // -// EXPECT(assert_equal(x1.translation(), x0.imuPrediction(x1, dt).second, tol)); -// EXPECT(assert_equal(x2.translation(), x1.imuPrediction(x2, dt).second, tol)); -// EXPECT(assert_equal(x3.translation(), x2.imuPrediction(x3, dt).second, tol)); -// EXPECT(assert_equal(x4.translation(), x3.imuPrediction(x4, dt).second, tol)); +// EXPECT(assert_equal(x1.translation(), x0.imuPrediction(x1, dt).second)); +// EXPECT(assert_equal(x2.translation(), x1.imuPrediction(x2, dt).second)); +// EXPECT(assert_equal(x3.translation(), x2.imuPrediction(x3, dt).second)); +// EXPECT(assert_equal(x4.translation(), x3.imuPrediction(x4, dt).second)); } @@ -129,8 +139,8 @@ TEST( testPoseRTV, compose ) { state1.compose(state2, actH1, actH2); Matrix numericH1 = numericalDerivative21(compose_proxy, state1, state2); Matrix numericH2 = numericalDerivative22(compose_proxy, state1, state2); - EXPECT(assert_equal(numericH1, actH1, tol)); - EXPECT(assert_equal(numericH2, actH2, tol)); + EXPECT(assert_equal(numericH1, actH1)); + EXPECT(assert_equal(numericH2, actH2)); } /* ************************************************************************* */ @@ -142,8 +152,8 @@ TEST( testPoseRTV, between ) { state1.between(state2, actH1, actH2); Matrix numericH1 = numericalDerivative21(between_proxy, state1, state2); Matrix numericH2 = numericalDerivative22(between_proxy, state1, state2); - EXPECT(assert_equal(numericH1, actH1, tol)); - EXPECT(assert_equal(numericH2, actH2, tol)); + EXPECT(assert_equal(numericH1, actH1)); + EXPECT(assert_equal(numericH2, actH2)); } /* ************************************************************************* */ @@ -154,7 +164,7 @@ TEST( testPoseRTV, inverse ) { Matrix actH1; state1.inverse(actH1); Matrix numericH1 = numericalDerivative11(inverse_proxy, state1); - EXPECT(assert_equal(numericH1, actH1, tol)); + EXPECT(assert_equal(numericH1, actH1)); } /* ************************************************************************* */ @@ -162,16 +172,16 @@ double range_proxy(const PoseRTV& A, const PoseRTV& B) { return A.range(B); } TEST( testPoseRTV, range ) { Point3 tA(1.0, 2.0, 3.0), tB(3.0, 2.0, 3.0); PoseRTV rtvA(tA), rtvB(tB); - EXPECT_DOUBLES_EQUAL(0.0, rtvA.range(rtvA), tol); - EXPECT_DOUBLES_EQUAL(2.0, rtvA.range(rtvB), tol); - EXPECT_DOUBLES_EQUAL(2.0, rtvB.range(rtvA), tol); + EXPECT_DOUBLES_EQUAL(0.0, rtvA.range(rtvA), 1e-9); + EXPECT_DOUBLES_EQUAL(2.0, rtvA.range(rtvB), 1e-9); + EXPECT_DOUBLES_EQUAL(2.0, rtvB.range(rtvA), 1e-9); Matrix actH1, actH2; rtvA.range(rtvB, actH1, actH2); Matrix numericH1 = numericalDerivative21(range_proxy, rtvA, rtvB); Matrix numericH2 = numericalDerivative22(range_proxy, rtvA, rtvB); - EXPECT(assert_equal(numericH1, actH1, tol)); - EXPECT(assert_equal(numericH2, actH2, tol)); + EXPECT(assert_equal(numericH1, actH1)); + EXPECT(assert_equal(numericH2, actH2)); } /* ************************************************************************* */ @@ -179,21 +189,21 @@ PoseRTV transformed_from_proxy(const PoseRTV& a, const Pose3& trans) { return a.transformed_from(trans); } TEST( testPoseRTV, transformed_from_1 ) { - Rot3 R = Rot3::rodriguez(0.1, 0.2, 0.3); + Rot3 R = Rot3::Rodrigues(0.1, 0.2, 0.3); Point3 T(1.0, 2.0, 3.0); Velocity3 V(2.0, 3.0, 4.0); PoseRTV start(R, T, V); - Pose3 transform(Rot3::yaw(M_PI_2), Point3(1.0, 2.0, 3.0)); + Pose3 transform(Rot3::Yaw(M_PI_2), Point3(1.0, 2.0, 3.0)); Matrix actDTrans, actDGlobal; PoseRTV actual = start.transformed_from(transform, actDGlobal, actDTrans); - PoseRTV expected(transform.compose(start.pose()), transform.rotation().rotate(V)); - EXPECT(assert_equal(expected, actual, tol)); + PoseRTV expected(transform.compose(start.pose()), transform.rotation().matrix() * V); + EXPECT(assert_equal(expected, actual)); Matrix numDGlobal = numericalDerivative21(transformed_from_proxy, start, transform, 1e-5); // At 1e-8, fails Matrix numDTrans = numericalDerivative22(transformed_from_proxy, start, transform, 1e-8); // Sensitive to step size - EXPECT(assert_equal(numDGlobal, actDGlobal, tol)); - EXPECT(assert_equal(numDTrans, actDTrans, tol)); // FIXME: still needs analytic derivative + EXPECT(assert_equal(numDGlobal, actDGlobal)); + EXPECT(assert_equal(numDTrans, actDTrans, 1e-5)); // FIXME: still needs analytic derivative } /* ************************************************************************* */ @@ -202,31 +212,31 @@ TEST( testPoseRTV, transformed_from_2 ) { Point3 T(1.0, 2.0, 3.0); Velocity3 V(2.0, 3.0, 4.0); PoseRTV start(R, T, V); - Pose3 transform(Rot3::yaw(M_PI_2), Point3(1.0, 2.0, 3.0)); + Pose3 transform(Rot3::Yaw(M_PI_2), Point3(1.0, 2.0, 3.0)); Matrix actDTrans, actDGlobal; PoseRTV actual = start.transformed_from(transform, actDGlobal, actDTrans); - PoseRTV expected(transform.compose(start.pose()), transform.rotation().rotate(V)); - EXPECT(assert_equal(expected, actual, tol)); + PoseRTV expected(transform.compose(start.pose()), transform.rotation().matrix() * V); + EXPECT(assert_equal(expected, actual)); Matrix numDGlobal = numericalDerivative21(transformed_from_proxy, start, transform, 1e-5); // At 1e-8, fails Matrix numDTrans = numericalDerivative22(transformed_from_proxy, start, transform, 1e-8); // Sensitive to step size - EXPECT(assert_equal(numDGlobal, actDGlobal, tol)); - EXPECT(assert_equal(numDTrans, actDTrans, tol)); // FIXME: still needs analytic derivative + EXPECT(assert_equal(numDGlobal, actDGlobal)); + EXPECT(assert_equal(numDTrans, actDTrans, 1e-5)); // FIXME: still needs analytic derivative } /* ************************************************************************* */ TEST(testPoseRTV, RRTMbn) { - EXPECT(assert_equal(Matrix::Identity(3,3), PoseRTV::RRTMbn(zero(3)), tol)); - EXPECT(assert_equal(Matrix::Identity(3,3), PoseRTV::RRTMbn(Rot3()), tol)); - EXPECT(assert_equal(PoseRTV::RRTMbn(Vector3(0.3, 0.2, 0.1)), PoseRTV::RRTMbn(Rot3::ypr(0.1, 0.2, 0.3)), tol)); + EXPECT(assert_equal(Matrix::Identity(3,3), PoseRTV::RRTMbn(kZero3))); + EXPECT(assert_equal(Matrix::Identity(3,3), PoseRTV::RRTMbn(Rot3()))); + EXPECT(assert_equal(PoseRTV::RRTMbn(Vector3(0.3, 0.2, 0.1)), PoseRTV::RRTMbn(Rot3::Ypr(0.1, 0.2, 0.3)))); } /* ************************************************************************* */ TEST(testPoseRTV, RRTMnb) { - EXPECT(assert_equal(Matrix::Identity(3,3), PoseRTV::RRTMnb(zero(3)), tol)); - EXPECT(assert_equal(Matrix::Identity(3,3), PoseRTV::RRTMnb(Rot3()), tol)); - EXPECT(assert_equal(PoseRTV::RRTMnb(Vector3(0.3, 0.2, 0.1)), PoseRTV::RRTMnb(Rot3::ypr(0.1, 0.2, 0.3)), tol)); + EXPECT(assert_equal(Matrix::Identity(3,3), PoseRTV::RRTMnb(kZero3))); + EXPECT(assert_equal(Matrix::Identity(3,3), PoseRTV::RRTMnb(Rot3()))); + EXPECT(assert_equal(PoseRTV::RRTMnb(Vector3(0.3, 0.2, 0.1)), PoseRTV::RRTMnb(Rot3::Ypr(0.1, 0.2, 0.3)))); } /* ************************************************************************* */ diff --git a/gtsam_unstable/dynamics/tests/testSimpleHelicopter.cpp b/gtsam_unstable/dynamics/tests/testSimpleHelicopter.cpp index a0d969c4d..1fb2cf39e 100644 --- a/gtsam_unstable/dynamics/tests/testSimpleHelicopter.cpp +++ b/gtsam_unstable/dynamics/tests/testSimpleHelicopter.cpp @@ -16,7 +16,7 @@ const double tol=1e-5; const double h = 0.01; //const double deg2rad = M_PI/180.0; -//Pose3 g1(Rot3::ypr(deg2rad*10.0, deg2rad*20.0, deg2rad*30.0), Point3(100.0, 200.0, 300.0)); +//Pose3 g1(Rot3::Ypr(deg2rad*10.0, deg2rad*20.0, deg2rad*30.0), Point3(100.0, 200.0, 300.0)); Pose3 g1(Rot3(), Point3(100.0, 0.0, 300.0)); //Vector6 v1((Vector(6) << 0.1, 0.05, 0.02, 10.0, 20.0, 30.0).finished()); Vector6 V1_w((Vector(6) << 0.0, 0.0, M_PI/3, 0.0, 0.0, 30.0).finished()); diff --git a/gtsam_unstable/dynamics/tests/testVelocityConstraint.cpp b/gtsam_unstable/dynamics/tests/testVelocityConstraint.cpp index 56d38714a..f253be371 100644 --- a/gtsam_unstable/dynamics/tests/testVelocityConstraint.cpp +++ b/gtsam_unstable/dynamics/tests/testVelocityConstraint.cpp @@ -15,9 +15,9 @@ const Key x1 = 1, x2 = 2; const double dt = 1.0; PoseRTV origin, - pose1(Point3(0.5, 0.0, 0.0), Rot3::identity(), Point3(1.0, 0.0, 0.0)), + pose1(Point3(0.5, 0.0, 0.0), Rot3::identity(), Velocity3(1.0, 0.0, 0.0)), pose1a(Point3(0.5, 0.0, 0.0)), - pose2(Point3(1.5, 0.0, 0.0), Rot3::identity(), Point3(1.0, 0.0, 0.0)); + pose2(Point3(1.5, 0.0, 0.0), Rot3::identity(), Velocity3(1.0, 0.0, 0.0)); /* ************************************************************************* */ TEST( testVelocityConstraint, trapezoidal ) { diff --git a/gtsam_unstable/examples/SmartProjectionFactorExample.cpp b/gtsam_unstable/examples/SmartProjectionFactorExample.cpp index dc921a7da..de1d3f77b 100644 --- a/gtsam_unstable/examples/SmartProjectionFactorExample.cpp +++ b/gtsam_unstable/examples/SmartProjectionFactorExample.cpp @@ -26,16 +26,14 @@ * -makes monocular observations of many landmarks */ -#include +#include +#include #include #include #include #include #include #include -#include - -#include #include #include @@ -46,6 +44,7 @@ using namespace gtsam; int main(int argc, char** argv){ + typedef PinholePose Camera; typedef SmartProjectionPoseFactor SmartFactor; Values initial_estimate; @@ -55,7 +54,7 @@ int main(int argc, char** argv){ string calibration_loc = findExampleDataFile("VO_calibration.txt"); string pose_loc = findExampleDataFile("VO_camera_poses_large.txt"); string factor_loc = findExampleDataFile("VO_stereo_factors_large.txt"); - + //read camera calibration info from file // focal lengths fx, fy, skew s, principal point u0, v0, baseline b cout << "Reading calibration info" << endl; @@ -68,18 +67,17 @@ int main(int argc, char** argv){ cout << "Reading camera poses" << endl; ifstream pose_file(pose_loc.c_str()); - int pose_id; + int pose_index; MatrixRowMajor m(4,4); //read camera pose parameters and use to make initial estimates of camera poses - while (pose_file >> pose_id) { - for (int i = 0; i < 16; i++) { + while (pose_file >> pose_index) { + for (int i = 0; i < 16; i++) pose_file >> m.data()[i]; - } - initial_estimate.insert(Symbol('x', pose_id), Pose3(m)); + initial_estimate.insert(pose_index, Pose3(m)); } - - // camera and landmark keys - size_t x, l; + + // landmark keys + size_t landmark_key; // pixel coordinates uL, uR, v (same for left/right images due to rectification) // landmark coordinates X, Y, Z in camera frame, resulting from triangulation @@ -89,24 +87,24 @@ int main(int argc, char** argv){ //read stereo measurements and construct smart factors - SmartFactor::shared_ptr factor(new SmartFactor()); + SmartFactor::shared_ptr factor(new SmartFactor(model, K)); size_t current_l = 3; // hardcoded landmark ID from first measurement - while (factor_file >> x >> l >> uL >> uR >> v >> X >> Y >> Z) { + while (factor_file >> pose_index >> landmark_key >> uL >> uR >> v >> X >> Y >> Z) { - if(current_l != l) { + if(current_l != landmark_key) { graph.push_back(factor); - factor = SmartFactor::shared_ptr(new SmartFactor()); - current_l = l; + factor = SmartFactor::shared_ptr(new SmartFactor(model, K)); + current_l = landmark_key; } - factor->add(Point2(uL,v), Symbol('x',x), model, K); + factor->add(Point2(uL,v), pose_index); } - Pose3 first_pose = initial_estimate.at(Symbol('x',1)); + Pose3 firstPose = initial_estimate.at(1); //constrain the first pose such that it cannot change from its original value during optimization // NOTE: NonlinearEquality forces the optimizer to use QR rather than Cholesky // QR is much slower than Cholesky, but numerically more stable - graph.push_back(NonlinearEquality(Symbol('x',1),first_pose)); + graph.push_back(NonlinearEquality(1,firstPose)); LevenbergMarquardtParams params; params.verbosityLM = LevenbergMarquardtParams::TRYLAMBDA; diff --git a/gtsam_unstable/examples/SmartRangeExample_plaza1.cpp b/gtsam_unstable/examples/SmartRangeExample_plaza1.cpp index 6cc8a7b78..4062d0659 100644 --- a/gtsam_unstable/examples/SmartRangeExample_plaza1.cpp +++ b/gtsam_unstable/examples/SmartRangeExample_plaza1.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/gtsam_unstable/examples/SmartRangeExample_plaza2.cpp b/gtsam_unstable/examples/SmartRangeExample_plaza2.cpp index b689179a2..90d92897e 100644 --- a/gtsam_unstable/examples/SmartRangeExample_plaza2.cpp +++ b/gtsam_unstable/examples/SmartRangeExample_plaza2.cpp @@ -39,7 +39,7 @@ // have been provided with the library for solving robotics SLAM problems. #include #include -#include +#include // Standard headers, added last, so we know headers above work on their own #include diff --git a/gtsam_unstable/examples/SmartStereoProjectionFactorExample.cpp b/gtsam_unstable/examples/SmartStereoProjectionFactorExample.cpp index ac2c31077..d3680460f 100644 --- a/gtsam_unstable/examples/SmartStereoProjectionFactorExample.cpp +++ b/gtsam_unstable/examples/SmartStereoProjectionFactorExample.cpp @@ -46,7 +46,7 @@ using namespace gtsam; int main(int argc, char** argv){ - typedef SmartStereoProjectionPoseFactor SmartFactor; + typedef SmartStereoProjectionPoseFactor SmartFactor; bool output_poses = true; string poseOutput("../../../examples/data/optimized_poses.txt"); @@ -109,17 +109,17 @@ int main(int argc, char** argv){ //read stereo measurements and construct smart factors - SmartFactor::shared_ptr factor(new SmartFactor()); + SmartFactor::shared_ptr factor(new SmartFactor(model)); size_t current_l = 3; // hardcoded landmark ID from first measurement while (factor_file >> x >> l >> uL >> uR >> v >> X >> Y >> Z) { if(current_l != l) { graph.push_back(factor); - factor = SmartFactor::shared_ptr(new SmartFactor()); + factor = SmartFactor::shared_ptr(new SmartFactor(model)); current_l = l; } - factor->add(StereoPoint2(uL,uR,v), Symbol('x',x), model, K); + factor->add(StereoPoint2(uL,uR,v), Symbol('x',x), K); } Pose3 first_pose = initial_estimate.at(Symbol('x',1)); diff --git a/gtsam_unstable/geometry/Event.cpp b/gtsam_unstable/geometry/Event.cpp new file mode 100644 index 000000000..68d4d60ce --- /dev/null +++ b/gtsam_unstable/geometry/Event.cpp @@ -0,0 +1,29 @@ +/* ---------------------------------------------------------------------------- + + * 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 Event + * @brief Space-time event + * @author Frank Dellaert + * @author Jay Chakravarty + * @date December 2014 + */ + +#include + +namespace gtsam { + +const double Event::Speed = 330; +const Matrix14 Event::JacobianZ = (Matrix14() << 0,0,0,1).finished(); + +} + + diff --git a/gtsam_unstable/geometry/Event.h b/gtsam_unstable/geometry/Event.h index 9d35331bb..3c622924a 100644 --- a/gtsam_unstable/geometry/Event.h +++ b/gtsam_unstable/geometry/Event.h @@ -99,9 +99,6 @@ public: } }; -const double Event::Speed = 330; -const Matrix14 Event::JacobianZ = (Matrix14() << 0,0,0,1).finished(); - // Define GTSAM traits template<> struct GTSAM_EXPORT traits : internal::Manifold {}; diff --git a/gtsam_unstable/geometry/Pose3Upright.cpp b/gtsam_unstable/geometry/Pose3Upright.cpp index 2ab3a6a9e..f83cb19fb 100644 --- a/gtsam_unstable/geometry/Pose3Upright.cpp +++ b/gtsam_unstable/geometry/Pose3Upright.cpp @@ -64,7 +64,7 @@ Rot2 Pose3Upright::rotation2() const { /* ************************************************************************* */ Rot3 Pose3Upright::rotation() const { - return Rot3::yaw(theta()); + return Rot3::Yaw(theta()); } /* ************************************************************************* */ diff --git a/gtsam_unstable/geometry/tests/testInvDepthCamera3.cpp b/gtsam_unstable/geometry/tests/testInvDepthCamera3.cpp index 2f3c763dd..6ac3389ed 100644 --- a/gtsam_unstable/geometry/tests/testInvDepthCamera3.cpp +++ b/gtsam_unstable/geometry/tests/testInvDepthCamera3.cpp @@ -17,7 +17,7 @@ using namespace std; using namespace gtsam; static Cal3_S2::shared_ptr K(new Cal3_S2(1500, 1200, 0, 640, 480)); -Pose3 level_pose = Pose3(Rot3::ypr(-M_PI/2, 0., -M_PI/2), gtsam::Point3(0,0,1)); +Pose3 level_pose = Pose3(Rot3::Ypr(-M_PI/2, 0., -M_PI/2), gtsam::Point3(0,0,1)); SimpleCamera level_camera(level_pose, *K); /* ************************************************************************* */ @@ -142,7 +142,7 @@ TEST(InvDepthFactor, backproject2) // backwards facing camera Vector expected((Vector(5) << -5.,-5.,2., 3., -0.1).finished()); double inv_depth(1./10); - InvDepthCamera3 inv_camera(Pose3(Rot3::ypr(1.5,0.1, -1.5), Point3(-5, -5, 2)),K); + InvDepthCamera3 inv_camera(Pose3(Rot3::Ypr(1.5,0.1, -1.5), Point3(-5, -5, 2)),K); Point2 z = inv_camera.project(expected, inv_depth); Vector5 actual_vec; diff --git a/gtsam_unstable/geometry/tests/testPose3Upright.cpp b/gtsam_unstable/geometry/tests/testPose3Upright.cpp index 0929035b6..cd54a8813 100644 --- a/gtsam_unstable/geometry/tests/testPose3Upright.cpp +++ b/gtsam_unstable/geometry/tests/testPose3Upright.cpp @@ -58,9 +58,9 @@ TEST( testPose3Upright, conversions ) { EXPECT(assert_equal(Point3(1.0, 2.0, 3.0), pose.translation(), tol)); EXPECT(assert_equal(Point2(1.0, 2.0), pose.translation2(), tol)); EXPECT(assert_equal(Rot2::fromAngle(0.1), pose.rotation2(), tol)); - EXPECT(assert_equal(Rot3::yaw(0.1), pose.rotation(), tol)); + EXPECT(assert_equal(Rot3::Yaw(0.1), pose.rotation(), tol)); EXPECT(assert_equal(Pose2(1.0, 2.0, 0.1), pose.pose2(), tol)); - EXPECT(assert_equal(Pose3(Rot3::yaw(0.1), Point3(1.0, 2.0, 3.0)), pose.pose(), tol)); + EXPECT(assert_equal(Pose3(Rot3::Yaw(0.1), Point3(1.0, 2.0, 3.0)), pose.pose(), tol)); } /* ************************************************************************* */ diff --git a/gtsam_unstable/gtsam_unstable.h b/gtsam_unstable/gtsam_unstable.h index 6b57bfcd0..99b33182f 100644 --- a/gtsam_unstable/gtsam_unstable.h +++ b/gtsam_unstable/gtsam_unstable.h @@ -53,9 +53,9 @@ class Dummy { class PoseRTV { PoseRTV(); PoseRTV(Vector rtv); - PoseRTV(const gtsam::Point3& pt, const gtsam::Rot3& rot, const gtsam::Point3& vel); - PoseRTV(const gtsam::Rot3& rot, const gtsam::Point3& pt, const gtsam::Point3& vel); - PoseRTV(const gtsam::Pose3& pose, const gtsam::Point3& vel); + PoseRTV(const gtsam::Point3& pt, const gtsam::Rot3& rot, const Vector& vel); + PoseRTV(const gtsam::Rot3& rot, const gtsam::Point3& pt, const Vector& vel); + PoseRTV(const gtsam::Pose3& pose, const Vector& vel); PoseRTV(const gtsam::Pose3& pose); PoseRTV(double roll, double pitch, double yaw, double x, double y, double z, double vx, double vy, double vz); @@ -66,7 +66,7 @@ class PoseRTV { // access gtsam::Point3 translation() const; gtsam::Rot3 rotation() const; - gtsam::Point3 velocity() const; + Vector velocity() const; gtsam::Pose3 pose() const; // Vector interfaces @@ -367,7 +367,7 @@ virtual class SmartRangeFactor : gtsam::NoiseModelFactor { }; -#include +#include template virtual class RangeFactor : gtsam::NonlinearFactor { RangeFactor(size_t key1, size_t key2, double measured, const gtsam::noiseModel::Base* noiseModel); @@ -452,7 +452,7 @@ virtual class DGroundConstraint : gtsam::NonlinearFactor { DGroundConstraint(size_t key, Vector constraint, const gtsam::noiseModel::Base* model); }; -#include +#include #include virtual class VelocityConstraint3 : gtsam::NonlinearFactor { diff --git a/gtsam_unstable/linear/QPSolver.h b/gtsam_unstable/linear/QPSolver.h index f7a575f8c..68713f965 100644 --- a/gtsam_unstable/linear/QPSolver.h +++ b/gtsam_unstable/linear/QPSolver.h @@ -48,7 +48,7 @@ class QPSolver { GaussianFactorGraph baseGraph_; //!< factor graphs of cost factors and linear equalities. The working set of inequalities will be added to this base graph in the process. VariableIndex costVariableIndex_, equalityVariableIndex_, inequalityVariableIndex_; - FastSet constrainedKeys_; //!< all constrained keys, will become factors in the dual graph + KeySet constrainedKeys_; //!< all constrained keys, will become factors in the dual graph public: /// Constructor diff --git a/gtsam_unstable/nonlinear/BatchFixedLagSmoother.cpp b/gtsam_unstable/nonlinear/BatchFixedLagSmoother.cpp index 563da4a9f..d74a0c302 100644 --- a/gtsam_unstable/nonlinear/BatchFixedLagSmoother.cpp +++ b/gtsam_unstable/nonlinear/BatchFixedLagSmoother.cpp @@ -205,7 +205,7 @@ void BatchFixedLagSmoother::reorder(const std::set& marginalizeKeys) { } // COLAMD groups will be used to place marginalize keys in Group 0, and everything else in Group 1 - ordering_ = Ordering::colamdConstrainedFirst(factors_, + ordering_ = Ordering::ColamdConstrainedFirst(factors_, std::vector(marginalizeKeys.begin(), marginalizeKeys.end())); if (debug) { @@ -407,7 +407,7 @@ void BatchFixedLagSmoother::marginalize(const std::set& marginalizeKeys) { std::set removedFactorSlots; VariableIndex variableIndex(factors_); BOOST_FOREACH(Key key, marginalizeKeys) { - const FastList& slots = variableIndex[key]; + const FastVector& slots = variableIndex[key]; removedFactorSlots.insert(slots.begin(), slots.end()); } @@ -463,7 +463,7 @@ void BatchFixedLagSmoother::PrintKeySet(const std::set& keys, } /* ************************************************************************* */ -void BatchFixedLagSmoother::PrintKeySet(const gtsam::FastSet& keys, +void BatchFixedLagSmoother::PrintKeySet(const gtsam::KeySet& keys, const std::string& label) { std::cout << label; BOOST_FOREACH(gtsam::Key key, keys) { @@ -531,13 +531,13 @@ NonlinearFactorGraph BatchFixedLagSmoother::calculateMarginalFactors( "BatchFixedLagSmoother::calculateMarginalFactors Marginalize Keys: "); // Get the set of all keys involved in the factor graph - FastSet allKeys(graph.keys()); + KeySet allKeys(graph.keys()); if (debug) PrintKeySet(allKeys, "BatchFixedLagSmoother::calculateMarginalFactors All Keys: "); // Calculate the set of RemainingKeys = AllKeys \Intersect marginalizeKeys - FastSet remainingKeys; + KeySet remainingKeys; std::set_difference(allKeys.begin(), allKeys.end(), marginalizeKeys.begin(), marginalizeKeys.end(), std::inserter(remainingKeys, remainingKeys.end())); if (debug) diff --git a/gtsam_unstable/nonlinear/BatchFixedLagSmoother.h b/gtsam_unstable/nonlinear/BatchFixedLagSmoother.h index 89da3d7e5..605f3a5e8 100644 --- a/gtsam_unstable/nonlinear/BatchFixedLagSmoother.h +++ b/gtsam_unstable/nonlinear/BatchFixedLagSmoother.h @@ -161,7 +161,7 @@ protected: private: /** Private methods for printing debug information */ static void PrintKeySet(const std::set& keys, const std::string& label); - static void PrintKeySet(const gtsam::FastSet& keys, const std::string& label); + static void PrintKeySet(const gtsam::KeySet& keys, const std::string& label); static void PrintSymbolicFactor(const NonlinearFactor::shared_ptr& factor); static void PrintSymbolicFactor(const GaussianFactor::shared_ptr& factor); static void PrintSymbolicGraph(const NonlinearFactorGraph& graph, const std::string& label); diff --git a/gtsam_unstable/nonlinear/ConcurrentBatchFilter.cpp b/gtsam_unstable/nonlinear/ConcurrentBatchFilter.cpp index fcaae9626..c3e307010 100644 --- a/gtsam_unstable/nonlinear/ConcurrentBatchFilter.cpp +++ b/gtsam_unstable/nonlinear/ConcurrentBatchFilter.cpp @@ -221,7 +221,7 @@ void ConcurrentBatchFilter::synchronize(const NonlinearFactorGraph& smootherSumm if(debug) { PrintNonlinearFactorGraph(smootherSummarization_, "ConcurrentBatchFilter::synchronize ", "Updated Smoother Summarization:", DefaultKeyFormatter); } // Find the set of new separator keys - FastSet newSeparatorKeys; + KeySet newSeparatorKeys; BOOST_FOREACH(const Values::ConstKeyValuePair& key_value, separatorValues_) { newSeparatorKeys.insert(key_value.key); } @@ -362,9 +362,9 @@ void ConcurrentBatchFilter::reorder(const boost::optional >& keysT // COLAMD groups will be used to place marginalize keys in Group 0, and everything else in Group 1 if(keysToMove && keysToMove->size() > 0) { - ordering_ = Ordering::colamdConstrainedFirst(factors_, std::vector(keysToMove->begin(), keysToMove->end())); + ordering_ = Ordering::ColamdConstrainedFirst(factors_, std::vector(keysToMove->begin(), keysToMove->end())); }else{ - ordering_ = Ordering::colamd(factors_); + ordering_ = Ordering::Colamd(factors_); } } @@ -536,7 +536,7 @@ void ConcurrentBatchFilter::moveSeparator(const FastList& keysToMove) { std::vector removedFactorSlots; VariableIndex variableIndex(factors_); BOOST_FOREACH(Key key, keysToMove) { - const FastList& slots = variableIndex[key]; + const FastVector& slots = variableIndex[key]; removedFactorSlots.insert(removedFactorSlots.end(), slots.begin(), slots.end()); } @@ -573,7 +573,7 @@ void ConcurrentBatchFilter::moveSeparator(const FastList& keysToMove) { } // Calculate the set of new separator keys: AffectedKeys + PreviousSeparatorKeys - KeysToMove - FastSet newSeparatorKeys = removedFactors.keys(); + KeySet newSeparatorKeys = removedFactors.keys(); BOOST_FOREACH(const Values::ConstKeyValuePair& key_value, separatorValues_) { newSeparatorKeys.insert(key_value.key); } @@ -584,7 +584,7 @@ void ConcurrentBatchFilter::moveSeparator(const FastList& keysToMove) { if(debug) { PrintKeys(newSeparatorKeys, "ConcurrentBatchFilter::synchronize ", "New Separator Keys:", DefaultKeyFormatter); } // Calculate the set of shortcut keys: NewSeparatorKeys + OldSeparatorKeys - FastSet shortcutKeys = newSeparatorKeys; + KeySet shortcutKeys = newSeparatorKeys; BOOST_FOREACH(Key key, smootherSummarization_.keys()) { shortcutKeys.insert(key); } diff --git a/gtsam_unstable/nonlinear/ConcurrentBatchSmoother.cpp b/gtsam_unstable/nonlinear/ConcurrentBatchSmoother.cpp index 0f6515056..29ee14aee 100644 --- a/gtsam_unstable/nonlinear/ConcurrentBatchSmoother.cpp +++ b/gtsam_unstable/nonlinear/ConcurrentBatchSmoother.cpp @@ -230,8 +230,8 @@ void ConcurrentBatchSmoother::reorder() { // Recalculate the variable index variableIndex_ = VariableIndex(factors_); - FastList separatorKeys = separatorValues_.keys(); - ordering_ = Ordering::colamdConstrainedLast(variableIndex_, std::vector(separatorKeys.begin(), separatorKeys.end())); + KeyVector separatorKeys = separatorValues_.keys(); + ordering_ = Ordering::ColamdConstrainedLast(variableIndex_, std::vector(separatorKeys.begin(), separatorKeys.end())); } @@ -371,7 +371,7 @@ void ConcurrentBatchSmoother::updateSmootherSummarization() { } // Get the set of separator keys - gtsam::FastSet separatorKeys; + gtsam::KeySet separatorKeys; BOOST_FOREACH(const Values::ConstKeyValuePair& key_value, separatorValues_) { separatorKeys.insert(key_value.key); } diff --git a/gtsam_unstable/nonlinear/ConcurrentFilteringAndSmoothing.cpp b/gtsam_unstable/nonlinear/ConcurrentFilteringAndSmoothing.cpp index 3b6b884f6..b893860cc 100644 --- a/gtsam_unstable/nonlinear/ConcurrentFilteringAndSmoothing.cpp +++ b/gtsam_unstable/nonlinear/ConcurrentFilteringAndSmoothing.cpp @@ -52,16 +52,16 @@ namespace internal { /* ************************************************************************* */ NonlinearFactorGraph calculateMarginalFactors(const NonlinearFactorGraph& graph, const Values& theta, - const FastSet& remainingKeys, const GaussianFactorGraph::Eliminate& eliminateFunction) { + const KeySet& remainingKeys, const GaussianFactorGraph::Eliminate& eliminateFunction) { // Calculate the set of RootKeys = AllKeys \Intersect RemainingKeys - FastSet rootKeys; - FastSet allKeys(graph.keys()); + KeySet rootKeys; + KeySet allKeys(graph.keys()); std::set_intersection(allKeys.begin(), allKeys.end(), remainingKeys.begin(), remainingKeys.end(), std::inserter(rootKeys, rootKeys.end())); // Calculate the set of MarginalizeKeys = AllKeys - RemainingKeys - FastSet marginalizeKeys; + KeySet marginalizeKeys; std::set_difference(allKeys.begin(), allKeys.end(), remainingKeys.begin(), remainingKeys.end(), std::inserter(marginalizeKeys, marginalizeKeys.end())); if(marginalizeKeys.size() == 0) { diff --git a/gtsam_unstable/nonlinear/ConcurrentFilteringAndSmoothing.h b/gtsam_unstable/nonlinear/ConcurrentFilteringAndSmoothing.h index fb4b78fc2..b8a9941ad 100644 --- a/gtsam_unstable/nonlinear/ConcurrentFilteringAndSmoothing.h +++ b/gtsam_unstable/nonlinear/ConcurrentFilteringAndSmoothing.h @@ -152,7 +152,7 @@ namespace internal { /** Calculate the marginal on the specified keys, returning a set of LinearContainerFactors. * Unlike other GTSAM functions with similar purposes, this version can operate on disconnected graphs. */ NonlinearFactorGraph calculateMarginalFactors(const NonlinearFactorGraph& graph, const Values& theta, - const FastSet& remainingKeys, const GaussianFactorGraph::Eliminate& eliminateFunction); + const KeySet& remainingKeys, const GaussianFactorGraph::Eliminate& eliminateFunction); } diff --git a/gtsam_unstable/nonlinear/ConcurrentIncrementalFilter.cpp b/gtsam_unstable/nonlinear/ConcurrentIncrementalFilter.cpp index 9742aefd7..4c4442141 100644 --- a/gtsam_unstable/nonlinear/ConcurrentIncrementalFilter.cpp +++ b/gtsam_unstable/nonlinear/ConcurrentIncrementalFilter.cpp @@ -184,7 +184,7 @@ void ConcurrentIncrementalFilter::synchronize(const NonlinearFactorGraph& smooth previousSmootherSummarization_ = smootherSummarization; // Find the set of new separator keys - const FastSet& newSeparatorKeys = isam2_.getFixedVariables(); + const KeySet& newSeparatorKeys = isam2_.getFixedVariables(); // Use the shortcut to calculate an updated marginal on the current separator // Combine just the shortcut and the previousSmootherSummarization @@ -291,7 +291,7 @@ std::vector ConcurrentIncrementalFilter::FindAdjacentFactors(const ISAM2 std::vector removedFactorSlots; const VariableIndex& variableIndex = isam2.getVariableIndex(); BOOST_FOREACH(Key key, keys) { - const FastList& slots = variableIndex[key]; + const FastVector& slots = variableIndex[key]; removedFactorSlots.insert(removedFactorSlots.end(), slots.begin(), slots.end()); } @@ -312,7 +312,7 @@ std::vector ConcurrentIncrementalFilter::FindAdjacentFactors(const ISAM2 void ConcurrentIncrementalFilter::updateShortcut(const NonlinearFactorGraph& removedFactors) { // Calculate the set of shortcut keys: NewSeparatorKeys + OldSeparatorKeys - FastSet shortcutKeys; + KeySet shortcutKeys; BOOST_FOREACH(size_t slot, currentSmootherSummarizationSlots_) { const NonlinearFactor::shared_ptr& factor = isam2_.getFactorsUnsafe().at(slot); if(factor) { @@ -343,7 +343,7 @@ NonlinearFactorGraph ConcurrentIncrementalFilter::calculateFilterSummarization() // variables that result from marginalizing out all of the other variables // Find the set of current separator keys - const FastSet& separatorKeys = isam2_.getFixedVariables(); + const KeySet& separatorKeys = isam2_.getFixedVariables(); // Find all cliques that contain any separator variables std::set separatorCliques; diff --git a/gtsam_unstable/nonlinear/ConcurrentIncrementalSmoother.cpp b/gtsam_unstable/nonlinear/ConcurrentIncrementalSmoother.cpp index 16a336695..b87409aae 100644 --- a/gtsam_unstable/nonlinear/ConcurrentIncrementalSmoother.cpp +++ b/gtsam_unstable/nonlinear/ConcurrentIncrementalSmoother.cpp @@ -245,7 +245,7 @@ void ConcurrentIncrementalSmoother::updateSmootherSummarization() { } // Get the set of separator keys - gtsam::FastSet separatorKeys; + gtsam::KeySet separatorKeys; BOOST_FOREACH(const Values::ConstKeyValuePair& key_value, separatorValues_) { separatorKeys.insert(key_value.key); } diff --git a/gtsam_unstable/nonlinear/tests/testConcurrentBatchSmoother.cpp b/gtsam_unstable/nonlinear/tests/testConcurrentBatchSmoother.cpp index 51c2a55a2..558654367 100644 --- a/gtsam_unstable/nonlinear/tests/testConcurrentBatchSmoother.cpp +++ b/gtsam_unstable/nonlinear/tests/testConcurrentBatchSmoother.cpp @@ -559,7 +559,7 @@ TEST( ConcurrentBatchSmoother, synchronize_3 ) ordering = smoother.getOrdering(); // I'm really hoping this is an acceptable ordering... GaussianFactorGraph::shared_ptr linearFactors = allFactors.linearize(allValues); - FastSet eliminateKeys = linearFactors->keys(); + KeySet eliminateKeys = linearFactors->keys(); BOOST_FOREACH(const Values::ConstKeyValuePair& key_value, filterSeparatorValues) { eliminateKeys.erase(key_value.key); } diff --git a/gtsam_unstable/nonlinear/tests/testConcurrentIncrementalSmootherDL.cpp b/gtsam_unstable/nonlinear/tests/testConcurrentIncrementalSmootherDL.cpp index 5f91527e6..22dd0ccaa 100644 --- a/gtsam_unstable/nonlinear/tests/testConcurrentIncrementalSmootherDL.cpp +++ b/gtsam_unstable/nonlinear/tests/testConcurrentIncrementalSmootherDL.cpp @@ -579,7 +579,7 @@ TEST( ConcurrentIncrementalSmootherDL, synchronize_3 ) // GaussianSequentialSolver GSS = GaussianSequentialSolver(*LinFactorGraph); // GaussianBayesNet::shared_ptr GBNsptr = GSS.eliminate(); - FastSet allkeys = LinFactorGraph->keys(); + KeySet allkeys = LinFactorGraph->keys(); BOOST_FOREACH(const Values::ConstKeyValuePair& key_value, filterSeparatorValues) { allkeys.erase(key_value.key); } diff --git a/gtsam_unstable/nonlinear/tests/testConcurrentIncrementalSmootherGN.cpp b/gtsam_unstable/nonlinear/tests/testConcurrentIncrementalSmootherGN.cpp index 9708eedb5..c372577ca 100644 --- a/gtsam_unstable/nonlinear/tests/testConcurrentIncrementalSmootherGN.cpp +++ b/gtsam_unstable/nonlinear/tests/testConcurrentIncrementalSmootherGN.cpp @@ -581,7 +581,7 @@ TEST( ConcurrentIncrementalSmootherGN, synchronize_3 ) // GaussianSequentialSolver GSS = GaussianSequentialSolver(*LinFactorGraph); // GaussianBayesNet::shared_ptr GBNsptr = GSS.eliminate(); - FastSet allkeys = LinFactorGraph->keys(); + KeySet allkeys = LinFactorGraph->keys(); BOOST_FOREACH(const Values::ConstKeyValuePair& key_value, filterSeparatorValues) allkeys.erase(key_value.key); std::vector variables(allkeys.begin(), allkeys.end()); diff --git a/gtsam_unstable/slam/Mechanization_bRn2.cpp b/gtsam_unstable/slam/Mechanization_bRn2.cpp index 4218a5561..20ffbdd4f 100644 --- a/gtsam_unstable/slam/Mechanization_bRn2.cpp +++ b/gtsam_unstable/slam/Mechanization_bRn2.cpp @@ -60,7 +60,7 @@ Mechanization_bRn2 Mechanization_bRn2::initialize(const Matrix& U, double pitch = atan2(-g1, sqrt(g2 * g2 + g3 * g3)); double yaw = 0; // This returns body-to-nav nRb - Rot3 bRn = Rot3::ypr(yaw, pitch, roll).inverse(); + Rot3 bRn = Rot3::Ypr(yaw, pitch, roll).inverse(); return Mechanization_bRn2(bRn, x_g, x_a); } @@ -69,7 +69,7 @@ Mechanization_bRn2 Mechanization_bRn2::initialize(const Matrix& U, Mechanization_bRn2 Mechanization_bRn2::correct(const Vector3& dx) const { Vector3 rho = sub(dx, 0, 3); - Rot3 delta_nRn = Rot3::rodriguez(rho); + Rot3 delta_nRn = Rot3::Rodrigues(rho); Rot3 bRn = bRn_ * delta_nRn; Vector3 x_g = x_g_ + sub(dx, 3, 6); @@ -101,10 +101,10 @@ Mechanization_bRn2 Mechanization_bRn2::integrate(const Vector3& u, // convert to navigation frame Rot3 nRb = bRn_.inverse(); - Vector3 n_omega_bn = (nRb*b_omega_bn).vector(); + Vector3 n_omega_bn = nRb * b_omega_bn; // integrate bRn using exponential map, assuming constant over dt - Rot3 delta_nRn = Rot3::rodriguez(n_omega_bn*dt); + Rot3 delta_nRn = Rot3::Rodrigues(n_omega_bn*dt); Rot3 bRn = bRn_.compose(delta_nRn); // implicit updating of biases (variables just do not change) diff --git a/gtsam_unstable/slam/Mechanization_bRn2.h b/gtsam_unstable/slam/Mechanization_bRn2.h index fa33ce5b9..4c85614d4 100644 --- a/gtsam_unstable/slam/Mechanization_bRn2.h +++ b/gtsam_unstable/slam/Mechanization_bRn2.h @@ -42,7 +42,7 @@ public: /// gravity in the body frame Vector3 b_g(double g_e) const { Vector3 n_g(0, 0, g_e); - return (bRn_ * n_g).vector(); + return bRn_ * n_g; } const Rot3& bRn() const {return bRn_; } diff --git a/gtsam_unstable/slam/MultiProjectionFactor.h b/gtsam_unstable/slam/MultiProjectionFactor.h index da60c2c31..f1487f562 100644 --- a/gtsam_unstable/slam/MultiProjectionFactor.h +++ b/gtsam_unstable/slam/MultiProjectionFactor.h @@ -70,7 +70,7 @@ namespace gtsam { * @param body_P_sensor is the transform from body to sensor frame (default identity) */ MultiProjectionFactor(const Vector& measured, const SharedNoiseModel& model, - FastSet poseKeys, Key pointKey, const boost::shared_ptr& K, + KeySet poseKeys, Key pointKey, const boost::shared_ptr& K, boost::optional body_P_sensor = boost::none) : Base(model), measured_(measured), K_(K), body_P_sensor_(body_P_sensor), throwCheirality_(false), verboseCheirality_(false) { @@ -91,7 +91,7 @@ namespace gtsam { * @param body_P_sensor is the transform from body to sensor frame (default identity) */ MultiProjectionFactor(const Vector& measured, const SharedNoiseModel& model, - FastSet poseKeys, Key pointKey, const boost::shared_ptr& K, + KeySet poseKeys, Key pointKey, const boost::shared_ptr& K, bool throwCheirality, bool verboseCheirality, boost::optional body_P_sensor = boost::none) : Base(model), measured_(measured), K_(K), body_P_sensor_(body_P_sensor), diff --git a/gtsam_unstable/slam/SmartStereoProjectionFactor.h b/gtsam_unstable/slam/SmartStereoProjectionFactor.h index 1358e1349..6651c005f 100644 --- a/gtsam_unstable/slam/SmartStereoProjectionFactor.h +++ b/gtsam_unstable/slam/SmartStereoProjectionFactor.h @@ -11,10 +11,11 @@ /** * @file SmartStereoProjectionFactor.h - * @brief Base class to create smart factors on poses or cameras + * @brief Smart stereo factor on StereoCameras (pose + calibration) * @author Luca Carlone * @author Zsolt Kira * @author Frank Dellaert + * @author Chris Beall */ #pragma once @@ -24,6 +25,7 @@ #include #include #include +#include #include #include @@ -33,113 +35,136 @@ namespace gtsam { +/// Linearization mode: what factor to linearize to + enum LinearizationMode { + HESSIAN, IMPLICIT_SCHUR, JACOBIAN_Q, JACOBIAN_SVD + }; + +/// How to manage degeneracy +enum DegeneracyMode { + IGNORE_DEGENERACY, ZERO_ON_DEGENERACY, HANDLE_INFINITY + }; + + /* + * Parameters for the smart stereo projection factors + */ + struct GTSAM_EXPORT SmartStereoProjectionParams { + + LinearizationMode linearizationMode; ///< How to linearize the factor + DegeneracyMode degeneracyMode; ///< How to linearize the factor + + /// @name Parameters governing the triangulation + /// @{ + TriangulationParameters triangulation; + double retriangulationThreshold; ///< threshold to decide whether to re-triangulate + /// @} + + /// @name Parameters governing how triangulation result is treated + /// @{ + bool throwCheirality; ///< If true, re-throws Cheirality exceptions (default: false) + bool verboseCheirality; ///< If true, prints text for Cheirality exceptions (default: false) + /// @} + + + /// Constructor + SmartStereoProjectionParams(LinearizationMode linMode = HESSIAN, + DegeneracyMode degMode = IGNORE_DEGENERACY, bool throwCheirality = false, + bool verboseCheirality = false) : + linearizationMode(linMode), degeneracyMode(degMode), retriangulationThreshold( + 1e-5), throwCheirality(throwCheirality), verboseCheirality( + verboseCheirality) { + } + + virtual ~SmartStereoProjectionParams() { + } + + void print(const std::string& str) const { + std::cout << "linearizationMode: " << linearizationMode << "\n"; + std::cout << " degeneracyMode: " << degeneracyMode << "\n"; + std::cout << triangulation << std::endl; + } + + LinearizationMode getLinearizationMode() const { + return linearizationMode; + } + DegeneracyMode getDegeneracyMode() const { + return degeneracyMode; + } + TriangulationParameters getTriangulationParameters() const { + return triangulation; + } + bool getVerboseCheirality() const { + return verboseCheirality; + } + bool getThrowCheirality() const { + return throwCheirality; + } + void setLinearizationMode(LinearizationMode linMode) { + linearizationMode = linMode; + } + void setDegeneracyMode(DegeneracyMode degMode) { + degeneracyMode = degMode; + } + void setRankTolerance(double rankTol) { + triangulation.rankTolerance = rankTol; + } + void setEnableEPI(bool enableEPI) { + triangulation.enableEPI = enableEPI; + } + void setLandmarkDistanceThreshold(double landmarkDistanceThreshold) { + triangulation.landmarkDistanceThreshold = landmarkDistanceThreshold; + } + void setDynamicOutlierRejectionThreshold(double dynOutRejectionThreshold) { + triangulation.dynamicOutlierRejectionThreshold = dynOutRejectionThreshold; + } + }; + + + /** - * Structure for storing some state memory, used to speed up optimization - * @addtogroup SLAM - */ -class SmartStereoProjectionFactorState { + * SmartStereoProjectionFactor: triangulates point and keeps an estimate of it around. + * This factor operates with StereoCamera. This factor requires that values + * contains the involved StereoCameras. Calibration is assumed to be fixed, as this + * is also assumed in StereoCamera. + * If you'd like to store poses in values instead of cameras, use + * SmartStereoProjectionPoseFactor instead +*/ +class SmartStereoProjectionFactor: public SmartFactorBase { +private: + + typedef SmartFactorBase Base; protected: -public: + /// @name Parameters + /// @{ + const SmartStereoProjectionParams params_; + /// @} - EIGEN_MAKE_ALIGNED_OPERATOR_NEW - - SmartStereoProjectionFactorState() { - } - // Hessian representation (after Schur complement) - bool calculatedHessian; - Matrix H; - Vector gs_vector; - std::vector Gs; - std::vector gs; - double f; -}; - -enum LinearizationMode { - HESSIAN, JACOBIAN_SVD, JACOBIAN_Q -}; - -/** - * SmartStereoProjectionFactor: triangulates point - */ -template -class SmartStereoProjectionFactor: public SmartFactorBase { -protected: - - // Some triangulation parameters - const double rankTolerance_; ///< threshold to decide whether triangulation is degenerate_ - const double retriangulationThreshold_; ///< threshold to decide whether to re-triangulate + /// @name Caching triangulation + /// @{ + mutable TriangulationResult result_; ///< result from triangulateSafe mutable std::vector cameraPosesTriangulation_; ///< current triangulation poses - - const bool manageDegeneracy_; ///< if set to true will use the rotation-only version for degenerate cases - - const bool enableEPI_; ///< if set to true, will refine triangulation using LM - - const double linearizationThreshold_; ///< threshold to decide whether to re-linearize - mutable std::vector cameraPosesLinearization_; ///< current linearization poses - - mutable Point3 point_; ///< Current estimate of the 3D point - - mutable bool degenerate_; - mutable bool cheiralityException_; - - // verbosity handling for Cheirality Exceptions - const bool throwCheirality_; ///< If true, rethrows Cheirality exceptions (default: false) - const bool verboseCheirality_; ///< If true, prints text for Cheirality exceptions (default: false) - - boost::shared_ptr state_; - - /// shorthand for smart projection factor state variable - typedef boost::shared_ptr SmartFactorStatePtr; - - /// shorthand for base class type - typedef SmartFactorBase Base; - - double landmarkDistanceThreshold_; // if the landmark is triangulated at a - // distance larger than that the factor is considered degenerate - - double dynamicOutlierRejectionThreshold_; // if this is nonnegative the factor will check if the - // average reprojection error is smaller than this threshold after triangulation, - // and the factor is disregarded if the error is large - - /// shorthand for this class - typedef SmartStereoProjectionFactor This; - - enum {ZDim = 3}; ///< Dimension trait of measurement type + /// @} public: /// shorthand for a smart pointer to a factor - typedef boost::shared_ptr shared_ptr; - - /// shorthand for a StereoCamera // TODO: Get rid of this? - typedef StereoCamera Camera; + typedef boost::shared_ptr shared_ptr; /// Vector of cameras - typedef CameraSet Cameras; + typedef CameraSet Cameras; /** * Constructor - * @param rankTol tolerance used to check if point triangulation is degenerate - * @param linThreshold threshold on relative pose changes used to decide whether to relinearize (selective relinearization) - * @param manageDegeneracy is true, in presence of degenerate triangulation, the factor is converted to a rotation-only constraint, - * otherwise the factor is simply neglected - * @param enableEPI if set to true linear triangulation is refined with embedded LM iterations - * @param body_P_sensor is the transform from body to sensor frame (default identity) + * @param params internal parameters of the smart factors */ - SmartStereoProjectionFactor(const double rankTol, const double linThreshold, - const bool manageDegeneracy, const bool enableEPI, - boost::optional body_P_sensor = boost::none, - double landmarkDistanceThreshold = 1e10, - double dynamicOutlierRejectionThreshold = -1, - SmartFactorStatePtr state = SmartFactorStatePtr(new SmartStereoProjectionFactorState())) : - Base(body_P_sensor), rankTolerance_(rankTol), retriangulationThreshold_( - 1e-5), manageDegeneracy_(manageDegeneracy), enableEPI_(enableEPI), linearizationThreshold_( - linThreshold), degenerate_(false), cheiralityException_(false), throwCheirality_( - false), verboseCheirality_(false), state_(state), - landmarkDistanceThreshold_(landmarkDistanceThreshold), - dynamicOutlierRejectionThreshold_(dynamicOutlierRejectionThreshold) { + SmartStereoProjectionFactor(const SharedNoiseModel& sharedNoiseModel, + const SmartStereoProjectionParams& params = + SmartStereoProjectionParams()) : + Base(sharedNoiseModel), // + params_(params), // + result_(TriangulationResult::Degenerate()) { } /** Virtual destructor */ @@ -153,14 +178,21 @@ public: */ void print(const std::string& s = "", const KeyFormatter& keyFormatter = DefaultKeyFormatter) const { - std::cout << s << "SmartStereoProjectionFactor, z = \n"; - std::cout << "rankTolerance_ = " << rankTolerance_ << std::endl; - std::cout << "degenerate_ = " << degenerate_ << std::endl; - std::cout << "cheiralityException_ = " << cheiralityException_ << std::endl; - std::cout << "linearizationThreshold_ = " << linearizationThreshold_ << std::endl; + std::cout << s << "SmartStereoProjectionFactor\n"; + std::cout << "linearizationMode:\n" << params_.linearizationMode << std::endl; + std::cout << "triangulationParameters:\n" << params_.triangulation << std::endl; + std::cout << "result:\n" << result_ << std::endl; Base::print("", keyFormatter); } + /// equals + virtual bool equals(const NonlinearFactor& p, double tol = 1e-9) const { + const SmartStereoProjectionFactor *e = + dynamic_cast(&p); + return e && params_.linearizationMode == e->params_.linearizationMode + && Base::equals(p, tol); + } + /// Check if the new linearization point_ is the same as the one used for previous triangulation bool decideIfTriangulate(const Cameras& cameras) const { // several calls to linearize will be done from the same linearization point_, hence it is not needed to re-triangulate @@ -179,7 +211,7 @@ public: if (!retriangulate) { for (size_t i = 0; i < cameras.size(); i++) { if (!cameras[i].pose().equals(cameraPosesTriangulation_[i], - retriangulationThreshold_)) { + params_.retriangulationThreshold)) { retriangulate = true; // at least two poses are different, hence we retriangulate break; } @@ -197,447 +229,306 @@ public: return retriangulate; // if we arrive to this point_ all poses are the same and we don't need re-triangulation } - /// This function checks if the new linearization point_ is 'close' to the previous one used for linearization - bool decideIfLinearize(const Cameras& cameras) const { - // "selective linearization" - // The function evaluates how close are the old and the new poses, transformed in the ref frame of the first pose - // (we only care about the "rigidity" of the poses, not about their absolute pose) - - if (this->linearizationThreshold_ < 0) //by convention if linearizationThreshold is negative we always relinearize - return true; - - // if we do not have a previous linearization point_ or the new linearization point_ includes more poses - if (cameraPosesLinearization_.empty() - || (cameras.size() != cameraPosesLinearization_.size())) - return true; - - Pose3 firstCameraPose, firstCameraPoseOld; - for (size_t i = 0; i < cameras.size(); i++) { - - if (i == 0) { // we store the initial pose, this is useful for selective re-linearization - firstCameraPose = cameras[i].pose(); - firstCameraPoseOld = cameraPosesLinearization_[i]; - continue; - } - - // we compare the poses in the frame of the first pose - Pose3 localCameraPose = firstCameraPose.between(cameras[i].pose()); - Pose3 localCameraPoseOld = firstCameraPoseOld.between( - cameraPosesLinearization_[i]); - if (!localCameraPose.equals(localCameraPoseOld, - this->linearizationThreshold_)) - return true; // at least two "relative" poses are different, hence we re-linearize - } - return false; // if we arrive to this point_ all poses are the same and we don't need re-linearize - } +// /// triangulateSafe +// size_t triangulateSafe(const Values& values) const { +// return triangulateSafe(this->cameras(values)); +// } /// triangulateSafe - size_t triangulateSafe(const Values& values) const { - return triangulateSafe(this->cameras(values)); - } - - /// triangulateSafe - size_t triangulateSafe(const Cameras& cameras) const { + TriangulationResult triangulateSafe(const Cameras& cameras) const { size_t m = cameras.size(); - if (m < 2) { // if we have a single pose the corresponding factor is uninformative - degenerate_ = true; - return m; - } bool retriangulate = decideIfTriangulate(cameras); +// if(!retriangulate) +// std::cout << "retriangulate = false" << std::endl; +// +// bool retriangulate = true; + if (retriangulate) { - // We triangulate the 3D position of the landmark - try { - // std::cout << "triangulatePoint3 i \n" << rankTolerance << std::endl; - - //TODO: Chris will replace this with something else for stereo -// point_ = triangulatePoint3(cameras, this->measured_, -// rankTolerance_, enableEPI_); - - // // // Temporary hack to use monocular triangulation - std::vector mono_measurements; - BOOST_FOREACH(const StereoPoint2& sp, this->measured_) { - mono_measurements.push_back(sp.point2()); - } - - std::vector > mono_cameras; - BOOST_FOREACH(const Camera& camera, cameras) { - const Pose3& pose = camera.pose(); - const Cal3_S2& K = camera.calibration()->calibration(); - mono_cameras.push_back(PinholeCamera(pose, K)); - } - point_ = triangulatePoint3 >(mono_cameras, mono_measurements, - rankTolerance_, enableEPI_); - - // // // End temporary hack - - // FIXME: temporary: triangulation using only first camera -// const StereoPoint2& z0 = this->measured_.at(0); -// point_ = cameras[0].backproject(z0); - - degenerate_ = false; - cheiralityException_ = false; - - // Check landmark distance and reprojection errors to avoid outliers - double totalReprojError = 0.0; - size_t i=0; - BOOST_FOREACH(const Camera& camera, cameras) { - Point3 cameraTranslation = camera.pose().translation(); - // we discard smart factors corresponding to points that are far away - if(cameraTranslation.distance(point_) > landmarkDistanceThreshold_){ - degenerate_ = true; - break; - } - const StereoPoint2& zi = this->measured_.at(i); - try { - StereoPoint2 reprojectionError(camera.project(point_) - zi); - totalReprojError += reprojectionError.vector().norm(); - } catch (CheiralityException) { - cheiralityException_ = true; - } - i += 1; - } - //std::cout << "totalReprojError error: " << totalReprojError << std::endl; - // we discard smart factors that have large reprojection error - if(dynamicOutlierRejectionThreshold_ > 0 && - totalReprojError/m > dynamicOutlierRejectionThreshold_) - degenerate_ = true; - - } catch (TriangulationUnderconstrainedException&) { - // if TriangulationUnderconstrainedException can be - // 1) There is a single pose for triangulation - this should not happen because we checked the number of poses before - // 2) The rank of the matrix used for triangulation is < 3: rotation-only, parallel cameras (or motion towards the landmark) - // in the second case we want to use a rotation-only smart factor - degenerate_ = true; - cheiralityException_ = false; - } catch (TriangulationCheiralityException&) { - // point is behind one of the cameras: can be the case of close-to-parallel cameras or may depend on outliers - // we manage this case by either discarding the smart factor, or imposing a rotation-only constraint - cheiralityException_ = true; +// std::cout << "Retriangulate " << std::endl; + std::vector reprojections; + reprojections.reserve(m); + for(size_t i = 0; i < m; i++) { + reprojections.push_back(cameras[i].backproject(measured_[i])); } - } - return m; + + Point3 pw_sum; + BOOST_FOREACH(const Point3& pw, reprojections) { + pw_sum = pw_sum + pw; + } + // average reprojected landmark + Point3 pw_avg = pw_sum / double(m); + + double totalReprojError = 0; + + // check if it lies in front of all cameras + for(size_t i = 0; i < m; i++) { + const Pose3& pose = cameras[i].pose(); + const Point3& pl = pose.transform_to(pw_avg); + if (pl.z() <= 0) { + result_ = TriangulationResult::BehindCamera(); + return result_; + } + + // check landmark distance + if (params_.triangulation.landmarkDistanceThreshold > 0 && + pl.norm() > params_.triangulation.landmarkDistanceThreshold) { + result_ = TriangulationResult::Degenerate(); + return result_; + } + + if (params_.triangulation.dynamicOutlierRejectionThreshold > 0) { + const StereoPoint2& zi = measured_[i]; + StereoPoint2 reprojectionError(cameras[i].project(pw_avg) - zi); + totalReprojError += reprojectionError.vector().norm(); + } + } // for + + if (params_.triangulation.dynamicOutlierRejectionThreshold > 0 + && totalReprojError / m > params_.triangulation.dynamicOutlierRejectionThreshold) { + result_ = TriangulationResult::Degenerate(); + return result_; + } + + if(params_.triangulation.enableEPI) { + try { + pw_avg = triangulateNonlinear(cameras, measured_, pw_avg); + } catch(StereoCheiralityException& e) { + if(params_.verboseCheirality) + std::cout << "Cheirality Exception in SmartStereoProjectionFactor" << std::endl; + if(params_.throwCheirality) + throw; + result_ = TriangulationResult::BehindCamera(); + return TriangulationResult::BehindCamera(); + } + } + + result_ = TriangulationResult(pw_avg); + + } // if retriangulate + return result_; + } /// triangulate bool triangulateForLinearize(const Cameras& cameras) const { - - bool isDebug = false; - size_t nrCameras = this->triangulateSafe(cameras); - - if (nrCameras < 2 - || (!this->manageDegeneracy_ - && (this->cheiralityException_ || this->degenerate_))) { - if (isDebug) { - std::cout << "createImplicitSchurFactor: degenerate configuration" - << std::endl; - } - return false; - } else { - - // instead, if we want to manage the exception.. - if (this->cheiralityException_ || this->degenerate_) { // if we want to manage the exceptions with rotation-only factors - this->degenerate_ = true; - } - return true; - } + triangulateSafe(cameras); // imperative, might reset result_ + return bool(result_); } /// linearize returns a Hessianfactor that is an approximation of error(p) - boost::shared_ptr > createHessianFactor( - const Cameras& cameras, const double lambda = 0.0) const { + boost::shared_ptr > createHessianFactor( + const Cameras& cameras, const double lambda = 0.0, bool diagonalDamping = + false) const { - bool isDebug = false; size_t numKeys = this->keys_.size(); // Create structures for Hessian Factors - std::vector < Key > js; - std::vector < Matrix > Gs(numKeys * (numKeys + 1) / 2); - std::vector < Vector > gs(numKeys); + std::vector js; + std::vector Gs(numKeys * (numKeys + 1) / 2); + std::vector gs(numKeys); if (this->measured_.size() != cameras.size()) { std::cout - << "SmartProjectionHessianFactor: this->measured_.size() inconsistent with input" + << "SmartStereoProjectionHessianFactor: this->measured_.size() inconsistent with input" << std::endl; exit(1); } - this->triangulateSafe(cameras); - if (isDebug) std::cout << "point_ = " << point_ << std::endl; + triangulateSafe(cameras); - if (numKeys < 2 - || (!this->manageDegeneracy_ - && (this->cheiralityException_ || this->degenerate_))) { - if (isDebug) std::cout << "In linearize: exception" << std::endl; + if (params_.degeneracyMode == ZERO_ON_DEGENERACY && !result_) { + // failed: return"empty" Hessian BOOST_FOREACH(Matrix& m, Gs) - m = zeros(D, D); + m = zeros(Base::Dim, Base::Dim); BOOST_FOREACH(Vector& v, gs) - v = zero(D); - return boost::make_shared >(this->keys_, Gs, gs, - 0.0); + v = zero(Base::Dim); + return boost::make_shared >(this->keys_, + Gs, gs, 0.0); } - // instead, if we want to manage the exception.. - if (this->cheiralityException_ || this->degenerate_) { // if we want to manage the exceptions with rotation-only factors - this->degenerate_ = true; - if (isDebug) std::cout << "degenerate_ = true" << std::endl; - } - - bool doLinearize = this->decideIfLinearize(cameras); - - if (isDebug) std::cout << "doLinearize = " << doLinearize << std::endl; - - if (this->linearizationThreshold_ >= 0 && doLinearize) // if we apply selective relinearization and we need to relinearize - for (size_t i = 0; i < cameras.size(); i++) - this->cameraPosesLinearization_[i] = cameras[i].pose(); - - if (!doLinearize) { // return the previous Hessian factor - std::cout << "=============================" << std::endl; - std::cout << "doLinearize " << doLinearize << std::endl; - std::cout << "this->linearizationThreshold_ " - << this->linearizationThreshold_ << std::endl; - std::cout << "this->degenerate_ " << this->degenerate_ << std::endl; - std::cout - << "something wrong in SmartProjectionHessianFactor: selective relinearization should be disabled" - << std::endl; - exit(1); - return boost::make_shared >(this->keys_, - this->state_->Gs, this->state_->gs, this->state_->f); - } - - // ================================================================== + // Jacobian could be 3D Point3 OR 2D Unit3, difference is E.cols(). + std::vector Fblocks; Matrix F, E; Vector b; - double f = computeJacobians(F, E, b, cameras); + computeJacobiansWithTriangulatedPoint(Fblocks, E, b, cameras); - // Schur complement trick - // Frank says: should be possible to do this more efficiently? - // And we care, as in grouped factors this is called repeatedly - Matrix H(D * numKeys, D * numKeys); - Vector gs_vector; + // Whiten using noise model + Base::whitenJacobians(Fblocks, E, b); - Matrix3 P = Base::PointCov(E,lambda); - H.noalias() = F.transpose() * (F - (E * (P * (E.transpose() * F)))); - gs_vector.noalias() = F.transpose() * (b - (E * (P * (E.transpose() * b)))); + // build augmented hessian + SymmetricBlockMatrix augmentedHessian = // + Cameras::SchurComplement(Fblocks, E, b, lambda, diagonalDamping); - if (isDebug) std::cout << "gs_vector size " << gs_vector.size() << std::endl; - if (isDebug) std::cout << "H:\n" << H << std::endl; - - // Populate Gs and gs - int GsCount2 = 0; - for (DenseIndex i1 = 0; i1 < (DenseIndex)numKeys; i1++) { // for each camera - DenseIndex i1D = i1 * D; - gs.at(i1) = gs_vector.segment < D > (i1D); - for (DenseIndex i2 = 0; i2 < (DenseIndex)numKeys; i2++) { - if (i2 >= i1) { - Gs.at(GsCount2) = H.block < D, D > (i1D, i2 * D); - GsCount2++; - } - } - } - // ================================================================== - if (this->linearizationThreshold_ >= 0) { // if we do not use selective relinearization we don't need to store these variables - this->state_->Gs = Gs; - this->state_->gs = gs; - this->state_->f = f; - } - return boost::make_shared >(this->keys_, Gs, gs, f); + return boost::make_shared >(this->keys_, + augmentedHessian); } -// // create factor -// boost::shared_ptr > createImplicitSchurFactor( + // create factor +// boost::shared_ptr > createRegularImplicitSchurFactor( // const Cameras& cameras, double lambda) const { // if (triangulateForLinearize(cameras)) -// return Base::createImplicitSchurFactor(cameras, point_, lambda); +// return Base::createRegularImplicitSchurFactor(cameras, *result_, lambda); // else -// return boost::shared_ptr >(); +// // failed: return empty +// return boost::shared_ptr >(); // } // // /// create factor -// boost::shared_ptr > createJacobianQFactor( +// boost::shared_ptr > createJacobianQFactor( // const Cameras& cameras, double lambda) const { // if (triangulateForLinearize(cameras)) -// return Base::createJacobianQFactor(cameras, point_, lambda); +// return Base::createJacobianQFactor(cameras, *result_, lambda); // else -// return boost::make_shared< JacobianFactorQ >(this->keys_); +// // failed: return empty +// return boost::make_shared >(this->keys_); // } // // /// Create a factor, takes values -// boost::shared_ptr > createJacobianQFactor( +// boost::shared_ptr > createJacobianQFactor( // const Values& values, double lambda) const { -// Cameras myCameras; -// // TODO triangulate twice ?? -// bool nonDegenerate = computeCamerasAndTriangulate(values, myCameras); -// if (nonDegenerate) -// return createJacobianQFactor(myCameras, lambda); -// else -// return boost::make_shared< JacobianFactorQ >(this->keys_); +// return createJacobianQFactor(this->cameras(values), lambda); +// } + + /// different (faster) way to compute Jacobian factor + boost::shared_ptr createJacobianSVDFactor( + const Cameras& cameras, double lambda) const { + if (triangulateForLinearize(cameras)) + return Base::createJacobianSVDFactor(cameras, *result_, lambda); + else + return boost::make_shared >(this->keys_); + } + +// /// linearize to a Hessianfactor +// virtual boost::shared_ptr > linearizeToHessian( +// const Values& values, double lambda = 0.0) const { +// return createHessianFactor(this->cameras(values), lambda); +// } + +// /// linearize to an Implicit Schur factor +// virtual boost::shared_ptr > linearizeToImplicit( +// const Values& values, double lambda = 0.0) const { +// return createRegularImplicitSchurFactor(this->cameras(values), lambda); // } // - /// different (faster) way to compute Jacobian factor - boost::shared_ptr< JacobianFactor > createJacobianSVDFactor(const Cameras& cameras, - double lambda) const { - if (triangulateForLinearize(cameras)) - return Base::createJacobianSVDFactor(cameras, point_, lambda); - else - return boost::make_shared< JacobianFactorSVD >(this->keys_); - } +// /// linearize to a JacobianfactorQ +// virtual boost::shared_ptr > linearizeToJacobian( +// const Values& values, double lambda = 0.0) const { +// return createJacobianQFactor(this->cameras(values), lambda); +// } - /// Returns true if nonDegenerate - bool computeCamerasAndTriangulate(const Values& values, - Cameras& myCameras) const { - Values valuesFactor; - - // Select only the cameras - BOOST_FOREACH(const Key key, this->keys_) - valuesFactor.insert(key, values.at(key)); - - myCameras = this->cameras(valuesFactor); - size_t nrCameras = this->triangulateSafe(myCameras); - - if (nrCameras < 2 - || (!this->manageDegeneracy_ - && (this->cheiralityException_ || this->degenerate_))) - return false; - - // instead, if we want to manage the exception.. - if (this->cheiralityException_ || this->degenerate_) // if we want to manage the exceptions with rotation-only factors - this->degenerate_ = true; - - if (this->degenerate_) { - std::cout << "SmartStereoProjectionFactor: this is not ready" << std::endl; - std::cout << "this->cheiralityException_ " << this->cheiralityException_ - << std::endl; - std::cout << "this->degenerate_ " << this->degenerate_ << std::endl; + /** + * Linearize to Gaussian Factor + * @param values Values structure which must contain camera poses for this factor + * @return a Gaussian factor + */ + boost::shared_ptr linearizeDamped(const Cameras& cameras, + const double lambda = 0.0) const { + // depending on flag set on construction we may linearize to different linear factors + switch (params_.linearizationMode) { + case HESSIAN: + return createHessianFactor(cameras, lambda); +// case IMPLICIT_SCHUR: +// return createRegularImplicitSchurFactor(cameras, lambda); + case JACOBIAN_SVD: + return createJacobianSVDFactor(cameras, lambda); +// case JACOBIAN_Q: +// return createJacobianQFactor(cameras, lambda); + default: + throw std::runtime_error("SmartStereoFactorlinearize: unknown mode"); } - return true; } - /// Assumes non-degenerate ! - void computeEP(Matrix& E, Matrix& PointCov, const Cameras& cameras) const { - Base::computeEP(E, PointCov, cameras, point_); + /** + * Linearize to Gaussian Factor + * @param values Values structure which must contain camera poses for this factor + * @return a Gaussian factor + */ + boost::shared_ptr linearizeDamped(const Values& values, + const double lambda = 0.0) const { + // depending on flag set on construction we may linearize to different linear factors + Cameras cameras = this->cameras(values); + return linearizeDamped(cameras, lambda); } - /// Takes values - bool computeEP(Matrix& E, Matrix& PointCov, const Values& values) const { - Cameras myCameras; - bool nonDegenerate = computeCamerasAndTriangulate(values, myCameras); + /// linearize + virtual boost::shared_ptr linearize( + const Values& values) const { + return linearizeDamped(values); + } + + /** + * Triangulate and compute derivative of error with respect to point + * @return whether triangulation worked + */ + bool triangulateAndComputeE(Matrix& E, const Cameras& cameras) const { + bool nonDegenerate = triangulateForLinearize(cameras); if (nonDegenerate) - computeEP(E, PointCov, myCameras); + cameras.project2(*result_, boost::none, E); return nonDegenerate; } - /// Version that takes values, and creates the point - bool computeJacobians(std::vector& Fblocks, - Matrix& E, Vector& b, const Values& values) const { - Cameras myCameras; - bool nonDegenerate = computeCamerasAndTriangulate(values, myCameras); - if (nonDegenerate) - computeJacobians(Fblocks, E, b, myCameras, 0.0); - return nonDegenerate; + /** + * Triangulate and compute derivative of error with respect to point + * @return whether triangulation worked + */ + bool triangulateAndComputeE(Matrix& E, const Values& values) const { + Cameras cameras = this->cameras(values); + return triangulateAndComputeE(E, cameras); } + /// Compute F, E only (called below in both vanilla and SVD versions) /// Assumes the point has been computed /// Note E can be 2m*3 or 2m*2, in case point is degenerate - double computeJacobians(std::vector& Fblocks, - Matrix& E, Vector& b, const Cameras& cameras) const { - if (this->degenerate_) { - throw("FIXME: computeJacobians degenerate case commented out!"); -// std::cout << "manage degeneracy " << manageDegeneracy_ << std::endl; -// std::cout << "point " << point_ << std::endl; -// std::cout -// << "SmartStereoProjectionFactor: Management of degeneracy is disabled - not ready to be used" -// << std::endl; -// if (D > 6) { -// std::cout -// << "Management of degeneracy is not yet ready when one also optimizes for the calibration " -// << std::endl; -// } -// -// int numKeys = this->keys_.size(); -// E = zeros(2 * numKeys, 2); -// b = zero(2 * numKeys); -// double f = 0; -// for (size_t i = 0; i < this->measured_.size(); i++) { -// if (i == 0) { // first pose -// this->point_ = cameras[i].backprojectPointAtInfinity( -// this->measured_.at(i)); -// // 3D parametrization of point at infinity: [px py 1] -// } -// Matrix Fi, Ei; -// Vector bi = -(cameras[i].projectPointAtInfinity(this->point_, Fi, Ei) -// - this->measured_.at(i)).vector(); -// -// this->noise_.at(i)->WhitenSystem(Fi, Ei, bi); -// f += bi.squaredNorm(); -// Fblocks.push_back(typename Base::KeyMatrix2D(this->keys_[i], Fi)); -// E.block < 2, 2 > (2 * i, 0) = Ei; -// subInsert(b, bi, 2 * i); -// } -// return f; - } else { - // nondegenerate: just return Base version - return Base::computeJacobians(Fblocks, E, b, cameras, point_); - } // end else - } - -// /// Version that computes PointCov, with optional lambda parameter -// double computeJacobians(std::vector& Fblocks, -// Matrix& E, Matrix& PointCov, Vector& b, const Cameras& cameras, -// const double lambda = 0.0) const { -// -// double f = computeJacobians(Fblocks, E, b, cameras); -// -// // Point covariance inv(E'*E) -// PointCov.noalias() = (E.transpose() * E + lambda * eye(E.cols())).inverse(); -// -// return f; -// } -// -// /// takes values -// bool computeJacobiansSVD(std::vector& Fblocks, -// Matrix& Enull, Vector& b, const Values& values) const { -// typename Base::Cameras myCameras; -// double good = computeCamerasAndTriangulate(values, myCameras); -// if (good) -// computeJacobiansSVD(Fblocks, Enull, b, myCameras); -// return true; -// } -// -// /// SVD version -// double computeJacobiansSVD(std::vector& Fblocks, -// Matrix& Enull, Vector& b, const Cameras& cameras) const { -// return Base::computeJacobiansSVD(Fblocks, Enull, b, cameras, point_); -// } -// -// /// Returns Matrix, TODO: maybe should not exist -> not sparse ! -// // TODO should there be a lambda? -// double computeJacobiansSVD(Matrix& F, Matrix& Enull, Vector& b, -// const Cameras& cameras) const { -// return Base::computeJacobiansSVD(F, Enull, b, cameras, point_); -// } - - /// Returns Matrix, TODO: maybe should not exist -> not sparse ! - double computeJacobians(Matrix& F, Matrix& E, Vector& b, + void computeJacobiansWithTriangulatedPoint( + std::vector& Fblocks, Matrix& E, Vector& b, const Cameras& cameras) const { - return Base::computeJacobians(F, E, b, cameras, point_); + + if (!result_) { + throw ("computeJacobiansWithTriangulatedPoint"); +// // Handle degeneracy +// // TODO check flag whether we should do this +// Unit3 backProjected; /* = cameras[0].backprojectPointAtInfinity( +// this->measured_.at(0)); */ +// +// Base::computeJacobians(Fblocks, E, b, cameras, backProjected); + } else { + // valid result: just return Base version + Base::computeJacobians(Fblocks, E, b, cameras, *result_); + } } - /// Calculate vector of re-projection errors, before applying noise model - /// Assumes triangulation was done and degeneracy handled - Vector reprojectionError(const Cameras& cameras) const { - return Base::reprojectionError(cameras, point_); - } - - /// Calculate vector of re-projection errors, before applying noise model - Vector reprojectionError(const Values& values) const { - Cameras myCameras; - bool nonDegenerate = computeCamerasAndTriangulate(values, myCameras); + /// Version that takes values, and creates the point + bool triangulateAndComputeJacobians( + std::vector& Fblocks, Matrix& E, Vector& b, + const Values& values) const { + Cameras cameras = this->cameras(values); + bool nonDegenerate = triangulateForLinearize(cameras); if (nonDegenerate) - return reprojectionError(myCameras); + computeJacobiansWithTriangulatedPoint(Fblocks, E, b, cameras); + return nonDegenerate; + } + + /// takes values + bool triangulateAndComputeJacobiansSVD( + std::vector& Fblocks, Matrix& Enull, Vector& b, + const Values& values) const { + Cameras cameras = this->cameras(values); + bool nonDegenerate = triangulateForLinearize(cameras); + if (nonDegenerate) + Base::computeJacobiansSVD(Fblocks, Enull, b, cameras, *result_); + return nonDegenerate; + } + + /// Calculate vector of re-projection errors, before applying noise model + Vector reprojectionErrorAfterTriangulation(const Values& values) const { + Cameras cameras = this->cameras(values); + bool nonDegenerate = triangulateForLinearize(cameras); + if (nonDegenerate) + return Base::unwhitenedError(cameras, *result_); else - return zero(myCameras.size() * 3); + return zero(cameras.size() * Base::ZDim); } /** @@ -649,87 +540,61 @@ public: double totalReprojectionError(const Cameras& cameras, boost::optional externalPoint = boost::none) const { - size_t nrCameras; - if (externalPoint) { - nrCameras = this->keys_.size(); - point_ = *externalPoint; - degenerate_ = false; - cheiralityException_ = false; - } else { - nrCameras = this->triangulateSafe(cameras); - } + if (externalPoint) + result_ = TriangulationResult(*externalPoint); + else + result_ = triangulateSafe(cameras); - if (nrCameras < 2 - || (!this->manageDegeneracy_ - && (this->cheiralityException_ || this->degenerate_))) { + if (result_) + // All good, just use version in base class + return Base::totalReprojectionError(cameras, *result_); + else if (params_.degeneracyMode == HANDLE_INFINITY) { + throw(std::runtime_error("Backproject at infinity not implemented for SmartStereo.")); +// // Otherwise, manage the exceptions with rotation-only factors +// const StereoPoint2& z0 = this->measured_.at(0); +// Unit3 backprojected; //= cameras.front().backprojectPointAtInfinity(z0); +// +// return Base::totalReprojectionError(cameras, backprojected); + } else { // if we don't want to manage the exceptions we discard the factor - // std::cout << "In error evaluation: exception" << std::endl; return 0.0; } - - if (this->cheiralityException_) { // if we want to manage the exceptions with rotation-only factors - std::cout - << "SmartProjectionHessianFactor: cheirality exception (this should not happen if CheiralityException is disabled)!" - << std::endl; - this->degenerate_ = true; - } - - if (this->degenerate_) { - return 0.0; // TODO: this maybe should be zero? -// std::cout -// << "SmartProjectionHessianFactor: trying to manage degeneracy (this should not happen is manageDegeneracy is disabled)!" -// << std::endl; -// size_t i = 0; -// double overallError = 0; -// BOOST_FOREACH(const Camera& camera, cameras) { -// const StereoPoint2& zi = this->measured_.at(i); -// if (i == 0) // first pose -// this->point_ = camera.backprojectPointAtInfinity(zi); // 3D parametrization of point at infinity -// StereoPoint2 reprojectionError( -// camera.projectPointAtInfinity(this->point_) - zi); -// overallError += 0.5 -// * this->noise_.at(i)->distance(reprojectionError.vector()); -// i += 1; -// } -// return overallError; - } else { - // Just use version in base class - return Base::totalReprojectionError(cameras, point_); - } } - /// Cameras are computed in derived class - virtual Cameras cameras(const Values& values) const = 0; + /// Calculate total reprojection error + virtual double error(const Values& values) const { + if (this->active(values)) { + return totalReprojectionError(Base::cameras(values)); + } else { // else of active flag + return 0.0; + } + } /** return the landmark */ - boost::optional point() const { - return point_; - } + TriangulationResult point() const { + return result_; + } - /** COMPUTE the landmark */ - boost::optional point(const Values& values) const { - triangulateSafe(values); - return point_; - } + /** COMPUTE the landmark */ + TriangulationResult point(const Values& values) const { + Cameras cameras = this->cameras(values); + return triangulateSafe(cameras); + } - /** return the degenerate state */ - inline bool isDegenerate() const { - return (cheiralityException_ || degenerate_); - } + /// Is result valid? + bool isValid() const { + return bool(result_); + } - /** return the cheirality status flag */ - inline bool isPointBehindCamera() const { - return cheiralityException_; - } - /** return chirality verbosity */ - inline bool verboseCheirality() const { - return verboseCheirality_; - } + /** return the degenerate state */ + bool isDegenerate() const { + return result_.degenerate(); + } - /** return flag for throwing cheirality exceptions */ - inline bool throwCheirality() const { - return throwCheirality_; - } + /** return the cheirality status flag */ + bool isPointBehindCamera() const { + return result_.behindCamera(); + } private: @@ -738,15 +603,15 @@ private: template void serialize(ARCHIVE & ar, const unsigned int /*version*/) { ar & BOOST_SERIALIZATION_BASE_OBJECT_NVP(Base); - ar & BOOST_SERIALIZATION_NVP(throwCheirality_); - ar & BOOST_SERIALIZATION_NVP(verboseCheirality_); + ar & BOOST_SERIALIZATION_NVP(params_.throwCheirality); + ar & BOOST_SERIALIZATION_NVP(params_.verboseCheirality); } }; /// traits -template -struct traits > : - public Testable > { +template<> +struct traits : public Testable< + SmartStereoProjectionFactor> { }; } // \ namespace gtsam diff --git a/gtsam_unstable/slam/SmartStereoProjectionPoseFactor.h b/gtsam_unstable/slam/SmartStereoProjectionPoseFactor.h index 3db1c883e..c2526fd74 100644 --- a/gtsam_unstable/slam/SmartStereoProjectionPoseFactor.h +++ b/gtsam_unstable/slam/SmartStereoProjectionPoseFactor.h @@ -11,10 +11,11 @@ /** * @file SmartStereoProjectionPoseFactor.h - * @brief Produces an Hessian factors on POSES from monocular measurements of a single landmark + * @brief Smart stereo factor on poses, assuming camera calibration is fixed * @author Luca Carlone * @author Chris Beall * @author Zsolt Kira + * @author Frank Dellaert */ #pragma once @@ -34,46 +35,41 @@ namespace gtsam { */ /** - * The calibration is known here. The factor only constraints poses (variable dimension is 6) + * This factor assumes that camera calibration is fixed, but each camera + * has its own calibration. + * The factor only constrains poses (variable dimension is 6). + * This factor requires that values contains the involved poses (Pose3). * @addtogroup SLAM */ -template -class SmartStereoProjectionPoseFactor: public SmartStereoProjectionFactor { +class SmartStereoProjectionPoseFactor: public SmartStereoProjectionFactor { + protected: - LinearizationMode linearizeTo_; ///< How to linearize the factor (HESSIAN, JACOBIAN_SVD, JACOBIAN_Q) - - std::vector > K_all_; ///< shared pointer to calibration object (one for each camera) + std::vector > K_all_; ///< shared pointer to calibration object (one for each camera) public: EIGEN_MAKE_ALIGNED_OPERATOR_NEW /// shorthand for base class type - typedef SmartStereoProjectionFactor Base; + typedef SmartStereoProjectionFactor Base; /// shorthand for this class - typedef SmartStereoProjectionPoseFactor This; + typedef SmartStereoProjectionPoseFactor This; /// shorthand for a smart pointer to a factor typedef boost::shared_ptr shared_ptr; /** * Constructor - * @param rankTol tolerance used to check if point triangulation is degenerate - * @param linThreshold threshold on relative pose changes used to decide whether to relinearize (selective relinearization) - * @param manageDegeneracy is true, in presence of degenerate triangulation, the factor is converted to a rotation-only constraint, - * otherwise the factor is simply neglected - * @param enableEPI if set to true linear triangulation is refined with embedded LM iterations - * @param body_P_sensor is the transform from body to sensor frame (default identity) + * @param Isotropic measurement noise + * @param params internal parameters of the smart factors */ - SmartStereoProjectionPoseFactor(const double rankTol = 1, - const double linThreshold = -1, const bool manageDegeneracy = false, - const bool enableEPI = false, boost::optional body_P_sensor = boost::none, - LinearizationMode linearizeTo = HESSIAN, double landmarkDistanceThreshold = 1e10, - double dynamicOutlierRejectionThreshold = -1) : - Base(rankTol, linThreshold, manageDegeneracy, enableEPI, body_P_sensor, - landmarkDistanceThreshold, dynamicOutlierRejectionThreshold), linearizeTo_(linearizeTo) {} + SmartStereoProjectionPoseFactor(const SharedNoiseModel& sharedNoiseModel, + const SmartStereoProjectionParams& params = + SmartStereoProjectionParams()) : + Base(sharedNoiseModel, params) { + } /** Virtual destructor */ virtual ~SmartStereoProjectionPoseFactor() {} @@ -82,27 +78,23 @@ public: * add a new measurement and pose key * @param measured is the 2m dimensional location of the projection of a single landmark in the m view (the measurement) * @param poseKey is key corresponding to the camera observing the same landmark - * @param noise_i is the measurement noise - * @param K_i is the (known) camera calibration + * @param K is the (fixed) camera calibration */ - void add(const StereoPoint2 measured_i, const Key poseKey_i, - const SharedNoiseModel noise_i, - const boost::shared_ptr K_i) { - Base::add(measured_i, poseKey_i, noise_i); - K_all_.push_back(K_i); + void add(const StereoPoint2 measured, const Key poseKey, + const boost::shared_ptr K) { + Base::add(measured, poseKey); + K_all_.push_back(K); } /** * Variant of the previous one in which we include a set of measurements * @param measurements vector of the 2m dimensional location of the projection of a single landmark in the m view (the measurement) * @param poseKeys vector of keys corresponding to the camera observing the same landmark - * @param noises vector of measurement noises * @param Ks vector of calibration objects */ void add(std::vector measurements, std::vector poseKeys, - std::vector noises, - std::vector > Ks) { - Base::add(measurements, poseKeys, noises); + std::vector > Ks) { + Base::add(measurements, poseKeys); for (size_t i = 0; i < measurements.size(); i++) { K_all_.push_back(Ks.at(i)); } @@ -112,13 +104,12 @@ public: * Variant of the previous one in which we include a set of measurements with the same noise and calibration * @param mmeasurements vector of the 2m dimensional location of the projection of a single landmark in the m view (the measurement) * @param poseKeys vector of keys corresponding to the camera observing the same landmark - * @param noise measurement noise (same for all measurements) * @param K the (known) camera calibration (same for all measurements) */ void add(std::vector measurements, std::vector poseKeys, - const SharedNoiseModel noise, const boost::shared_ptr K) { + const boost::shared_ptr K) { for (size_t i = 0; i < measurements.size(); i++) { - Base::add(measurements.at(i), poseKeys.at(i), noise); + Base::add(measurements.at(i), poseKeys.at(i)); K_all_.push_back(K); } } @@ -131,57 +122,19 @@ public: void print(const std::string& s = "", const KeyFormatter& keyFormatter = DefaultKeyFormatter) const { std::cout << s << "SmartStereoProjectionPoseFactor, z = \n "; - BOOST_FOREACH(const boost::shared_ptr& K, K_all_) + BOOST_FOREACH(const boost::shared_ptr& K, K_all_) K->print("calibration = "); Base::print("", keyFormatter); } /// equals virtual bool equals(const NonlinearFactor& p, double tol = 1e-9) const { - const This *e = dynamic_cast(&p); + const SmartStereoProjectionPoseFactor *e = + dynamic_cast(&p); return e && Base::equals(p, tol); } - /** - * Collect all cameras involved in this factor - * @param values Values structure which must contain camera poses corresponding - * to keys involved in this factor - * @return vector of Values - */ - typename Base::Cameras cameras(const Values& values) const { - typename Base::Cameras cameras; - size_t i=0; - BOOST_FOREACH(const Key& k, this->keys_) { - Pose3 pose = values.at(k); - typename Base::Camera camera(pose, K_all_[i++]); - cameras.push_back(camera); - } - return cameras; - } - - /** - * Linearize to Gaussian Factor - * @param values Values structure which must contain camera poses for this factor - * @return - */ - virtual boost::shared_ptr linearize( - const Values& values) const { - // depending on flag set on construction we may linearize to different linear factors - switch(linearizeTo_){ - case JACOBIAN_SVD : - return this->createJacobianSVDFactor(cameras(values), 0.0); - break; - case JACOBIAN_Q : - throw("JacobianQ not working yet!"); -// return this->createJacobianQFactor(cameras(values), 0.0); - break; - default: - return this->createHessianFactor(cameras(values)); - break; - } - } - /** * error calculates the error of the factor. */ @@ -194,10 +147,27 @@ public: } /** return the calibration object */ - inline const std::vector > calibration() const { + inline const std::vector > calibration() const { return K_all_; } + /** + * Collect all cameras involved in this factor + * @param values Values structure which must contain camera poses corresponding + * to keys involved in this factor + * @return vector of Values + */ + Base::Cameras cameras(const Values& values) const { + Base::Cameras cameras; + size_t i=0; + BOOST_FOREACH(const Key& k, this->keys_) { + const Pose3& pose = values.at(k); + StereoCamera camera(pose, K_all_[i++]); + cameras.push_back(camera); + } + return cameras; + } + private: /// Serialization function @@ -211,9 +181,9 @@ private: }; // end of class declaration /// traits -template -struct traits > : public Testable< - SmartStereoProjectionPoseFactor > { +template<> +struct traits : public Testable< + SmartStereoProjectionPoseFactor> { }; } // \ namespace gtsam diff --git a/gtsam_unstable/slam/serialization.cpp b/gtsam_unstable/slam/serialization.cpp index a598fb689..7928a2aac 100644 --- a/gtsam_unstable/slam/serialization.cpp +++ b/gtsam_unstable/slam/serialization.cpp @@ -5,20 +5,19 @@ * @author Alex Cunningham */ -#include -#include +#include +#include #include #include //#include -#include -#include +#include #include //#include #include #include #include -#include +#include #include #include #include @@ -80,9 +79,6 @@ typedef RangeFactor RangeFactorSimpleCameraP typedef RangeFactor RangeFactorCalibratedCamera; typedef RangeFactor RangeFactorSimpleCamera; -typedef BearingFactor BearingFactor2D; -typedef BearingFactor BearingFactor3D; - typedef BearingRangeFactor BearingRangeFactor2D; typedef BearingRangeFactor BearingRangeFactor3D; @@ -185,8 +181,6 @@ BOOST_CLASS_EXPORT_GUID(RangeFactorSimpleCameraPoint, "gtsam::RangeFactorSimpleC BOOST_CLASS_EXPORT_GUID(RangeFactorCalibratedCamera, "gtsam::RangeFactorCalibratedCamera"); BOOST_CLASS_EXPORT_GUID(RangeFactorSimpleCamera, "gtsam::RangeFactorSimpleCamera"); -BOOST_CLASS_EXPORT_GUID(BearingFactor2D, "gtsam::BearingFactor2D"); - BOOST_CLASS_EXPORT_GUID(BearingRangeFactor2D, "gtsam::BearingRangeFactor2D"); BOOST_CLASS_EXPORT_GUID(GenericProjectionFactorCal3_S2, "gtsam::GenericProjectionFactorCal3_S2"); diff --git a/gtsam_unstable/slam/tests/testBiasedGPSFactor.cpp b/gtsam_unstable/slam/tests/testBiasedGPSFactor.cpp index d8a3ba0c1..c85187d5f 100644 --- a/gtsam_unstable/slam/tests/testBiasedGPSFactor.cpp +++ b/gtsam_unstable/slam/tests/testBiasedGPSFactor.cpp @@ -21,7 +21,7 @@ using symbol_shorthand::B; TEST(BiasedGPSFactor, errorNoiseless) { - Rot3 R = Rot3::rodriguez(0.1, 0.2, 0.3); + Rot3 R = Rot3::Rodrigues(0.1, 0.2, 0.3); Point3 t(1.0, 0.5, 0.2); Pose3 pose(R,t); Point3 bias(0.0,0.0,0.0); @@ -36,7 +36,7 @@ TEST(BiasedGPSFactor, errorNoiseless) { TEST(BiasedGPSFactor, errorNoisy) { - Rot3 R = Rot3::rodriguez(0.1, 0.2, 0.3); + Rot3 R = Rot3::Rodrigues(0.1, 0.2, 0.3); Point3 t(1.0, 0.5, 0.2); Pose3 pose(R,t); Point3 bias(0.0,0.0,0.0); @@ -51,7 +51,7 @@ TEST(BiasedGPSFactor, errorNoisy) { TEST(BiasedGPSFactor, jacobian) { - Rot3 R = Rot3::rodriguez(0.1, 0.2, 0.3); + Rot3 R = Rot3::Rodrigues(0.1, 0.2, 0.3); Point3 t(1.0, 0.5, 0.2); Pose3 pose(R,t); Point3 bias(0.0,0.0,0.0); diff --git a/gtsam_unstable/slam/tests/testGaussMarkov1stOrderFactor.cpp b/gtsam_unstable/slam/tests/testGaussMarkov1stOrderFactor.cpp index a86306a8d..209326672 100644 --- a/gtsam_unstable/slam/tests/testGaussMarkov1stOrderFactor.cpp +++ b/gtsam_unstable/slam/tests/testGaussMarkov1stOrderFactor.cpp @@ -21,7 +21,7 @@ #include #include #include -#include +#include using namespace std; using namespace gtsam; diff --git a/gtsam_unstable/slam/tests/testInvDepthFactor3.cpp b/gtsam_unstable/slam/tests/testInvDepthFactor3.cpp index 407c9a345..99f494ad9 100644 --- a/gtsam_unstable/slam/tests/testInvDepthFactor3.cpp +++ b/gtsam_unstable/slam/tests/testInvDepthFactor3.cpp @@ -22,7 +22,7 @@ static Cal3_S2::shared_ptr K(new Cal3_S2(1500, 1200, 0, 640, 480)); static SharedNoiseModel sigma(noiseModel::Unit::Create(2)); // camera pose at (0,0,1) looking straight along the x-axis. -Pose3 level_pose = Pose3(Rot3::ypr(-M_PI/2, 0., -M_PI/2), gtsam::Point3(0,0,1)); +Pose3 level_pose = Pose3(Rot3::Ypr(-M_PI/2, 0., -M_PI/2), gtsam::Point3(0,0,1)); SimpleCamera level_camera(level_pose, *K); typedef InvDepthFactor3 InverseDepthFactor; diff --git a/gtsam_unstable/slam/tests/testInvDepthFactorVariant1.cpp b/gtsam_unstable/slam/tests/testInvDepthFactorVariant1.cpp index 99a4f90a4..3aa758701 100644 --- a/gtsam_unstable/slam/tests/testInvDepthFactorVariant1.cpp +++ b/gtsam_unstable/slam/tests/testInvDepthFactorVariant1.cpp @@ -24,8 +24,8 @@ using namespace gtsam; TEST( InvDepthFactorVariant1, optimize) { // Create two poses looking in the x-direction - Pose3 pose1(Rot3::ypr(-M_PI/2, 0., -M_PI/2), Point3(0,0,1.0)); - Pose3 pose2(Rot3::ypr(-M_PI/2, 0., -M_PI/2), Point3(0,0,1.5)); + Pose3 pose1(Rot3::Ypr(-M_PI/2, 0., -M_PI/2), Point3(0,0,1.0)); + Pose3 pose2(Rot3::Ypr(-M_PI/2, 0., -M_PI/2), Point3(0,0,1.5)); // Create a landmark 5 meters in front of pose1 (camera center at (0,0,1)) Point3 landmark(5, 0, 1); diff --git a/gtsam_unstable/slam/tests/testInvDepthFactorVariant2.cpp b/gtsam_unstable/slam/tests/testInvDepthFactorVariant2.cpp index 2c85b3dad..d20fc000c 100644 --- a/gtsam_unstable/slam/tests/testInvDepthFactorVariant2.cpp +++ b/gtsam_unstable/slam/tests/testInvDepthFactorVariant2.cpp @@ -24,8 +24,8 @@ using namespace gtsam; TEST( InvDepthFactorVariant2, optimize) { // Create two poses looking in the x-direction - Pose3 pose1(Rot3::ypr(-M_PI/2, 0., -M_PI/2), gtsam::Point3(0,0,1.0)); - Pose3 pose2(Rot3::ypr(-M_PI/2, 0., -M_PI/2), gtsam::Point3(0,0,1.5)); + Pose3 pose1(Rot3::Ypr(-M_PI/2, 0., -M_PI/2), gtsam::Point3(0,0,1.0)); + Pose3 pose2(Rot3::Ypr(-M_PI/2, 0., -M_PI/2), gtsam::Point3(0,0,1.5)); // Create a landmark 5 meters in front of pose1 (camera center at (0,0,1)) Point3 landmark(5, 0, 1); diff --git a/gtsam_unstable/slam/tests/testInvDepthFactorVariant3.cpp b/gtsam_unstable/slam/tests/testInvDepthFactorVariant3.cpp index ec9aa90c3..a6eed54d5 100644 --- a/gtsam_unstable/slam/tests/testInvDepthFactorVariant3.cpp +++ b/gtsam_unstable/slam/tests/testInvDepthFactorVariant3.cpp @@ -24,8 +24,8 @@ using namespace gtsam; TEST( InvDepthFactorVariant3, optimize) { // Create two poses looking in the x-direction - Pose3 pose1(Rot3::ypr(-M_PI/2, 0., -M_PI/2), gtsam::Point3(0,0,1.0)); - Pose3 pose2(Rot3::ypr(-M_PI/2, 0., -M_PI/2), gtsam::Point3(0,0,1.5)); + Pose3 pose1(Rot3::Ypr(-M_PI/2, 0., -M_PI/2), gtsam::Point3(0,0,1.0)); + Pose3 pose2(Rot3::Ypr(-M_PI/2, 0., -M_PI/2), gtsam::Point3(0,0,1.5)); // Create a landmark 5 meters in front of pose1 (camera center at (0,0,1)) Point3 landmark(5, 0, 1); diff --git a/gtsam_unstable/slam/tests/testMultiProjectionFactor.cpp b/gtsam_unstable/slam/tests/testMultiProjectionFactor.cpp index 2794e5707..ca91d4cb5 100644 --- a/gtsam_unstable/slam/tests/testMultiProjectionFactor.cpp +++ b/gtsam_unstable/slam/tests/testMultiProjectionFactor.cpp @@ -69,7 +69,7 @@ TEST( MultiProjectionFactor, create ){ n_measPixel << 10, 10, 10, 10, 10, 10; const SharedDiagonal noiseProjection = noiseModel::Isotropic::Sigma(2, 1); - FastSet views; + KeySet views; views.insert(x1); views.insert(x2); views.insert(x3); diff --git a/gtsam_unstable/slam/tests/testRelativeElevationFactor.cpp b/gtsam_unstable/slam/tests/testRelativeElevationFactor.cpp index c6ad9a38b..a06c39182 100644 --- a/gtsam_unstable/slam/tests/testRelativeElevationFactor.cpp +++ b/gtsam_unstable/slam/tests/testRelativeElevationFactor.cpp @@ -18,7 +18,7 @@ SharedNoiseModel model1 = noiseModel::Unit::Create(1); const double tol = 1e-5; const Pose3 pose1(Rot3(), Point3(2.0, 3.0, 4.0)); -const Pose3 pose2(Rot3::pitch(-M_PI_2), Point3(2.0, 3.0, 4.0)); +const Pose3 pose2(Rot3::Pitch(-M_PI_2), Point3(2.0, 3.0, 4.0)); const Pose3 pose3(Rot3::RzRyRx(0.1, 0.2, 0.3), Point3(2.0, 3.0, 4.0)); const Point3 point1(3.0, 4.0, 2.0); const gtsam::Key poseKey = 1, pointKey = 2; diff --git a/gtsam_unstable/slam/tests/testSerialization.cpp b/gtsam_unstable/slam/tests/testSerialization.cpp index a5e09515c..1d8b30850 100644 --- a/gtsam_unstable/slam/tests/testSerialization.cpp +++ b/gtsam_unstable/slam/tests/testSerialization.cpp @@ -17,7 +17,7 @@ #include #include -#include +#include #include #include diff --git a/gtsam_unstable/slam/tests/testSmartStereoProjectionPoseFactor.cpp b/gtsam_unstable/slam/tests/testSmartStereoProjectionPoseFactor.cpp index eac63006d..5bad0e171 100644 --- a/gtsam_unstable/slam/tests/testSmartStereoProjectionPoseFactor.cpp +++ b/gtsam_unstable/slam/tests/testSmartStereoProjectionPoseFactor.cpp @@ -18,8 +18,8 @@ * @date Sept 2013 */ +// TODO #include #include - #include #include #include @@ -32,8 +32,6 @@ using namespace std; using namespace boost::assign; using namespace gtsam; -static bool isDebugTest = false; - // make a realistic calibration matrix static double fov = 60; // degrees static size_t w = 640, h = 480; @@ -42,11 +40,10 @@ static double b = 1; static Cal3_S2Stereo::shared_ptr K(new Cal3_S2Stereo(fov, w, h, b)); static Cal3_S2Stereo::shared_ptr K2( new Cal3_S2Stereo(1500, 1200, 0, 640, 480, b)); -static boost::shared_ptr Kbundler( - new Cal3Bundler(500, 1e-3, 1e-3, 1000, 2000)); -static double rankTol = 1.0; -static double linThreshold = -1.0; + +static SmartStereoProjectionParams params; + // static bool manageDegeneracy = true; // Create a noise model for the pixel error static SharedNoiseModel model(noiseModel::Isotropic::Sigma(3, 0.1)); @@ -65,9 +62,6 @@ static StereoPoint2 measurement1(323.0, 300.0, 240.0); //potentially use more re static Pose3 body_P_sensor1(Rot3::RzRyRx(-M_PI_2, 0.0, -M_PI_2), Point3(0.25, -0.10, 1.0)); -typedef SmartStereoProjectionPoseFactor SmartFactor; -typedef SmartStereoProjectionPoseFactor SmartFactorBundler; - vector stereo_projectToMultipleCameras(const StereoCamera& cam1, const StereoCamera& cam2, const StereoCamera& cam3, Point3 landmark) { @@ -83,55 +77,45 @@ vector stereo_projectToMultipleCameras(const StereoCamera& cam1, return measurements_cam; } +LevenbergMarquardtParams lm_params; + /* ************************************************************************* */ TEST( SmartStereoProjectionPoseFactor, Constructor) { - fprintf(stderr, "Test 1 Complete"); - SmartFactor::shared_ptr factor1(new SmartFactor()); + SmartStereoProjectionPoseFactor::shared_ptr factor1(new SmartStereoProjectionPoseFactor(model)); } /* ************************************************************************* */ TEST( SmartStereoProjectionPoseFactor, Constructor2) { - SmartFactor factor1(rankTol, linThreshold); + SmartStereoProjectionPoseFactor factor1(model, params); } /* ************************************************************************* */ TEST( SmartStereoProjectionPoseFactor, Constructor3) { - SmartFactor::shared_ptr factor1(new SmartFactor()); - factor1->add(measurement1, poseKey1, model, K); + SmartStereoProjectionPoseFactor::shared_ptr factor1(new SmartStereoProjectionPoseFactor(model)); + factor1->add(measurement1, poseKey1, K); } /* ************************************************************************* */ TEST( SmartStereoProjectionPoseFactor, Constructor4) { - SmartFactor factor1(rankTol, linThreshold); - factor1.add(measurement1, poseKey1, model, K); -} - -/* ************************************************************************* */ -TEST( SmartStereoProjectionPoseFactor, ConstructorWithTransform) { - bool manageDegeneracy = true; - bool enableEPI = false; - SmartFactor factor1(rankTol, linThreshold, manageDegeneracy, enableEPI, - body_P_sensor1); - factor1.add(measurement1, poseKey1, model, K); + SmartStereoProjectionPoseFactor factor1(model, params); + factor1.add(measurement1, poseKey1, K); } /* ************************************************************************* */ TEST( SmartStereoProjectionPoseFactor, Equals ) { - SmartFactor::shared_ptr factor1(new SmartFactor()); - factor1->add(measurement1, poseKey1, model, K); + SmartStereoProjectionPoseFactor::shared_ptr factor1(new SmartStereoProjectionPoseFactor(model)); + factor1->add(measurement1, poseKey1, K); - SmartFactor::shared_ptr factor2(new SmartFactor()); - factor2->add(measurement1, poseKey1, model, K); + SmartStereoProjectionPoseFactor::shared_ptr factor2(new SmartStereoProjectionPoseFactor(model)); + factor2->add(measurement1, poseKey1, K); CHECK(assert_equal(*factor1, *factor2)); } /* *************************************************************************/ TEST_UNSAFE( SmartStereoProjectionPoseFactor, noiseless ) { - // cout << " ************************ SmartStereoProjectionPoseFactor: noisy ****************************" << endl; - // create first camera. Looking along X-axis, 1 meter above ground plane (x-y) - Pose3 level_pose = Pose3(Rot3::ypr(-M_PI / 2, 0., -M_PI / 2), + Pose3 level_pose = Pose3(Rot3::Ypr(-M_PI / 2, 0., -M_PI / 2), Point3(0, 0, 1)); StereoCamera level_camera(level_pose, K2); @@ -150,15 +134,15 @@ TEST_UNSAFE( SmartStereoProjectionPoseFactor, noiseless ) { values.insert(x1, level_pose); values.insert(x2, level_pose_right); - SmartFactor factor1; - factor1.add(level_uv, x1, model, K2); - factor1.add(level_uv_right, x2, model, K2); + SmartStereoProjectionPoseFactor factor1(model); + factor1.add(level_uv, x1, K2); + factor1.add(level_uv_right, x2, K2); double actualError = factor1.error(values); double expectedError = 0.0; EXPECT_DOUBLES_EQUAL(expectedError, actualError, 1e-7); - SmartFactor::Cameras cameras = factor1.cameras(values); + SmartStereoProjectionPoseFactor::Cameras cameras = factor1.cameras(values); double actualError2 = factor1.totalReprojectionError(cameras); EXPECT_DOUBLES_EQUAL(expectedError, actualError2, 1e-7); @@ -169,10 +153,8 @@ TEST_UNSAFE( SmartStereoProjectionPoseFactor, noiseless ) { /* *************************************************************************/ TEST( SmartStereoProjectionPoseFactor, noisy ) { - // cout << " ************************ SmartStereoProjectionPoseFactor: noisy ****************************" << endl; - // create first camera. Looking along X-axis, 1 meter above ground plane (x-y) - Pose3 level_pose = Pose3(Rot3::ypr(-M_PI / 2, 0., -M_PI / 2), + Pose3 level_pose = Pose3(Rot3::Ypr(-M_PI / 2, 0., -M_PI / 2), Point3(0, 0, 1)); StereoCamera level_camera(level_pose, K2); @@ -190,25 +172,21 @@ TEST( SmartStereoProjectionPoseFactor, noisy ) { Values values; values.insert(x1, level_pose); - Pose3 noise_pose = Pose3(Rot3::ypr(-M_PI / 10, 0., -M_PI / 10), + Pose3 noise_pose = Pose3(Rot3::Ypr(-M_PI / 10, 0., -M_PI / 10), Point3(0.5, 0.1, 0.3)); values.insert(x2, level_pose_right.compose(noise_pose)); - SmartFactor::shared_ptr factor1(new SmartFactor()); - factor1->add(level_uv, x1, model, K); - factor1->add(level_uv_right, x2, model, K); + SmartStereoProjectionPoseFactor::shared_ptr factor1(new SmartStereoProjectionPoseFactor(model)); + factor1->add(level_uv, x1, K); + factor1->add(level_uv_right, x2, K); double actualError1 = factor1->error(values); - SmartFactor::shared_ptr factor2(new SmartFactor()); + SmartStereoProjectionPoseFactor::shared_ptr factor2(new SmartStereoProjectionPoseFactor(model)); vector measurements; measurements.push_back(level_uv); measurements.push_back(level_uv_right); - vector noises; - noises.push_back(model); - noises.push_back(model); - vector > Ks; ///< shared pointer to calibration object (one for each camera) Ks.push_back(K); Ks.push_back(K); @@ -217,7 +195,7 @@ TEST( SmartStereoProjectionPoseFactor, noisy ) { views.push_back(x1); views.push_back(x2); - factor2->add(measurements, views, noises, Ks); + factor2->add(measurements, views, Ks); double actualError2 = factor2->error(values); @@ -226,12 +204,9 @@ TEST( SmartStereoProjectionPoseFactor, noisy ) { /* *************************************************************************/ TEST( SmartStereoProjectionPoseFactor, 3poses_smart_projection_factor ) { - cout - << " ************************ SmartStereoProjectionPoseFactor: 3 cams + 3 landmarks **********************" - << endl; // create first camera. Looking along X-axis, 1 meter above ground plane (x-y) - Pose3 pose1 = Pose3(Rot3::ypr(-M_PI / 2, 0., -M_PI / 2), Point3(0, 0, 1)); + Pose3 pose1 = Pose3(Rot3::Ypr(-M_PI / 2, 0., -M_PI / 2), Point3(0, 0, 1)); StereoCamera cam1(pose1, K2); // create second camera 1 meter to the right of first camera @@ -248,11 +223,11 @@ TEST( SmartStereoProjectionPoseFactor, 3poses_smart_projection_factor ) { Point3 landmark3(3, 0, 3.0); // 1. Project three landmarks into three cameras and triangulate - vector measurements_cam1 = stereo_projectToMultipleCameras(cam1, + vector measurements_l1 = stereo_projectToMultipleCameras(cam1, cam2, cam3, landmark1); - vector measurements_cam2 = stereo_projectToMultipleCameras(cam1, + vector measurements_l2 = stereo_projectToMultipleCameras(cam1, cam2, cam3, landmark2); - vector measurements_cam3 = stereo_projectToMultipleCameras(cam1, + vector measurements_l3 = stereo_projectToMultipleCameras(cam1, cam2, cam3, landmark3); vector views; @@ -260,17 +235,21 @@ TEST( SmartStereoProjectionPoseFactor, 3poses_smart_projection_factor ) { views.push_back(x2); views.push_back(x3); - SmartFactor::shared_ptr smartFactor1(new SmartFactor()); - smartFactor1->add(measurements_cam1, views, model, K2); + SmartStereoProjectionParams smart_params; + smart_params.triangulation.enableEPI = true; + SmartStereoProjectionPoseFactor::shared_ptr smartFactor1(new SmartStereoProjectionPoseFactor(model, smart_params)); + smartFactor1->add(measurements_l1, views, K2); - SmartFactor::shared_ptr smartFactor2(new SmartFactor()); - smartFactor2->add(measurements_cam2, views, model, K2); + SmartStereoProjectionPoseFactor::shared_ptr smartFactor2(new SmartStereoProjectionPoseFactor(model, smart_params)); + smartFactor2->add(measurements_l2, views, K2); - SmartFactor::shared_ptr smartFactor3(new SmartFactor()); - smartFactor3->add(measurements_cam3, views, model, K2); + SmartStereoProjectionPoseFactor::shared_ptr smartFactor3(new SmartStereoProjectionPoseFactor(model, smart_params)); + smartFactor3->add(measurements_l3, views, K2); const SharedDiagonal noisePrior = noiseModel::Isotropic::Sigma(6, 0.10); + + NonlinearFactorGraph graph; graph.push_back(smartFactor1); graph.push_back(smartFactor2); @@ -278,39 +257,92 @@ TEST( SmartStereoProjectionPoseFactor, 3poses_smart_projection_factor ) { graph.push_back(PriorFactor(x1, pose1, noisePrior)); graph.push_back(PriorFactor(x2, pose2, noisePrior)); - // Pose3 noise_pose = Pose3(Rot3::ypr(-M_PI/10, 0., -M_PI/10), Point3(0.5,0.1,0.3)); // noise from regular projection factor test below - Pose3 noise_pose = Pose3(Rot3::ypr(-M_PI / 100, 0., -M_PI / 100), + // Pose3 noise_pose = Pose3(Rot3::Ypr(-M_PI/10, 0., -M_PI/10), Point3(0.5,0.1,0.3)); // noise from regular projection factor test below + Pose3 noise_pose = Pose3(Rot3::Ypr(-M_PI / 100, 0., -M_PI / 100), Point3(0.1, 0.1, 0.1)); // smaller noise Values values; values.insert(x1, pose1); values.insert(x2, pose2); // initialize third pose with some noise, we expect it to move back to original pose3 values.insert(x3, pose3 * noise_pose); - if (isDebugTest) - values.at(x3).print("Smart: Pose3 before optimization: "); + EXPECT( + assert_equal( + Pose3( + Rot3(0, -0.0314107591, 0.99950656, -0.99950656, -0.0313952598, + -0.000986635786, 0.0314107591, -0.999013364, -0.0313952598), + Point3(0.1, -0.1, 1.9)), values.at(x3))); - LevenbergMarquardtParams params; - if (isDebugTest) - params.verbosityLM = LevenbergMarquardtParams::TRYLAMBDA; - if (isDebugTest) - params.verbosity = NonlinearOptimizerParams::ERROR; + // cout << std::setprecision(10) << "\n----SmartStereoFactor graph initial error: " << graph.error(values) << endl; + EXPECT_DOUBLES_EQUAL(797312.95069157204, graph.error(values), 1e-7); + + // get triangulated landmarks from smart factors + Point3 landmark1_smart = *smartFactor1->point(); + Point3 landmark2_smart = *smartFactor2->point(); + Point3 landmark3_smart = *smartFactor3->point(); Values result; - gttic_ (SmartStereoProjectionPoseFactor); - LevenbergMarquardtOptimizer optimizer(graph, values, params); + gttic_(SmartStereoProjectionPoseFactor); + LevenbergMarquardtOptimizer optimizer(graph, values, lm_params); result = optimizer.optimize(); gttoc_(SmartStereoProjectionPoseFactor); tictoc_finishedIteration_(); -// GaussianFactorGraph::shared_ptr GFG = graph.linearize(values); -// VectorValues delta = GFG->optimize(); + EXPECT_DOUBLES_EQUAL(0, graph.error(result), 1e-5); + +// cout << std::setprecision(10) << "SmartStereoFactor graph optimized error: " << graph.error(result) << endl; + + GaussianFactorGraph::shared_ptr GFG = graph.linearize(result); + VectorValues delta = GFG->optimize(); + VectorValues expected = VectorValues::Zero(delta); + EXPECT(assert_equal(expected, delta, 1e-6)); // result.print("results of 3 camera, 3 landmark optimization \n"); - if (isDebugTest) - result.at(x3).print("Smart: Pose3 after optimization: "); EXPECT(assert_equal(pose3, result.at(x3))); - if (isDebugTest) - tictoc_print_(); + + /* *************************************************************** + * Same problem with regular Stereo factors, expect same error! + * ****************************************************************/ + +// landmark1_smart.print("landmark1_smart"); +// landmark2_smart.print("landmark2_smart"); +// landmark3_smart.print("landmark3_smart"); + + // add landmarks to values + values.insert(L(1), landmark1_smart); + values.insert(L(2), landmark2_smart); + values.insert(L(3), landmark3_smart); + + // add factors + NonlinearFactorGraph graph2; + + graph2.push_back(PriorFactor(x1, pose1, noisePrior)); + graph2.push_back(PriorFactor(x2, pose2, noisePrior)); + + typedef GenericStereoFactor ProjectionFactor; + + bool verboseCheirality = true; + + graph2.push_back(ProjectionFactor(measurements_l1[0], model, x1, L(1), K2, false, verboseCheirality)); + graph2.push_back(ProjectionFactor(measurements_l1[1], model, x2, L(1), K2, false, verboseCheirality)); + graph2.push_back(ProjectionFactor(measurements_l1[2], model, x3, L(1), K2, false, verboseCheirality)); + + graph2.push_back(ProjectionFactor(measurements_l2[0], model, x1, L(2), K2, false, verboseCheirality)); + graph2.push_back(ProjectionFactor(measurements_l2[1], model, x2, L(2), K2, false, verboseCheirality)); + graph2.push_back(ProjectionFactor(measurements_l2[2], model, x3, L(2), K2, false, verboseCheirality)); + + graph2.push_back(ProjectionFactor(measurements_l3[0], model, x1, L(3), K2, false, verboseCheirality)); + graph2.push_back(ProjectionFactor(measurements_l3[1], model, x2, L(3), K2, false, verboseCheirality)); + graph2.push_back(ProjectionFactor(measurements_l3[2], model, x3, L(3), K2, false, verboseCheirality)); + +// cout << std::setprecision(10) << "\n----StereoFactor graph initial error: " << graph2.error(values) << endl; + EXPECT_DOUBLES_EQUAL(797312.95069157204, graph2.error(values), 1e-7); + + LevenbergMarquardtOptimizer optimizer2(graph2, values, lm_params); + Values result2 = optimizer2.optimize(); + EXPECT_DOUBLES_EQUAL(0, graph2.error(result2), 1e-5); + +// cout << std::setprecision(10) << "StereoFactor graph optimized error: " << graph2.error(result2) << endl; + } /* *************************************************************************/ @@ -322,7 +354,7 @@ TEST( SmartStereoProjectionPoseFactor, jacobianSVD ) { views.push_back(x3); // create first camera. Looking along X-axis, 1 meter above ground plane (x-y) - Pose3 pose1 = Pose3(Rot3::ypr(-M_PI / 2, 0., -M_PI / 2), Point3(0, 0, 1)); + Pose3 pose1 = Pose3(Rot3::Ypr(-M_PI / 2, 0., -M_PI / 2), Point3(0, 0, 1)); StereoCamera cam1(pose1, K); // create second camera 1 meter to the right of first camera Pose3 pose2 = pose1 * Pose3(Rot3(), Point3(1, 0, 0)); @@ -344,17 +376,17 @@ TEST( SmartStereoProjectionPoseFactor, jacobianSVD ) { vector measurements_cam3 = stereo_projectToMultipleCameras(cam1, cam2, cam3, landmark3); - SmartFactor::shared_ptr smartFactor1( - new SmartFactor(1, -1, false, false, boost::none, JACOBIAN_SVD)); - smartFactor1->add(measurements_cam1, views, model, K); + SmartStereoProjectionParams params; + params.setLinearizationMode(JACOBIAN_SVD); - SmartFactor::shared_ptr smartFactor2( - new SmartFactor(1, -1, false, false, boost::none, JACOBIAN_SVD)); - smartFactor2->add(measurements_cam2, views, model, K); + SmartStereoProjectionPoseFactor::shared_ptr smartFactor1( new SmartStereoProjectionPoseFactor(model, params)); + smartFactor1->add(measurements_cam1, views, K); - SmartFactor::shared_ptr smartFactor3( - new SmartFactor(1, -1, false, false, boost::none, JACOBIAN_SVD)); - smartFactor3->add(measurements_cam3, views, model, K); + SmartStereoProjectionPoseFactor::shared_ptr smartFactor2(new SmartStereoProjectionPoseFactor(model, params)); + smartFactor2->add(measurements_cam2, views, K); + + SmartStereoProjectionPoseFactor::shared_ptr smartFactor3(new SmartStereoProjectionPoseFactor(model, params)); + smartFactor3->add(measurements_cam3, views, K); const SharedDiagonal noisePrior = noiseModel::Isotropic::Sigma(6, 0.10); @@ -365,17 +397,16 @@ TEST( SmartStereoProjectionPoseFactor, jacobianSVD ) { graph.push_back(PriorFactor(x1, pose1, noisePrior)); graph.push_back(PriorFactor(x2, pose2, noisePrior)); - // Pose3 noise_pose = Pose3(Rot3::ypr(-M_PI/10, 0., -M_PI/10), Point3(0.5,0.1,0.3)); // noise from regular projection factor test below - Pose3 noise_pose = Pose3(Rot3::ypr(-M_PI / 100, 0., -M_PI / 100), + // Pose3 noise_pose = Pose3(Rot3::Ypr(-M_PI/10, 0., -M_PI/10), Point3(0.5,0.1,0.3)); // noise from regular projection factor test below + Pose3 noise_pose = Pose3(Rot3::Ypr(-M_PI / 100, 0., -M_PI / 100), Point3(0.1, 0.1, 0.1)); // smaller noise Values values; values.insert(x1, pose1); values.insert(x2, pose2); values.insert(x3, pose3 * noise_pose); - LevenbergMarquardtParams params; Values result; - LevenbergMarquardtOptimizer optimizer(graph, values, params); + LevenbergMarquardtOptimizer optimizer(graph, values, lm_params); result = optimizer.optimize(); EXPECT(assert_equal(pose3, result.at(x3))); } @@ -383,7 +414,7 @@ TEST( SmartStereoProjectionPoseFactor, jacobianSVD ) { /* *************************************************************************/ TEST( SmartStereoProjectionPoseFactor, landmarkDistance ) { - double excludeLandmarksFutherThanDist = 2; +// double excludeLandmarksFutherThanDist = 2; vector views; views.push_back(x1); @@ -391,7 +422,7 @@ TEST( SmartStereoProjectionPoseFactor, landmarkDistance ) { views.push_back(x3); // create first camera. Looking along X-axis, 1 meter above ground plane (x-y) - Pose3 pose1 = Pose3(Rot3::ypr(-M_PI / 2, 0., -M_PI / 2), Point3(0, 0, 1)); + Pose3 pose1 = Pose3(Rot3::Ypr(-M_PI / 2, 0., -M_PI / 2), Point3(0, 0, 1)); StereoCamera cam1(pose1, K); // create second camera 1 meter to the right of first camera Pose3 pose2 = pose1 * Pose3(Rot3(), Point3(1, 0, 0)); @@ -413,20 +444,18 @@ TEST( SmartStereoProjectionPoseFactor, landmarkDistance ) { vector measurements_cam3 = stereo_projectToMultipleCameras(cam1, cam2, cam3, landmark3); - SmartFactor::shared_ptr smartFactor1( - new SmartFactor(1, -1, false, false, boost::none, JACOBIAN_SVD, - excludeLandmarksFutherThanDist)); - smartFactor1->add(measurements_cam1, views, model, K); + SmartStereoProjectionParams params; + params.setLinearizationMode(JACOBIAN_SVD); + params.setLandmarkDistanceThreshold(2); - SmartFactor::shared_ptr smartFactor2( - new SmartFactor(1, -1, false, false, boost::none, JACOBIAN_SVD, - excludeLandmarksFutherThanDist)); - smartFactor2->add(measurements_cam2, views, model, K); + SmartStereoProjectionPoseFactor::shared_ptr smartFactor1(new SmartStereoProjectionPoseFactor(model, params)); + smartFactor1->add(measurements_cam1, views, K); - SmartFactor::shared_ptr smartFactor3( - new SmartFactor(1, -1, false, false, boost::none, JACOBIAN_SVD, - excludeLandmarksFutherThanDist)); - smartFactor3->add(measurements_cam3, views, model, K); + SmartStereoProjectionPoseFactor::shared_ptr smartFactor2(new SmartStereoProjectionPoseFactor(model, params)); + smartFactor2->add(measurements_cam2, views, K); + + SmartStereoProjectionPoseFactor::shared_ptr smartFactor3(new SmartStereoProjectionPoseFactor(model, params)); + smartFactor3->add(measurements_cam3, views, K); const SharedDiagonal noisePrior = noiseModel::Isotropic::Sigma(6, 0.10); @@ -437,8 +466,8 @@ TEST( SmartStereoProjectionPoseFactor, landmarkDistance ) { graph.push_back(PriorFactor(x1, pose1, noisePrior)); graph.push_back(PriorFactor(x2, pose2, noisePrior)); - // Pose3 noise_pose = Pose3(Rot3::ypr(-M_PI/10, 0., -M_PI/10), Point3(0.5,0.1,0.3)); // noise from regular projection factor test below - Pose3 noise_pose = Pose3(Rot3::ypr(-M_PI / 100, 0., -M_PI / 100), + // Pose3 noise_pose = Pose3(Rot3::Ypr(-M_PI/10, 0., -M_PI/10), Point3(0.5,0.1,0.3)); // noise from regular projection factor test below + Pose3 noise_pose = Pose3(Rot3::Ypr(-M_PI / 100, 0., -M_PI / 100), Point3(0.1, 0.1, 0.1)); // smaller noise Values values; values.insert(x1, pose1); @@ -446,9 +475,8 @@ TEST( SmartStereoProjectionPoseFactor, landmarkDistance ) { values.insert(x3, pose3 * noise_pose); // All factors are disabled and pose should remain where it is - LevenbergMarquardtParams params; Values result; - LevenbergMarquardtOptimizer optimizer(graph, values, params); + LevenbergMarquardtOptimizer optimizer(graph, values, lm_params); result = optimizer.optimize(); EXPECT(assert_equal(values.at(x3), result.at(x3))); } @@ -456,16 +484,13 @@ TEST( SmartStereoProjectionPoseFactor, landmarkDistance ) { /* *************************************************************************/ TEST( SmartStereoProjectionPoseFactor, dynamicOutlierRejection ) { - double excludeLandmarksFutherThanDist = 1e10; - double dynamicOutlierRejectionThreshold = 1; // max 1 pixel of average reprojection error - vector views; views.push_back(x1); views.push_back(x2); views.push_back(x3); // create first camera. Looking along X-axis, 1 meter above ground plane (x-y) - Pose3 pose1 = Pose3(Rot3::ypr(-M_PI / 2, 0., -M_PI / 2), Point3(0, 0, 1)); + Pose3 pose1 = Pose3(Rot3::Ypr(-M_PI / 2, 0., -M_PI / 2), Point3(0, 0, 1)); StereoCamera cam1(pose1, K); // create second camera 1 meter to the right of first camera Pose3 pose2 = pose1 * Pose3(Rot3(), Point3(1, 0, 0)); @@ -492,25 +517,26 @@ TEST( SmartStereoProjectionPoseFactor, dynamicOutlierRejection ) { measurements_cam4.at(0) = measurements_cam4.at(0) + StereoPoint2(10, 10, 1); // add outlier - SmartFactor::shared_ptr smartFactor1( - new SmartFactor(1, -1, false, false, boost::none, JACOBIAN_SVD, - excludeLandmarksFutherThanDist, dynamicOutlierRejectionThreshold)); - smartFactor1->add(measurements_cam1, views, model, K); + SmartStereoProjectionParams params; + params.setLinearizationMode(JACOBIAN_SVD); + params.setDynamicOutlierRejectionThreshold(1); - SmartFactor::shared_ptr smartFactor2( - new SmartFactor(1, -1, false, false, boost::none, JACOBIAN_SVD, - excludeLandmarksFutherThanDist, dynamicOutlierRejectionThreshold)); - smartFactor2->add(measurements_cam2, views, model, K); - SmartFactor::shared_ptr smartFactor3( - new SmartFactor(1, -1, false, false, boost::none, JACOBIAN_SVD, - excludeLandmarksFutherThanDist, dynamicOutlierRejectionThreshold)); - smartFactor3->add(measurements_cam3, views, model, K); + SmartStereoProjectionPoseFactor::shared_ptr smartFactor1(new SmartStereoProjectionPoseFactor(model, params)); + smartFactor1->add(measurements_cam1, views, K); - SmartFactor::shared_ptr smartFactor4( - new SmartFactor(1, -1, false, false, boost::none, JACOBIAN_SVD, - excludeLandmarksFutherThanDist, dynamicOutlierRejectionThreshold)); - smartFactor4->add(measurements_cam4, views, model, K); + SmartStereoProjectionPoseFactor::shared_ptr smartFactor2(new SmartStereoProjectionPoseFactor(model, params)); + smartFactor2->add(measurements_cam2, views, K); + + SmartStereoProjectionPoseFactor::shared_ptr smartFactor3(new SmartStereoProjectionPoseFactor(model, params)); + smartFactor3->add(measurements_cam3, views, K); + + SmartStereoProjectionPoseFactor::shared_ptr smartFactor4(new SmartStereoProjectionPoseFactor(model, params)); + smartFactor4->add(measurements_cam4, views, K); + + // same as factor 4, but dynamic outlier rejection is off + SmartStereoProjectionPoseFactor::shared_ptr smartFactor4b(new SmartStereoProjectionPoseFactor(model)); + smartFactor4b->add(measurements_cam4, views, K); const SharedDiagonal noisePrior = noiseModel::Isotropic::Sigma(6, 0.10); @@ -522,17 +548,32 @@ TEST( SmartStereoProjectionPoseFactor, dynamicOutlierRejection ) { graph.push_back(PriorFactor(x1, pose1, noisePrior)); graph.push_back(PriorFactor(x2, pose2, noisePrior)); - Pose3 noise_pose = Pose3(Rot3::ypr(-M_PI / 100, 0., -M_PI / 100), + Pose3 noise_pose = Pose3(Rot3::Ypr(-M_PI / 100, 0., -M_PI / 100), Point3(0.1, 0.1, 0.1)); // smaller noise Values values; values.insert(x1, pose1); values.insert(x2, pose2); values.insert(x3, pose3); - // All factors are disabled and pose should remain where it is - LevenbergMarquardtParams params; + EXPECT_DOUBLES_EQUAL(0, smartFactor1->error(values), 1e-9); + EXPECT_DOUBLES_EQUAL(0, smartFactor2->error(values), 1e-9); + EXPECT_DOUBLES_EQUAL(0, smartFactor3->error(values), 1e-9); + // zero error due to dynamic outlier rejection + EXPECT_DOUBLES_EQUAL(0, smartFactor4->error(values), 1e-9); + + // dynamic outlier rejection is off + EXPECT_DOUBLES_EQUAL(6700, smartFactor4b->error(values), 1e-9); + + // Factors 1-3 should have valid point, factor 4 should not + EXPECT(smartFactor1->point()); + EXPECT(smartFactor2->point()); + EXPECT(smartFactor3->point()); + EXPECT(smartFactor4->point().degenerate()); + EXPECT(smartFactor4b->point()); + + // Factor 4 is disabled, pose 3 stays put Values result; - LevenbergMarquardtOptimizer optimizer(graph, values, params); + LevenbergMarquardtOptimizer optimizer(graph, values, lm_params); result = optimizer.optimize(); EXPECT(assert_equal(pose3, result.at(x3))); } @@ -546,7 +587,7 @@ TEST( SmartStereoProjectionPoseFactor, dynamicOutlierRejection ) { // views.push_back(x3); // // // create first camera. Looking along X-axis, 1 meter above ground plane (x-y) -// Pose3 pose1 = Pose3(Rot3::ypr(-M_PI/2, 0., -M_PI/2), Point3(0,0,1)); +// Pose3 pose1 = Pose3(Rot3::Ypr(-M_PI/2, 0., -M_PI/2), Point3(0,0,1)); // StereoCamera cam1(pose1, K); // // create second camera 1 meter to the right of first camera // Pose3 pose2 = pose1 * Pose3(Rot3(), Point3(1,0,0)); @@ -567,13 +608,13 @@ TEST( SmartStereoProjectionPoseFactor, dynamicOutlierRejection ) { // stereo_projectToMultipleCameras(cam1, cam2, cam3, landmark2, measurements_cam2); // stereo_projectToMultipleCameras(cam1, cam2, cam3, landmark3, measurements_cam3); // -// SmartFactor::shared_ptr smartFactor1(new SmartFactor(1, -1, false, false, boost::none, JACOBIAN_Q)); +// SmartStereoProjectionPoseFactor::shared_ptr smartFactor1(new SmartStereoProjectionPoseFactor(1, -1, false, false, JACOBIAN_Q)); // smartFactor1->add(measurements_cam1, views, model, K); // -// SmartFactor::shared_ptr smartFactor2(new SmartFactor(1, -1, false, false, boost::none, JACOBIAN_Q)); +// SmartStereoProjectionPoseFactor::shared_ptr smartFactor2(new SmartStereoProjectionPoseFactor(1, -1, false, false, JACOBIAN_Q)); // smartFactor2->add(measurements_cam2, views, model, K); // -// SmartFactor::shared_ptr smartFactor3(new SmartFactor(1, -1, false, false, boost::none, JACOBIAN_Q)); +// SmartStereoProjectionPoseFactor::shared_ptr smartFactor3(new SmartStereoProjectionPoseFactor(1, -1, false, false, JACOBIAN_Q)); // smartFactor3->add(measurements_cam3, views, model, K); // // const SharedDiagonal noisePrior = noiseModel::Isotropic::Sigma(6, 0.10); @@ -585,23 +626,21 @@ TEST( SmartStereoProjectionPoseFactor, dynamicOutlierRejection ) { // graph.push_back(PriorFactor(x1, pose1, noisePrior)); // graph.push_back(PriorFactor(x2, pose2, noisePrior)); // -// // Pose3 noise_pose = Pose3(Rot3::ypr(-M_PI/10, 0., -M_PI/10), Point3(0.5,0.1,0.3)); // noise from regular projection factor test below -// Pose3 noise_pose = Pose3(Rot3::ypr(-M_PI/100, 0., -M_PI/100), Point3(0.1,0.1,0.1)); // smaller noise +// // Pose3 noise_pose = Pose3(Rot3::Ypr(-M_PI/10, 0., -M_PI/10), Point3(0.5,0.1,0.3)); // noise from regular projection factor test below +// Pose3 noise_pose = Pose3(Rot3::Ypr(-M_PI/100, 0., -M_PI/100), Point3(0.1,0.1,0.1)); // smaller noise // Values values; // values.insert(x1, pose1); // values.insert(x2, pose2); // values.insert(x3, pose3*noise_pose); // -// LevenbergMarquardtParams params; -// Values result; -// LevenbergMarquardtOptimizer optimizer(graph, values, params); +//// Values result; +// LevenbergMarquardtOptimizer optimizer(graph, values, lm_params); // result = optimizer.optimize(); // EXPECT(assert_equal(pose3,result.at(x3))); //} // ///* *************************************************************************/ //TEST( SmartStereoProjectionPoseFactor, 3poses_projection_factor ){ -// // cout << " ************************ Normal ProjectionFactor: 3 cams + 3 landmarks **********************" << endl; // // vector views; // views.push_back(x1); @@ -609,7 +648,7 @@ TEST( SmartStereoProjectionPoseFactor, dynamicOutlierRejection ) { // views.push_back(x3); // // // create first camera. Looking along X-axis, 1 meter above ground plane (x-y) -// Pose3 pose1 = Pose3(Rot3::ypr(-M_PI/2, 0., -M_PI/2), Point3(0,0,1)); +// Pose3 pose1 = Pose3(Rot3::Ypr(-M_PI/2, 0., -M_PI/2), Point3(0,0,1)); // StereoCamera cam1(pose1, K2); // // // create second camera 1 meter to the right of first camera @@ -645,7 +684,7 @@ TEST( SmartStereoProjectionPoseFactor, dynamicOutlierRejection ) { // graph.push_back(PriorFactor(x1, pose1, noisePrior)); // graph.push_back(PriorFactor(x2, pose2, noisePrior)); // -// Pose3 noise_pose = Pose3(Rot3::ypr(-M_PI/10, 0., -M_PI/10), Point3(0.5,0.1,0.3)); +// Pose3 noise_pose = Pose3(Rot3::Ypr(-M_PI/10, 0., -M_PI/10), Point3(0.5,0.1,0.3)); // Values values; // values.insert(x1, pose1); // values.insert(x2, pose2); @@ -653,15 +692,10 @@ TEST( SmartStereoProjectionPoseFactor, dynamicOutlierRejection ) { // values.insert(L(1), landmark1); // values.insert(L(2), landmark2); // values.insert(L(3), landmark3); -// if(isDebugTest) values.at(x3).print("Pose3 before optimization: "); // -// LevenbergMarquardtParams params; -// if(isDebugTest) params.verbosityLM = LevenbergMarquardtParams::TRYLAMBDA; -// if(isDebugTest) params.verbosity = NonlinearOptimizerParams::ERROR; -// LevenbergMarquardtOptimizer optimizer(graph, values, params); +// LevenbergMarquardtOptimizer optimizer(graph, values, lm_params); // Values result = optimizer.optimize(); // -// if(isDebugTest) result.at(x3).print("Pose3 after optimization: "); // EXPECT(assert_equal(pose3,result.at(x3))); //} // @@ -674,7 +708,7 @@ TEST( SmartStereoProjectionPoseFactor, CheckHessian) { views.push_back(x3); // create first camera. Looking along X-axis, 1 meter above ground plane (x-y) - Pose3 pose1 = Pose3(Rot3::ypr(-M_PI / 2, 0., -M_PI / 2), Point3(0, 0, 1)); + Pose3 pose1 = Pose3(Rot3::Ypr(-M_PI / 2, 0., -M_PI / 2), Point3(0, 0, 1)); StereoCamera cam1(pose1, K); // create second camera @@ -698,17 +732,17 @@ TEST( SmartStereoProjectionPoseFactor, CheckHessian) { vector measurements_cam3 = stereo_projectToMultipleCameras(cam1, cam2, cam3, landmark3); - // Create smartfactors - double rankTol = 10; + SmartStereoProjectionParams params; + params.setRankTolerance(10); - SmartFactor::shared_ptr smartFactor1(new SmartFactor(rankTol)); - smartFactor1->add(measurements_cam1, views, model, K); + SmartStereoProjectionPoseFactor::shared_ptr smartFactor1(new SmartStereoProjectionPoseFactor(model, params)); + smartFactor1->add(measurements_cam1, views, K); - SmartFactor::shared_ptr smartFactor2(new SmartFactor(rankTol)); - smartFactor2->add(measurements_cam2, views, model, K); + SmartStereoProjectionPoseFactor::shared_ptr smartFactor2(new SmartStereoProjectionPoseFactor(model, params)); + smartFactor2->add(measurements_cam2, views, K); - SmartFactor::shared_ptr smartFactor3(new SmartFactor(rankTol)); - smartFactor3->add(measurements_cam3, views, model, K); + SmartStereoProjectionPoseFactor::shared_ptr smartFactor3(new SmartStereoProjectionPoseFactor(model, params)); + smartFactor3->add(measurements_cam3, views, K); // Create graph to optimize NonlinearFactorGraph graph; @@ -720,11 +754,9 @@ TEST( SmartStereoProjectionPoseFactor, CheckHessian) { values.insert(x1, pose1); values.insert(x2, pose2); // initialize third pose with some noise, we expect it to move back to original pose3 - Pose3 noise_pose = Pose3(Rot3::ypr(-M_PI / 100, 0., -M_PI / 100), + Pose3 noise_pose = Pose3(Rot3::Ypr(-M_PI / 100, 0., -M_PI / 100), Point3(0.1, 0.1, 0.1)); // smaller noise values.insert(x3, pose3 * noise_pose); - if (isDebugTest) - values.at(x3).print("Smart: Pose3 before optimization: "); // TODO: next line throws Cheirality exception on Mac boost::shared_ptr hessianFactor1 = smartFactor1->linearize( @@ -749,7 +781,6 @@ TEST( SmartStereoProjectionPoseFactor, CheckHessian) { + hessianFactor3->augmentedInformation(); // Check Information vector - // cout << AugInformationMatrix.size() << endl; Vector InfoVector = AugInformationMatrix.block(0, 18, 18, 1); // 18x18 Hessian + information vector // Check Hessian @@ -758,7 +789,6 @@ TEST( SmartStereoProjectionPoseFactor, CheckHessian) { // ///* *************************************************************************/ //TEST( SmartStereoProjectionPoseFactor, 3poses_2land_rotation_only_smart_projection_factor ){ -// // cout << " ************************ SmartStereoProjectionPoseFactor: 3 cams + 2 landmarks: Rotation Only**********************" << endl; // // vector views; // views.push_back(x1); @@ -766,7 +796,7 @@ TEST( SmartStereoProjectionPoseFactor, CheckHessian) { // views.push_back(x3); // // // create first camera. Looking along X-axis, 1 meter above ground plane (x-y) -// Pose3 pose1 = Pose3(Rot3::ypr(-M_PI/2, 0., -M_PI/2), Point3(0,0,1)); +// Pose3 pose1 = Pose3(Rot3::Ypr(-M_PI/2, 0., -M_PI/2), Point3(0,0,1)); // StereoCamera cam1(pose1, K2); // // // create second camera 1 meter to the right of first camera @@ -788,10 +818,10 @@ TEST( SmartStereoProjectionPoseFactor, CheckHessian) { // stereo_projectToMultipleCameras(cam1, cam2, cam3, landmark2, measurements_cam2); // // double rankTol = 50; -// SmartFactor::shared_ptr smartFactor1(new SmartFactor(rankTol, linThreshold, manageDegeneracy)); +// SmartStereoProjectionPoseFactor::shared_ptr smartFactor1(new SmartStereoProjectionPoseFactor(rankTol, linThreshold, manageDegeneracy)); // smartFactor1->add(measurements_cam1, views, model, K2); // -// SmartFactor::shared_ptr smartFactor2(new SmartFactor(rankTol, linThreshold, manageDegeneracy)); +// SmartStereoProjectionPoseFactor::shared_ptr smartFactor2(new SmartStereoProjectionPoseFactor(rankTol, linThreshold, manageDegeneracy)); // smartFactor2->add(measurements_cam2, views, model, K2); // // const SharedDiagonal noisePrior = noiseModel::Isotropic::Sigma(6, 0.10); @@ -805,35 +835,26 @@ TEST( SmartStereoProjectionPoseFactor, CheckHessian) { // graph.push_back(PoseTranslationPrior(x2, positionPrior, noisePriorTranslation)); // graph.push_back(PoseTranslationPrior(x3, positionPrior, noisePriorTranslation)); // -// Pose3 noise_pose = Pose3(Rot3::ypr(-M_PI/10, 0., -M_PI/10), Point3(0.1,0.1,0.1)); // smaller noise +// Pose3 noise_pose = Pose3(Rot3::Ypr(-M_PI/10, 0., -M_PI/10), Point3(0.1,0.1,0.1)); // smaller noise // Values values; // values.insert(x1, pose1); // values.insert(x2, pose2*noise_pose); // // initialize third pose with some noise, we expect it to move back to original pose3 // values.insert(x3, pose3*noise_pose*noise_pose); -// if(isDebugTest) values.at(x3).print("Smart: Pose3 before optimization: "); -// -// LevenbergMarquardtParams params; -// if(isDebugTest) params.verbosityLM = LevenbergMarquardtParams::TRYDELTA; -// if(isDebugTest) params.verbosity = NonlinearOptimizerParams::ERROR; // // Values result; // gttic_(SmartStereoProjectionPoseFactor); -// LevenbergMarquardtOptimizer optimizer(graph, values, params); +// LevenbergMarquardtOptimizer optimizer(graph, values, lm_params); // result = optimizer.optimize(); // gttoc_(SmartStereoProjectionPoseFactor); // tictoc_finishedIteration_(); // // // result.print("results of 3 camera, 3 landmark optimization \n"); -// if(isDebugTest) result.at(x3).print("Smart: Pose3 after optimization: "); -// cout << "TEST COMMENTED: rotation only version of smart factors has been deprecated " << endl; // // EXPECT(assert_equal(pose3,result.at(x3))); -// if(isDebugTest) tictoc_print_(); //} // ///* *************************************************************************/ //TEST( SmartStereoProjectionPoseFactor, 3poses_rotation_only_smart_projection_factor ){ -// // cout << " ************************ SmartStereoProjectionPoseFactor: 3 cams + 3 landmarks: Rotation Only**********************" << endl; // // vector views; // views.push_back(x1); @@ -841,7 +862,7 @@ TEST( SmartStereoProjectionPoseFactor, CheckHessian) { // views.push_back(x3); // // // create first camera. Looking along X-axis, 1 meter above ground plane (x-y) -// Pose3 pose1 = Pose3(Rot3::ypr(-M_PI/2, 0., -M_PI/2), Point3(0,0,1)); +// Pose3 pose1 = Pose3(Rot3::Ypr(-M_PI/2, 0., -M_PI/2), Point3(0,0,1)); // StereoCamera cam1(pose1, K); // // // create second camera 1 meter to the right of first camera @@ -866,13 +887,13 @@ TEST( SmartStereoProjectionPoseFactor, CheckHessian) { // // double rankTol = 10; // -// SmartFactor::shared_ptr smartFactor1(new SmartFactor(rankTol, linThreshold, manageDegeneracy)); +// SmartStereoProjectionPoseFactor::shared_ptr smartFactor1(new SmartStereoProjectionPoseFactor(rankTol, linThreshold, manageDegeneracy)); // smartFactor1->add(measurements_cam1, views, model, K); // -// SmartFactor::shared_ptr smartFactor2(new SmartFactor(rankTol, linThreshold, manageDegeneracy)); +// SmartStereoProjectionPoseFactor::shared_ptr smartFactor2(new SmartStereoProjectionPoseFactor(rankTol, linThreshold, manageDegeneracy)); // smartFactor2->add(measurements_cam2, views, model, K); // -// SmartFactor::shared_ptr smartFactor3(new SmartFactor(rankTol, linThreshold, manageDegeneracy)); +// SmartStereoProjectionPoseFactor::shared_ptr smartFactor3(new SmartStereoProjectionPoseFactor(rankTol, linThreshold, manageDegeneracy)); // smartFactor3->add(measurements_cam3, views, model, K); // // const SharedDiagonal noisePrior = noiseModel::Isotropic::Sigma(6, 0.10); @@ -887,43 +908,34 @@ TEST( SmartStereoProjectionPoseFactor, CheckHessian) { // graph.push_back(PoseTranslationPrior(x2, positionPrior, noisePriorTranslation)); // graph.push_back(PoseTranslationPrior(x3, positionPrior, noisePriorTranslation)); // -// // Pose3 noise_pose = Pose3(Rot3::ypr(-M_PI/10, 0., -M_PI/10), Point3(0.5,0.1,0.3)); // noise from regular projection factor test below -// Pose3 noise_pose = Pose3(Rot3::ypr(-M_PI/100, 0., -M_PI/100), Point3(0.1,0.1,0.1)); // smaller noise +// // Pose3 noise_pose = Pose3(Rot3::Ypr(-M_PI/10, 0., -M_PI/10), Point3(0.5,0.1,0.3)); // noise from regular projection factor test below +// Pose3 noise_pose = Pose3(Rot3::Ypr(-M_PI/100, 0., -M_PI/100), Point3(0.1,0.1,0.1)); // smaller noise // Values values; // values.insert(x1, pose1); // values.insert(x2, pose2); // // initialize third pose with some noise, we expect it to move back to original pose3 // values.insert(x3, pose3*noise_pose); -// if(isDebugTest) values.at(x3).print("Smart: Pose3 before optimization: "); -// -// LevenbergMarquardtParams params; -// if(isDebugTest) params.verbosityLM = LevenbergMarquardtParams::TRYDELTA; -// if(isDebugTest) params.verbosity = NonlinearOptimizerParams::ERROR; // // Values result; // gttic_(SmartStereoProjectionPoseFactor); -// LevenbergMarquardtOptimizer optimizer(graph, values, params); +// LevenbergMarquardtOptimizer optimizer(graph, values, lm_params); // result = optimizer.optimize(); // gttoc_(SmartStereoProjectionPoseFactor); // tictoc_finishedIteration_(); // // // result.print("results of 3 camera, 3 landmark optimization \n"); -// if(isDebugTest) result.at(x3).print("Smart: Pose3 after optimization: "); -// cout << "TEST COMMENTED: rotation only version of smart factors has been deprecated " << endl; // // EXPECT(assert_equal(pose3,result.at(x3))); -// if(isDebugTest) tictoc_print_(); //} // ///* *************************************************************************/ //TEST( SmartStereoProjectionPoseFactor, Hessian ){ -// // cout << " ************************ SmartStereoProjectionPoseFactor: Hessian **********************" << endl; // // vector views; // views.push_back(x1); // views.push_back(x2); // // // create first camera. Looking along X-axis, 1 meter above ground plane (x-y) -// Pose3 pose1 = Pose3(Rot3::ypr(-M_PI/2, 0., -M_PI/2), Point3(0,0,1)); +// Pose3 pose1 = Pose3(Rot3::Ypr(-M_PI/2, 0., -M_PI/2), Point3(0,0,1)); // StereoCamera cam1(pose1, K2); // // // create second camera 1 meter to the right of first camera @@ -940,16 +952,15 @@ TEST( SmartStereoProjectionPoseFactor, CheckHessian) { // measurements_cam1.push_back(cam1_uv1); // measurements_cam1.push_back(cam2_uv1); // -// SmartFactor::shared_ptr smartFactor1(new SmartFactor()); +// SmartStereoProjectionPoseFactor::shared_ptr smartFactor1(new SmartStereoProjectionPoseFactor()); // smartFactor1->add(measurements_cam1,views, model, K2); // -// Pose3 noise_pose = Pose3(Rot3::ypr(-M_PI/10, 0., -M_PI/10), Point3(0.5,0.1,0.3)); +// Pose3 noise_pose = Pose3(Rot3::Ypr(-M_PI/10, 0., -M_PI/10), Point3(0.5,0.1,0.3)); // Values values; // values.insert(x1, pose1); // values.insert(x2, pose2); // // boost::shared_ptr hessianFactor = smartFactor1->linearize(values); -// if(isDebugTest) hessianFactor->print("Hessian factor \n"); // // // compute triangulation from linearization point // // compute reprojection errors (sum squared) @@ -960,15 +971,13 @@ TEST( SmartStereoProjectionPoseFactor, CheckHessian) { /* *************************************************************************/ TEST( SmartStereoProjectionPoseFactor, HessianWithRotation ) { - // cout << " ************************ SmartStereoProjectionPoseFactor: rotated Hessian **********************" << endl; - vector views; views.push_back(x1); views.push_back(x2); views.push_back(x3); // create first camera. Looking along X-axis, 1 meter above ground plane (x-y) - Pose3 pose1 = Pose3(Rot3::ypr(-M_PI / 2, 0., -M_PI / 2), Point3(0, 0, 1)); + Pose3 pose1 = Pose3(Rot3::Ypr(-M_PI / 2, 0., -M_PI / 2), Point3(0, 0, 1)); StereoCamera cam1(pose1, K); // create second camera 1 meter to the right of first camera @@ -984,8 +993,8 @@ TEST( SmartStereoProjectionPoseFactor, HessianWithRotation ) { vector measurements_cam1 = stereo_projectToMultipleCameras(cam1, cam2, cam3, landmark1); - SmartFactor::shared_ptr smartFactorInstance(new SmartFactor()); - smartFactorInstance->add(measurements_cam1, views, model, K); + SmartStereoProjectionPoseFactor::shared_ptr smartFactorInstance(new SmartStereoProjectionPoseFactor(model)); + smartFactorInstance->add(measurements_cam1, views, K); Values values; values.insert(x1, pose1); @@ -996,7 +1005,7 @@ TEST( SmartStereoProjectionPoseFactor, HessianWithRotation ) { smartFactorInstance->linearize(values); // hessianFactor->print("Hessian factor \n"); - Pose3 poseDrift = Pose3(Rot3::ypr(-M_PI / 2, 0., -M_PI / 2), Point3(0, 0, 0)); + Pose3 poseDrift = Pose3(Rot3::Ypr(-M_PI / 2, 0., -M_PI / 2), Point3(0, 0, 0)); Values rotValues; rotValues.insert(x1, poseDrift.compose(pose1)); @@ -1012,7 +1021,7 @@ TEST( SmartStereoProjectionPoseFactor, HessianWithRotation ) { assert_equal(hessianFactor->information(), hessianFactorRot->information(), 1e-7)); - Pose3 poseDrift2 = Pose3(Rot3::ypr(-M_PI / 2, -M_PI / 3, -M_PI / 2), + Pose3 poseDrift2 = Pose3(Rot3::Ypr(-M_PI / 2, -M_PI / 3, -M_PI / 2), Point3(10, -4, 5)); Values tranValues; @@ -1031,7 +1040,6 @@ TEST( SmartStereoProjectionPoseFactor, HessianWithRotation ) { /* *************************************************************************/ TEST( SmartStereoProjectionPoseFactor, HessianWithRotationDegenerate ) { - // cout << " ************************ SmartStereoProjectionPoseFactor: rotated Hessian (degenerate) **********************" << endl; vector views; views.push_back(x1); @@ -1039,7 +1047,7 @@ TEST( SmartStereoProjectionPoseFactor, HessianWithRotationDegenerate ) { views.push_back(x3); // create first camera. Looking along X-axis, 1 meter above ground plane (x-y) - Pose3 pose1 = Pose3(Rot3::ypr(-M_PI / 2, 0., -M_PI / 2), Point3(0, 0, 1)); + Pose3 pose1 = Pose3(Rot3::Ypr(-M_PI / 2, 0., -M_PI / 2), Point3(0, 0, 1)); StereoCamera cam1(pose1, K2); // Second and third cameras in same place, which is a degenerate configuration @@ -1053,8 +1061,8 @@ TEST( SmartStereoProjectionPoseFactor, HessianWithRotationDegenerate ) { vector measurements_cam1 = stereo_projectToMultipleCameras(cam1, cam2, cam3, landmark1); - SmartFactor::shared_ptr smartFactor(new SmartFactor()); - smartFactor->add(measurements_cam1, views, model, K2); + SmartStereoProjectionPoseFactor::shared_ptr smartFactor(new SmartStereoProjectionPoseFactor(model)); + smartFactor->add(measurements_cam1, views, K2); Values values; values.insert(x1, pose1); @@ -1063,10 +1071,8 @@ TEST( SmartStereoProjectionPoseFactor, HessianWithRotationDegenerate ) { boost::shared_ptr hessianFactor = smartFactor->linearize( values); - if (isDebugTest) - hessianFactor->print("Hessian factor \n"); - Pose3 poseDrift = Pose3(Rot3::ypr(-M_PI / 2, 0., -M_PI / 2), Point3(0, 0, 0)); + Pose3 poseDrift = Pose3(Rot3::Ypr(-M_PI / 2, 0., -M_PI / 2), Point3(0, 0, 0)); Values rotValues; rotValues.insert(x1, poseDrift.compose(pose1)); @@ -1075,15 +1081,13 @@ TEST( SmartStereoProjectionPoseFactor, HessianWithRotationDegenerate ) { boost::shared_ptr hessianFactorRot = smartFactor->linearize( rotValues); - if (isDebugTest) - hessianFactorRot->print("Hessian factor \n"); // Hessian is invariant to rotations in the nondegenerate case EXPECT( assert_equal(hessianFactor->information(), - hessianFactorRot->information(), 1e-8)); + hessianFactorRot->information(), 1e-6)); - Pose3 poseDrift2 = Pose3(Rot3::ypr(-M_PI / 2, -M_PI / 3, -M_PI / 2), + Pose3 poseDrift2 = Pose3(Rot3::Ypr(-M_PI / 2, -M_PI / 3, -M_PI / 2), Point3(10, -4, 5)); Values tranValues; @@ -1097,7 +1101,7 @@ TEST( SmartStereoProjectionPoseFactor, HessianWithRotationDegenerate ) { // Hessian is invariant to rotations and translations in the nondegenerate case EXPECT( assert_equal(hessianFactor->information(), - hessianFactorRotTran->information(), 1e-8)); + hessianFactorRotTran->information(), 1e-6)); } /* ************************************************************************* */ diff --git a/gtsampy.h b/gtsampy.h new file mode 100644 index 000000000..ca014ad5d --- /dev/null +++ b/gtsampy.h @@ -0,0 +1,2669 @@ +/** + + * GTSAM Wrap Module Definition + * + * These are the current classes available through the matlab toolbox interface, + * add more functions/classes as they are available. + * + * Requirements: + * Classes must start with an uppercase letter + * - Can wrap a typedef + * Only one Method/Constructor per line, though methods/constructors can extend across multiple lines + * Methods can return + * - Eigen types: Matrix, Vector + * - C/C++ basic types: string, bool, size_t, int, double, char, unsigned char + * - void + * - Any class with which be copied with boost::make_shared() + * - boost::shared_ptr of any object type + * Constructors + * - Overloads are supported + * - A class with no constructors can be returned from other functions but not allocated directly in MATLAB + * Methods + * - Constness has no effect + * - Specify by-value (not reference) return types, even if C++ method returns reference + * - Must start with a letter (upper or lowercase) + * - Overloads are supported + * Static methods + * - Must start with a letter (upper or lowercase) and use the "static" keyword + * - The first letter will be made uppercase in the generated MATLAB interface + * - Overloads are supported + * Arguments to functions any of + * - Eigen types: Matrix, Vector + * - Eigen types and classes as an optionally const reference + * - C/C++ basic types: string, bool, size_t, size_t, double, char, unsigned char + * - Any class with which be copied with boost::make_shared() (except Eigen) + * - boost::shared_ptr of any object type (except Eigen) + * Comments can use either C++ or C style, with multiple lines + * Namespace definitions + * - Names of namespaces must start with a lowercase letter + * - start a namespace with "namespace {" + * - end a namespace with exactly "}" + * - Namespaces can be nested + * Namespace usage + * - Namespaces can be specified for classes in arguments and return values + * - In each case, the namespace must be fully specified, e.g., "namespace1::namespace2::ClassName" + * Includes in C++ wrappers + * - All includes will be collected and added in a single file + * - All namespaces must have angle brackets: + * - No default includes will be added + * Global/Namespace functions + * - Functions specified outside of a class are global + * - Can be overloaded with different arguments + * - Can have multiple functions of the same name in different namespaces + * Using classes defined in other modules + * - If you are using a class 'OtherClass' not wrapped in this definition file, add "class OtherClass;" to avoid a dependency error + * Virtual inheritance + * - Specify fully-qualified base classes, i.e. "virtual class Derived : ns::Base {" where "ns" is the namespace + * - Mark with 'virtual' keyword, e.g. "virtual class Base {", and also "virtual class Derived : ns::Base {" + * - Forward declarations must also be marked virtual, e.g. "virtual class ns::Base;" and + * also "virtual class ns::Derived;" + * - Pure virtual (abstract) classes should list no constructors in this interface file + * - Virtual classes must have a clone() function in C++ (though it does not have to be included + * in the MATLAB interface). clone() will be called whenever an object copy is needed, instead + * of using the copy constructor (which is used for non-virtual objects). + * - Signature of clone function - will be called virtually, so must appear at least at the top of the inheritance tree + * virtual boost::shared_ptr clone() const; + * Class Templates + * - Basic templates are supported either with an explicit list of types to instantiate, + * e.g. template class Class1 { ... }; + * or with typedefs, e.g. + * template class Class2 { ... }; + * typedef Class2 MyInstantiatedClass; + * - In the class definition, appearances of the template argument(s) will be replaced with their + * instantiated types, e.g. 'void setValue(const T& value);'. + * - To refer to the instantiation of the template class itself, use 'This', i.e. 'static This Create();' + * - To create new instantiations in other modules, you must copy-and-paste the whole class definition + * into the new module, but use only your new instantiation types. + * - When forward-declaring template instantiations, use the generated/typedefed name, e.g. + * class gtsam::Class1Pose2; + * class gtsam::MyInstantiatedClass; + * Boost.serialization within Matlab: + * - you need to mark classes as being serializable in the markup file (see this file for an example). + * - There are two options currently, depending on the class. To "mark" a class as serializable, + * add a function with a particular signature so that wrap will catch it. + * - Add "void serialize()" to a class to create serialization functions for a class. + * Adding this flag subsumes the serializable() flag below. Requirements: + * - A default constructor must be publicly accessible + * - Must not be an abstract base class + * - The class must have an actual boost.serialization serialize() function. + * - Add "void serializable()" to a class if you only want the class to be serialized as a + * part of a container (such as noisemodel). This version does not require a publicly + * accessible default constructor. + */ + +/** + * Status: + * - TODO: default values for arguments + * - WORKAROUND: make multiple versions of the same function for different configurations of default arguments + * - TODO: Handle gtsam::Rot3M conversions to quaternions + * - TODO: Parse return of const ref arguments + * - TODO: Parse std::string variants and convert directly to special string + * - TODO: Add enum support + * - TODO: Add generalized serialization support via boost.serialization with hooks to matlab save/load + */ + +namespace std { + #include + template + class vector + { + //Do we need these? + //Capacity + /*size_t size() const; + size_t max_size() const; + //void resize(size_t sz); + size_t capacity() const; + bool empty() const; + void reserve(size_t n); + + //Element access + T* at(size_t n); + T* front(); + T* back(); + + //Modifiers + void assign(size_t n, const T& u); + void push_back(const T& x); + void pop_back();*/ + }; + //typedef std::vector + + #include + template + class list + { + + + }; + +} + +namespace gtsam { + +//************************************************************************* +// base +//************************************************************************* + +/** gtsam namespace functions */ +bool linear_independent(Matrix A, Matrix B, double tol); + +virtual class Value { + // No constructors because this is an abstract class + + // Testable + void print(string s) const; + + // Manifold + size_t dim() const; +}; + +#include +class LieScalar { + // Standard constructors + LieScalar(); + LieScalar(double d); + + // Standard interface + double value() const; + + // Testable + void print(string s) const; + bool equals(const gtsam::LieScalar& expected, double tol) const; + + // Group + static gtsam::LieScalar identity(); + gtsam::LieScalar inverse() const; + gtsam::LieScalar compose(const gtsam::LieScalar& p) const; + gtsam::LieScalar between(const gtsam::LieScalar& l2) const; + + // Manifold + size_t dim() const; + gtsam::LieScalar retract(Vector v) const; + Vector localCoordinates(const gtsam::LieScalar& t2) const; + + // Lie group + static gtsam::LieScalar Expmap(Vector v); + static Vector Logmap(const gtsam::LieScalar& p); +}; + +#include +class LieVector { + // Standard constructors + LieVector(); + LieVector(Vector v); + + // Standard interface + Vector vector() const; + + // Testable + void print(string s) const; + bool equals(const gtsam::LieVector& expected, double tol) const; + + // Group + static gtsam::LieVector identity(); + gtsam::LieVector inverse() const; + gtsam::LieVector compose(const gtsam::LieVector& p) const; + gtsam::LieVector between(const gtsam::LieVector& l2) const; + + // Manifold + size_t dim() const; + gtsam::LieVector retract(Vector v) const; + Vector localCoordinates(const gtsam::LieVector& t2) const; + + // Lie group + static gtsam::LieVector Expmap(Vector v); + static Vector Logmap(const gtsam::LieVector& p); + + // enabling serialization functionality + void serialize() const; +}; + +#include +class LieMatrix { + // Standard constructors + LieMatrix(); + LieMatrix(Matrix v); + + // Standard interface + Matrix matrix() const; + + // Testable + void print(string s) const; + bool equals(const gtsam::LieMatrix& expected, double tol) const; + + // Group + static gtsam::LieMatrix identity(); + gtsam::LieMatrix inverse() const; + gtsam::LieMatrix compose(const gtsam::LieMatrix& p) const; + gtsam::LieMatrix between(const gtsam::LieMatrix& l2) const; + + // Manifold + size_t dim() const; + gtsam::LieMatrix retract(Vector v) const; + Vector localCoordinates(const gtsam::LieMatrix & t2) const; + + // Lie group + static gtsam::LieMatrix Expmap(Vector v); + static Vector Logmap(const gtsam::LieMatrix& p); + + // enabling serialization functionality + void serialize() const; +}; + +//************************************************************************* +// geometry +//************************************************************************* + +class Point2 { + // Standard Constructors + Point2(); + Point2(double x, double y); + Point2(Vector v); + + // Testable + void print(string s) const; + bool equals(const gtsam::Point2& pose, double tol) const; + + // Group + static gtsam::Point2 identity(); + gtsam::Point2 inverse() const; + gtsam::Point2 compose(const gtsam::Point2& p2) const; + gtsam::Point2 between(const gtsam::Point2& p2) const; + + // Manifold + gtsam::Point2 retract(Vector v) const; + Vector localCoordinates(const gtsam::Point2& p) const; + + // Lie Group + static gtsam::Point2 Expmap(Vector v); + static Vector Logmap(const gtsam::Point2& p); + + // Standard Interface + double x() const; + double y() const; + Vector vector() const; + double dist(const gtsam::Point2& p2) const; + double norm() const; + + // enabling serialization functionality + void serialize() const; +}; + +// std::vector +class Point2Vector +{ + // Constructors + Point2Vector(); + Point2Vector(const gtsam::Point2Vector& v); + + //Capacity + size_t size() const; + size_t max_size() const; + void resize(size_t sz); + size_t capacity() const; + bool empty() const; + void reserve(size_t n); + + //Element access + gtsam::Point2 at(size_t n) const; + gtsam::Point2 front() const; + gtsam::Point2 back() const; + + //Modifiers + void assign(size_t n, const gtsam::Point2& u); + void push_back(const gtsam::Point2& x); + void pop_back(); +}; + +class StereoPoint2 { + // Standard Constructors + StereoPoint2(); + StereoPoint2(double uL, double uR, double v); + + // Testable + void print(string s) const; + bool equals(const gtsam::StereoPoint2& point, double tol) const; + + // Group + static gtsam::StereoPoint2 identity(); + gtsam::StereoPoint2 inverse() const; + gtsam::StereoPoint2 compose(const gtsam::StereoPoint2& p2) const; + gtsam::StereoPoint2 between(const gtsam::StereoPoint2& p2) const; + + // Manifold + gtsam::StereoPoint2 retract(Vector v) const; + Vector localCoordinates(const gtsam::StereoPoint2& p) const; + + // Lie Group + static gtsam::StereoPoint2 Expmap(Vector v); + static Vector Logmap(const gtsam::StereoPoint2& p); + + // Standard Interface + Vector vector() const; + double uL() const; + double uR() const; + double v() const; + + // enabling serialization functionality + void serialize() const; +}; + +class Point3 { + // Standard Constructors + Point3(); + Point3(double x, double y, double z); + Point3(Vector v); + + // Testable + void print(string s) const; + bool equals(const gtsam::Point3& p, double tol) const; + + // Group + static gtsam::Point3 identity(); + gtsam::Point3 inverse() const; + gtsam::Point3 compose(const gtsam::Point3& p2) const; + gtsam::Point3 between(const gtsam::Point3& p2) const; + + // Manifold + gtsam::Point3 retract(Vector v) const; + Vector localCoordinates(const gtsam::Point3& p) const; + + // Lie Group + static gtsam::Point3 Expmap(Vector v); + static Vector Logmap(const gtsam::Point3& p); + + // Standard Interface + Vector vector() const; + double x() const; + double y() const; + double z() const; + + // enabling serialization functionality + void serialize() const; +}; + +class Rot2 { + // Standard Constructors and Named Constructors + Rot2(); + Rot2(double theta); + static gtsam::Rot2 fromAngle(double theta); + static gtsam::Rot2 fromDegrees(double theta); + static gtsam::Rot2 fromCosSin(double c, double s); + + // Testable + void print(string s) const; + bool equals(const gtsam::Rot2& rot, double tol) const; + + // Group + static gtsam::Rot2 identity(); + gtsam::Rot2 inverse(); + gtsam::Rot2 compose(const gtsam::Rot2& p2) const; + gtsam::Rot2 between(const gtsam::Rot2& p2) const; + + // Manifold + gtsam::Rot2 retract(Vector v) const; + Vector localCoordinates(const gtsam::Rot2& p) const; + + // Lie Group + static gtsam::Rot2 Expmap(Vector v); + static Vector Logmap(const gtsam::Rot2& p); + + // Group Action on Point2 + gtsam::Point2 rotate(const gtsam::Point2& point) const; + gtsam::Point2 unrotate(const gtsam::Point2& point) const; + + // Standard Interface + static gtsam::Rot2 relativeBearing(const gtsam::Point2& d); // Ignoring derivative + static gtsam::Rot2 atan2(double y, double x); + double theta() const; + double degrees() const; + double c() const; + double s() const; + Matrix matrix() const; + + // enabling serialization functionality + void serialize() const; +}; + +class Rot3 { + // Standard Constructors and Named Constructors + Rot3(); + Rot3(Matrix R); + static gtsam::Rot3 Rx(double t); + static gtsam::Rot3 Ry(double t); + static gtsam::Rot3 Rz(double t); + static gtsam::Rot3 RzRyRx(double x, double y, double z); + static gtsam::Rot3 RzRyRx(Vector xyz); + static gtsam::Rot3 yaw(double t); // positive yaw is to right (as in aircraft heading) + static gtsam::Rot3 pitch(double t); // positive pitch is up (increasing aircraft altitude) + static gtsam::Rot3 roll(double t); // positive roll is to right (increasing yaw in aircraft) + static gtsam::Rot3 ypr(double y, double p, double r); + static gtsam::Rot3 quaternion(double w, double x, double y, double z); + static gtsam::Rot3 Rodrigues(Vector v); + + // Testable + void print(string s) const; + bool equals(const gtsam::Rot3& rot, double tol) const; + + // Group + static gtsam::Rot3 identity(); + gtsam::Rot3 inverse() const; + gtsam::Rot3 compose(const gtsam::Rot3& p2) const; + gtsam::Rot3 between(const gtsam::Rot3& p2) const; + + // Manifold + //gtsam::Rot3 retractCayley(Vector v) const; // FIXME, does not exist in both Matrix and Quaternion options + gtsam::Rot3 retract(Vector v) const; + Vector localCoordinates(const gtsam::Rot3& p) const; + + // Group Action on Point3 + gtsam::Point3 rotate(const gtsam::Point3& p) const; + gtsam::Point3 unrotate(const gtsam::Point3& p) const; + + // Standard Interface + static gtsam::Rot3 Expmap(Vector v); + static Vector Logmap(const gtsam::Rot3& p); + Matrix matrix() const; + Matrix transpose() const; + gtsam::Point3 column(size_t index) const; + Vector xyz() const; + Vector ypr() const; + Vector rpy() const; + double roll() const; + double pitch() const; + double yaw() const; +// Vector toQuaternion() const; // FIXME: Can't cast to Vector properly + Vector quaternion() const; + + // enabling serialization functionality + void serialize() const; +}; + +class Pose2 { + // Standard Constructor + Pose2(); + Pose2(const gtsam::Pose2& pose); + Pose2(double x, double y, double theta); + Pose2(double theta, const gtsam::Point2& t); + Pose2(const gtsam::Rot2& r, const gtsam::Point2& t); + Pose2(Vector v); + + // Testable + void print(string s) const; + bool equals(const gtsam::Pose2& pose, double tol) const; + + // Group + static gtsam::Pose2 identity(); + gtsam::Pose2 inverse() const; + gtsam::Pose2 compose(const gtsam::Pose2& p2) const; + gtsam::Pose2 between(const gtsam::Pose2& p2) const; + + // Manifold + gtsam::Pose2 retract(Vector v) const; + Vector localCoordinates(const gtsam::Pose2& p) const; + + // Lie Group + static gtsam::Pose2 Expmap(Vector v); + static Vector Logmap(const gtsam::Pose2& p); + Matrix AdjointMap() const; + Vector Adjoint(const Vector& xi) const; + static Matrix wedge(double vx, double vy, double w); + + // Group Actions on Point2 + gtsam::Point2 transform_from(const gtsam::Point2& p) const; + gtsam::Point2 transform_to(const gtsam::Point2& p) const; + + // Standard Interface + double x() const; + double y() const; + double theta() const; + gtsam::Rot2 bearing(const gtsam::Point2& point) const; + double range(const gtsam::Point2& point) const; + gtsam::Point2 translation() const; + gtsam::Rot2 rotation() const; + Matrix matrix() const; + + // enabling serialization functionality + void serialize() const; +}; + +class Pose3 { + // Standard Constructors + Pose3(); + Pose3(const gtsam::Pose3& pose); + Pose3(const gtsam::Rot3& r, const gtsam::Point3& t); + Pose3(const gtsam::Pose2& pose2); // FIXME: shadows Pose3(Pose3 pose) + Pose3(Matrix t); + + // Testable + void print(string s) const; + bool equals(const gtsam::Pose3& pose, double tol) const; + + // Group + static gtsam::Pose3 identity(); + gtsam::Pose3 inverse() const; + gtsam::Pose3 compose(const gtsam::Pose3& p2) const; + gtsam::Pose3 between(const gtsam::Pose3& p2) const; + + // Manifold + gtsam::Pose3 retract(Vector v) const; + Vector localCoordinates(const gtsam::Pose3& T2) const; + + // Lie Group + static gtsam::Pose3 Expmap(Vector v); + static Vector Logmap(const gtsam::Pose3& p); + Matrix AdjointMap() const; + Vector Adjoint(Vector xi) const; + static Matrix wedge(double wx, double wy, double wz, double vx, double vy, double vz); + + // Group Action on Point3 + gtsam::Point3 transform_from(const gtsam::Point3& p) const; + gtsam::Point3 transform_to(const gtsam::Point3& p) const; + + // Standard Interface + gtsam::Rot3 rotation() const; + gtsam::Point3 translation() const; + double x() const; + double y() const; + double z() const; + Matrix matrix() const; + gtsam::Pose3 transform_to(const gtsam::Pose3& pose) const; // FIXME: shadows other transform_to() + double range(const gtsam::Point3& point); + double range(const gtsam::Pose3& pose); + + // enabling serialization functionality + void serialize() const; +}; + +// std::vector +class Pose3Vector +{ + Pose3Vector(); + size_t size() const; + bool empty() const; + gtsam::Pose3 at(size_t n) const; + void push_back(const gtsam::Pose3& x); +}; + +#include +class Unit3 { + // Standard Constructors + Unit3(); + Unit3(const gtsam::Point3& pose); + + // Testable + void print(string s) const; + bool equals(const gtsam::Unit3& pose, double tol) const; + + // Other functionality + Matrix basis() const; + Matrix skew() const; + + // Manifold + static size_t Dim(); + size_t dim() const; + gtsam::Unit3 retract(Vector v) const; + Vector localCoordinates(const gtsam::Unit3& s) const; +}; + +#include +class EssentialMatrix { + // Standard Constructors + EssentialMatrix(const gtsam::Rot3& aRb, const gtsam::Unit3& aTb); + + // Testable + void print(string s) const; + bool equals(const gtsam::EssentialMatrix& pose, double tol) const; + + // Manifold + static size_t Dim(); + size_t dim() const; + gtsam::EssentialMatrix retract(Vector v) const; + Vector localCoordinates(const gtsam::EssentialMatrix& s) const; + + // Other methods: + gtsam::Rot3 rotation() const; + gtsam::Unit3 direction() const; + Matrix matrix() const; + double error(Vector vA, Vector vB); +}; + +class Cal3_S2 { + // Standard Constructors + Cal3_S2(); + Cal3_S2(double fx, double fy, double s, double u0, double v0); + Cal3_S2(Vector v); + Cal3_S2(double fov, int w, int h); + + // Testable + void print(string s) const; + bool equals(const gtsam::Cal3_S2& rhs, double tol) const; + + // Manifold + static size_t Dim(); + size_t dim() const; + gtsam::Cal3_S2 retract(Vector v) const; + Vector localCoordinates(const gtsam::Cal3_S2& c) const; + + // Action on Point2 + gtsam::Point2 calibrate(const gtsam::Point2& p) const; + gtsam::Point2 uncalibrate(const gtsam::Point2& p) const; + + // Standard Interface + double fx() const; + double fy() const; + double skew() const; + double px() const; + double py() const; + gtsam::Point2 principalPoint() const; + Vector vector() const; + Matrix matrix() const; + Matrix matrix_inverse() const; + + // enabling serialization functionality + void serialize() const; +}; + +#include +virtual class Cal3DS2_Base { + // Standard Constructors + Cal3DS2_Base(); + + // Testable + void print(string s) const; + + // Standard Interface + double fx() const; + double fy() const; + double skew() const; + double px() const; + double py() const; + double k1() const; + double k2() const; + + // Action on Point2 + gtsam::Point2 uncalibrate(const gtsam::Point2& p) const; + gtsam::Point2 calibrate(const gtsam::Point2& p, double tol) const; + gtsam::Point2 calibrate(const gtsam::Point2& p) const; + + // enabling serialization functionality + void serialize() const; +}; + +#include +virtual class Cal3DS2 : gtsam::Cal3DS2_Base { + // Standard Constructors + Cal3DS2(); + Cal3DS2(double fx, double fy, double s, double u0, double v0, double k1, double k2); + Cal3DS2(double fx, double fy, double s, double u0, double v0, double k1, double k2, double p1, double p2); + Cal3DS2(Vector v); + + // Testable + bool equals(const gtsam::Cal3DS2& rhs, double tol) const; + + // Manifold + size_t dim() const; + static size_t Dim(); + gtsam::Cal3DS2 retract(Vector v) const; + Vector localCoordinates(const gtsam::Cal3DS2& c) const; + + // enabling serialization functionality + void serialize() const; +}; + +#include +virtual class Cal3Unified : gtsam::Cal3DS2_Base { + // Standard Constructors + Cal3Unified(); + Cal3Unified(double fx, double fy, double s, double u0, double v0, double k1, double k2); + Cal3Unified(double fx, double fy, double s, double u0, double v0, double k1, double k2, double p1, double p2, double xi); + Cal3Unified(Vector v); + + // Testable + bool equals(const gtsam::Cal3Unified& rhs, double tol) const; + + // Standard Interface + double xi() const; + gtsam::Point2 spaceToNPlane(const gtsam::Point2& p) const; + gtsam::Point2 nPlaneToSpace(const gtsam::Point2& p) const; + + // Manifold + size_t dim() const; + static size_t Dim(); + gtsam::Cal3Unified retract(Vector v) const; + Vector localCoordinates(const gtsam::Cal3Unified& c) const; + + // enabling serialization functionality + void serialize() const; +}; + +#include +class Cal3_S2Stereo { + // Standard Constructors + Cal3_S2Stereo(); + Cal3_S2Stereo(double fx, double fy, double s, double u0, double v0, double b); + Cal3_S2Stereo(Vector v); + + // Testable + void print(string s) const; + bool equals(const gtsam::Cal3_S2Stereo& K, double tol) const; + + // Standard Interface + double fx() const; + double fy() const; + double skew() const; + double px() const; + double py() const; + gtsam::Point2 principalPoint() const; + double baseline() const; +}; + +#include +class Cal3Bundler { + // Standard Constructors + Cal3Bundler(); + Cal3Bundler(double fx, double k1, double k2, double u0, double v0); + + // Testable + void print(string s) const; + bool equals(const gtsam::Cal3Bundler& rhs, double tol) const; + + // Manifold + static size_t Dim(); + size_t dim() const; + gtsam::Cal3Bundler retract(Vector v) const; + Vector localCoordinates(const gtsam::Cal3Bundler& c) const; + + // Action on Point2 + gtsam::Point2 calibrate(const gtsam::Point2& p, double tol) const; + gtsam::Point2 calibrate(const gtsam::Point2& p) const; + gtsam::Point2 uncalibrate(const gtsam::Point2& p) const; + + // Standard Interface + double fx() const; + double fy() const; + double k1() const; + double k2() const; + double u0() const; + double v0() const; + Vector vector() const; + Vector k() const; + //Matrix K() const; //FIXME: Uppercase + + // enabling serialization functionality + void serialize() const; +}; + +class CalibratedCamera { + // Standard Constructors and Named Constructors + CalibratedCamera(); + CalibratedCamera(const gtsam::Pose3& pose); + CalibratedCamera(const Vector& v); + static gtsam::CalibratedCamera Level(const gtsam::Pose2& pose2, double height); + + // Testable + void print(string s) const; + bool equals(const gtsam::CalibratedCamera& camera, double tol) const; + + // Manifold + static size_t Dim(); + size_t dim() const; + gtsam::CalibratedCamera retract(const Vector& d) const; + Vector localCoordinates(const gtsam::CalibratedCamera& T2) const; + + // Action on Point3 + gtsam::Point2 project(const gtsam::Point3& point) const; + static gtsam::Point2 Project(const gtsam::Point3& cameraPoint); + + // Standard Interface + gtsam::Pose3 pose() const; + double range(const gtsam::Point3& p) const; // TODO: Other overloaded range methods + + // enabling serialization functionality + void serialize() const; +}; + +template +class PinholeCamera { + // Standard Constructors and Named Constructors + PinholeCamera(); + PinholeCamera(const gtsam::Pose3& pose); + PinholeCamera(const gtsam::Pose3& pose, const CALIBRATION& K); + static This Level(const CALIBRATION& K, const gtsam::Pose2& pose, double height); + static This Level(const gtsam::Pose2& pose, double height); + static This Lookat(const gtsam::Point3& eye, const gtsam::Point3& target, + const gtsam::Point3& upVector, const CALIBRATION& K); + + // Testable + void print(string s) const; + bool equals(const This& camera, double tol) const; + + // Standard Interface + gtsam::Pose3 pose() const; + CALIBRATION calibration() const; + + // Manifold + This retract(const Vector& d) const; + Vector localCoordinates(const This& T2) const; + size_t dim() const; + static size_t Dim(); + + // Transformations and measurement functions + static gtsam::Point2 Project(const gtsam::Point3& cameraPoint); + pair projectSafe(const gtsam::Point3& pw) const; + gtsam::Point2 project(const gtsam::Point3& point); + gtsam::Point3 backproject(const gtsam::Point2& p, double depth) const; + double range(const gtsam::Point3& point); + double range(const gtsam::Pose3& point); + + // enabling serialization functionality + void serialize() const; +}; + +virtual class SimpleCamera { + // Standard Constructors and Named Constructors + SimpleCamera(); + SimpleCamera(const gtsam::Pose3& pose); + SimpleCamera(const gtsam::Pose3& pose, const gtsam::Cal3_S2& K); + static gtsam::SimpleCamera Level(const gtsam::Cal3_S2& K, const gtsam::Pose2& pose, double height); + static gtsam::SimpleCamera Level(const gtsam::Pose2& pose, double height); + static gtsam::SimpleCamera Lookat(const gtsam::Point3& eye, const gtsam::Point3& target, + const gtsam::Point3& upVector, const gtsam::Cal3_S2& K); + + // Testable + void print(string s) const; + bool equals(const gtsam::SimpleCamera& camera, double tol) const; + + // Standard Interface + gtsam::Pose3 pose() const; + gtsam::Cal3_S2 calibration() const; + + // Manifold + gtsam::SimpleCamera retract(const Vector& d) const; + Vector localCoordinates(const gtsam::SimpleCamera& T2) const; + size_t dim() const; + static size_t Dim(); + + // Transformations and measurement functions + static gtsam::Point2 Project(const gtsam::Point3& cameraPoint); + pair projectSafe(const gtsam::Point3& pw) const; + gtsam::Point2 project(const gtsam::Point3& point); + gtsam::Point3 backproject(const gtsam::Point2& p, double depth) const; + double range(const gtsam::Point3& point); + double range(const gtsam::Pose3& point); + + // enabling serialization functionality + void serialize() const; + +}; + +// Some typedefs for common camera types +// PinholeCameraCal3_S2 is the same as SimpleCamera above +typedef gtsam::PinholeCamera PinholeCameraCal3_S2; +typedef gtsam::PinholeCamera PinholeCameraCal3DS2; +typedef gtsam::PinholeCamera PinholeCameraCal3Unified; +typedef gtsam::PinholeCamera PinholeCameraCal3Bundler; + +class StereoCamera { + // Standard Constructors and Named Constructors + StereoCamera(); + StereoCamera(const gtsam::Pose3& pose, const gtsam::Cal3_S2Stereo* K); + + // Testable + void print(string s) const; + bool equals(const gtsam::StereoCamera& camera, double tol) const; + + // Standard Interface + gtsam::Pose3 pose() const; + double baseline() const; + gtsam::Cal3_S2Stereo calibration() const; + + // Manifold + gtsam::StereoCamera retract(const Vector& d) const; + Vector localCoordinates(const gtsam::StereoCamera& T2) const; + size_t dim() const; + static size_t Dim(); + + // Transformations and measurement functions + gtsam::StereoPoint2 project(const gtsam::Point3& point); + gtsam::Point3 backproject(const gtsam::StereoPoint2& p) const; + + // enabling serialization functionality + void serialize() const; +}; + +#include + +// Templates appear not yet supported for free functions +gtsam::Point3 triangulatePoint3(const gtsam::Pose3Vector& poses, + gtsam::Cal3_S2* sharedCal, const gtsam::Point2Vector& measurements, + double rank_tol, bool optimize); +gtsam::Point3 triangulatePoint3(const gtsam::Pose3Vector& poses, + gtsam::Cal3Bundler* sharedCal, const gtsam::Point2Vector& measurements, + double rank_tol, bool optimize); + +//************************************************************************* +// Symbolic +//************************************************************************* + +#include +virtual class SymbolicFactor { + // Standard Constructors and Named Constructors + SymbolicFactor(const gtsam::SymbolicFactor& f); + SymbolicFactor(); + SymbolicFactor(size_t j); + SymbolicFactor(size_t j1, size_t j2); + SymbolicFactor(size_t j1, size_t j2, size_t j3); + SymbolicFactor(size_t j1, size_t j2, size_t j3, size_t j4); + SymbolicFactor(size_t j1, size_t j2, size_t j3, size_t j4, size_t j5); + SymbolicFactor(size_t j1, size_t j2, size_t j3, size_t j4, size_t j5, size_t j6); + static gtsam::SymbolicFactor FromKeys(const gtsam::KeyVector& js); + + // From Factor + size_t size() const; + void print(string s) const; + bool equals(const gtsam::SymbolicFactor& other, double tol) const; + gtsam::KeyVector keys(); +}; + +#include +virtual class SymbolicFactorGraph { + SymbolicFactorGraph(); + SymbolicFactorGraph(const gtsam::SymbolicBayesNet& bayesNet); + SymbolicFactorGraph(const gtsam::SymbolicBayesTree& bayesTree); + + // From FactorGraph + void push_back(gtsam::SymbolicFactor* factor); + void print(string s) const; + bool equals(const gtsam::SymbolicFactorGraph& rhs, double tol) const; + size_t size() const; + bool exists(size_t idx) const; + + // Standard interface + gtsam::KeySet keys() const; + void push_back(gtsam::SymbolicFactor* factor); + void push_back(const gtsam::SymbolicFactorGraph& graph); + void push_back(const gtsam::SymbolicBayesNet& bayesNet); + void push_back(const gtsam::SymbolicBayesTree& bayesTree); + + //Advanced Interface + void push_factor(size_t key); + void push_factor(size_t key1, size_t key2); + void push_factor(size_t key1, size_t key2, size_t key3); + void push_factor(size_t key1, size_t key2, size_t key3, size_t key4); + + gtsam::SymbolicBayesNet* eliminateSequential(); + gtsam::SymbolicBayesNet* eliminateSequential(const gtsam::Ordering& ordering); + gtsam::SymbolicBayesTree* eliminateMultifrontal(); + gtsam::SymbolicBayesTree* eliminateMultifrontal(const gtsam::Ordering& ordering); + pair eliminatePartialSequential( + const gtsam::Ordering& ordering); + pair eliminatePartialSequential( + const gtsam::KeyVector& keys); + pair eliminatePartialMultifrontal( + const gtsam::Ordering& ordering); + pair eliminatePartialMultifrontal( + const gtsam::KeyVector& keys); + gtsam::SymbolicBayesNet* marginalMultifrontalBayesNet(const gtsam::Ordering& variables); + gtsam::SymbolicBayesNet* marginalMultifrontalBayesNet(const gtsam::KeyVector& variables); + gtsam::SymbolicBayesNet* marginalMultifrontalBayesNet(const gtsam::Ordering& variables, + const gtsam::Ordering& marginalizedVariableOrdering); + gtsam::SymbolicBayesNet* marginalMultifrontalBayesNet(const gtsam::KeyVector& variables, + const gtsam::Ordering& marginalizedVariableOrdering); + gtsam::SymbolicFactorGraph* marginal(const gtsam::KeyVector& variables); +}; + +#include +virtual class SymbolicConditional : gtsam::SymbolicFactor { + // Standard Constructors and Named Constructors + SymbolicConditional(); + SymbolicConditional(const gtsam::SymbolicConditional& other); + SymbolicConditional(size_t key); + SymbolicConditional(size_t key, size_t parent); + SymbolicConditional(size_t key, size_t parent1, size_t parent2); + SymbolicConditional(size_t key, size_t parent1, size_t parent2, size_t parent3); + static gtsam::SymbolicConditional FromKeys(const gtsam::KeyVector& keys, size_t nrFrontals); + + // Testable + void print(string s) const; + bool equals(const gtsam::SymbolicConditional& other, double tol) const; + + // Standard interface + size_t nrFrontals() const; + size_t nrParents() const; +}; + +#include +class SymbolicBayesNet { + SymbolicBayesNet(); + SymbolicBayesNet(const gtsam::SymbolicBayesNet& other); + // Testable + void print(string s) const; + bool equals(const gtsam::SymbolicBayesNet& other, double tol) const; + + // Standard interface + size_t size() const; + void saveGraph(string s) const; + gtsam::SymbolicConditional* at(size_t idx) const; + gtsam::SymbolicConditional* front() const; + gtsam::SymbolicConditional* back() const; + void push_back(gtsam::SymbolicConditional* conditional); + void push_back(const gtsam::SymbolicBayesNet& bayesNet); +}; + +#include +class SymbolicBayesTree { + + //Constructors + SymbolicBayesTree(); + SymbolicBayesTree(const gtsam::SymbolicBayesTree& other); + + // Testable + void print(string s); + bool equals(const gtsam::SymbolicBayesTree& other, double tol) const; + + //Standard Interface + //size_t findParentClique(const gtsam::IndexVector& parents) const; + size_t size(); + void saveGraph(string s) const; + void clear(); + void deleteCachedShortcuts(); + size_t numCachedSeparatorMarginals() const; + + gtsam::SymbolicConditional* marginalFactor(size_t key) const; + gtsam::SymbolicFactorGraph* joint(size_t key1, size_t key2) const; + gtsam::SymbolicBayesNet* jointBayesNet(size_t key1, size_t key2) const; +}; + +// class SymbolicBayesTreeClique { +// BayesTreeClique(); +// BayesTreeClique(CONDITIONAL* conditional); +// // BayesTreeClique(const std::pair& result) : Base(result) {} +// +// bool equals(const This& other, double tol) const; +// void print(string s) const; +// void printTree() const; // Default indent of "" +// void printTree(string indent) const; +// size_t numCachedSeparatorMarginals() const; +// +// CONDITIONAL* conditional() const; +// bool isRoot() const; +// size_t treeSize() const; +// // const std::list& children() const { return children_; } +// // derived_ptr parent() const { return parent_.lock(); } +// +// // FIXME: need wrapped versions graphs, BayesNet +// // BayesNet shortcut(derived_ptr root, Eliminate function) const; +// // FactorGraph marginal(derived_ptr root, Eliminate function) const; +// // FactorGraph joint(derived_ptr C2, derived_ptr root, Eliminate function) const; +// +// void deleteCachedShortcuts(); +// }; + +#include +class VariableIndex { + // Standard Constructors and Named Constructors + VariableIndex(); + // TODO: Templetize constructor when wrap supports it + //template + //VariableIndex(const T& factorGraph, size_t nVariables); + //VariableIndex(const T& factorGraph); + VariableIndex(const gtsam::SymbolicFactorGraph& factorGraph); + VariableIndex(const gtsam::GaussianFactorGraph& factorGraph); + VariableIndex(const gtsam::NonlinearFactorGraph& factorGraph); + VariableIndex(const gtsam::VariableIndex& other); + + // Testable + bool equals(const gtsam::VariableIndex& other, double tol) const; + void print(string s) const; + + // Standard interface + size_t size() const; + size_t nFactors() const; + size_t nEntries() const; +}; + +//************************************************************************* +// linear +//************************************************************************* + +namespace noiseModel { +#include +virtual class Base { +}; + +virtual class Gaussian : gtsam::noiseModel::Base { + static gtsam::noiseModel::Gaussian* SqrtInformation(Matrix R); + static gtsam::noiseModel::Gaussian* Covariance(Matrix R); + Matrix R() const; + bool equals(gtsam::noiseModel::Base& expected, double tol); + void print(string s) const; + + // enabling serialization functionality + void serializable() const; +}; + +virtual class Diagonal : gtsam::noiseModel::Gaussian { + static gtsam::noiseModel::Diagonal* Sigmas(Vector sigmas); + static gtsam::noiseModel::Diagonal* Variances(Vector variances); + static gtsam::noiseModel::Diagonal* Precisions(Vector precisions); + Matrix R() const; + void print(string s) const; + + // enabling serialization functionality + void serializable() const; +}; + +virtual class Constrained : gtsam::noiseModel::Diagonal { + static gtsam::noiseModel::Constrained* MixedSigmas(const Vector& mu, const Vector& sigmas); + static gtsam::noiseModel::Constrained* MixedSigmas(double m, const Vector& sigmas); + static gtsam::noiseModel::Constrained* MixedVariances(const Vector& mu, const Vector& variances); + static gtsam::noiseModel::Constrained* MixedVariances(const Vector& variances); + static gtsam::noiseModel::Constrained* MixedPrecisions(const Vector& mu, const Vector& precisions); + static gtsam::noiseModel::Constrained* MixedPrecisions(const Vector& precisions); + + static gtsam::noiseModel::Constrained* All(size_t dim); + static gtsam::noiseModel::Constrained* All(size_t dim, double mu); + + gtsam::noiseModel::Constrained* unit() const; + + // enabling serialization functionality + void serializable() const; +}; + +virtual class Isotropic : gtsam::noiseModel::Diagonal { + static gtsam::noiseModel::Isotropic* Sigma(size_t dim, double sigma); + static gtsam::noiseModel::Isotropic* Variance(size_t dim, double varianace); + static gtsam::noiseModel::Isotropic* Precision(size_t dim, double precision); + void print(string s) const; + + // enabling serialization functionality + void serializable() const; +}; + +virtual class Unit : gtsam::noiseModel::Isotropic { + static gtsam::noiseModel::Unit* Create(size_t dim); + void print(string s) const; + + // enabling serialization functionality + void serializable() const; +}; + +namespace mEstimator { +virtual class Base { +}; + +virtual class Null: gtsam::noiseModel::mEstimator::Base { + Null(); + void print(string s) const; + static gtsam::noiseModel::mEstimator::Null* Create(); + + // enabling serialization functionality + void serializable() const; +}; + +virtual class Fair: gtsam::noiseModel::mEstimator::Base { + Fair(double c); + void print(string s) const; + static gtsam::noiseModel::mEstimator::Fair* Create(double c); + + // enabling serialization functionality + void serializable() const; +}; + +virtual class Huber: gtsam::noiseModel::mEstimator::Base { + Huber(double k); + void print(string s) const; + static gtsam::noiseModel::mEstimator::Huber* Create(double k); + + // enabling serialization functionality + void serializable() const; +}; + +virtual class Tukey: gtsam::noiseModel::mEstimator::Base { + Tukey(double k); + void print(string s) const; + static gtsam::noiseModel::mEstimator::Tukey* Create(double k); + + // enabling serialization functionality + void serializable() const; +}; + +}///\namespace mEstimator + +virtual class Robust : gtsam::noiseModel::Base { + Robust(const gtsam::noiseModel::mEstimator::Base* robust, const gtsam::noiseModel::Base* noise); + static gtsam::noiseModel::Robust* Create(const gtsam::noiseModel::mEstimator::Base* robust, const gtsam::noiseModel::Base* noise); + void print(string s) const; + + // enabling serialization functionality + void serializable() const; +}; + +}///\namespace noiseModel + +#include +class Sampler { + //Constructors + Sampler(gtsam::noiseModel::Diagonal* model, int seed); + Sampler(Vector sigmas, int seed); + Sampler(int seed); + + //Standard Interface + size_t dim() const; + Vector sigmas() const; + gtsam::noiseModel::Diagonal* model() const; + Vector sample(); + Vector sampleNewModel(gtsam::noiseModel::Diagonal* model); +}; + +#include +class VectorValues { + //Constructors + VectorValues(); + VectorValues(const gtsam::VectorValues& other); + + //Named Constructors + static gtsam::VectorValues Zero(const gtsam::VectorValues& model); + + //Standard Interface + size_t size() const; + size_t dim(size_t j) const; + bool exists(size_t j) const; + void print(string s) const; + bool equals(const gtsam::VectorValues& expected, double tol) const; + void insert(size_t j, Vector value); + Vector vector() const; + Vector at(size_t j) const; + void update(const gtsam::VectorValues& values); + + //Advanced Interface + void setZero(); + + gtsam::VectorValues add(const gtsam::VectorValues& c) const; + void addInPlace(const gtsam::VectorValues& c); + gtsam::VectorValues subtract(const gtsam::VectorValues& c) const; + gtsam::VectorValues scale(double a) const; + void scaleInPlace(double a); + + bool hasSameStructure(const gtsam::VectorValues& other) const; + double dot(const gtsam::VectorValues& V) const; + double norm() const; + double squaredNorm() const; + + // enabling serialization functionality + void serialize() const; +}; + +#include +virtual class GaussianFactor { + gtsam::KeyVector keys() const; + void print(string s) const; + bool equals(const gtsam::GaussianFactor& lf, double tol) const; + double error(const gtsam::VectorValues& c) const; + gtsam::GaussianFactor* clone() const; + gtsam::GaussianFactor* negate() const; + Matrix augmentedInformation() const; + Matrix information() const; + Matrix augmentedJacobian() const; + pair jacobian() const; + size_t size() const; + bool empty() const; +}; + +#include +virtual class JacobianFactor : gtsam::GaussianFactor { + //Constructors + JacobianFactor(); + JacobianFactor(const gtsam::GaussianFactor& factor); + JacobianFactor(Vector b_in); + JacobianFactor(size_t i1, Matrix A1, Vector b, + const gtsam::noiseModel::Diagonal* model); + JacobianFactor(size_t i1, Matrix A1, size_t i2, Matrix A2, Vector b, + const gtsam::noiseModel::Diagonal* model); + JacobianFactor(size_t i1, Matrix A1, size_t i2, Matrix A2, size_t i3, Matrix A3, + Vector b, const gtsam::noiseModel::Diagonal* model); + JacobianFactor(const gtsam::GaussianFactorGraph& graph); + + //Testable + void print(string s) const; + void printKeys(string s) const; + bool equals(const gtsam::GaussianFactor& lf, double tol) const; + size_t size() const; + Vector unweighted_error(const gtsam::VectorValues& c) const; + Vector error_vector(const gtsam::VectorValues& c) const; + double error(const gtsam::VectorValues& c) const; + + //Standard Interface + Matrix getA() const; + Vector getb() const; + size_t rows() const; + size_t cols() const; + bool isConstrained() const; + pair jacobianUnweighted() const; + Matrix augmentedJacobianUnweighted() const; + + void transposeMultiplyAdd(double alpha, const Vector& e, gtsam::VectorValues& x) const; + gtsam::JacobianFactor whiten() const; + + pair eliminate(const gtsam::Ordering& keys) const; + + void setModel(bool anyConstrained, const Vector& sigmas); + + gtsam::noiseModel::Diagonal* get_model() const; + + // enabling serialization functionality + void serialize() const; +}; + +#include +virtual class HessianFactor : gtsam::GaussianFactor { + //Constructors + HessianFactor(); + HessianFactor(const gtsam::GaussianFactor& factor); + HessianFactor(size_t j, Matrix G, Vector g, double f); + HessianFactor(size_t j, Vector mu, Matrix Sigma); + HessianFactor(size_t j1, size_t j2, Matrix G11, Matrix G12, Vector g1, Matrix G22, + Vector g2, double f); + HessianFactor(size_t j1, size_t j2, size_t j3, Matrix G11, Matrix G12, Matrix G13, + Vector g1, Matrix G22, Matrix G23, Vector g2, Matrix G33, Vector g3, + double f); + HessianFactor(const gtsam::GaussianFactorGraph& factors); + + //Testable + size_t size() const; + void print(string s) const; + void printKeys(string s) const; + bool equals(const gtsam::GaussianFactor& lf, double tol) const; + double error(const gtsam::VectorValues& c) const; + + //Standard Interface + size_t rows() const; + Matrix info() const; + double constantTerm() const; + Vector linearTerm() const; + + // enabling serialization functionality + void serialize() const; +}; + +#include +class GaussianFactorGraph { + GaussianFactorGraph(); + GaussianFactorGraph(const gtsam::GaussianBayesNet& bayesNet); + GaussianFactorGraph(const gtsam::GaussianBayesTree& bayesTree); + + // From FactorGraph + void print(string s) const; + bool equals(const gtsam::GaussianFactorGraph& lfgraph, double tol) const; + size_t size() const; + gtsam::GaussianFactor* at(size_t idx) const; + gtsam::KeySet keys() const; + bool exists(size_t idx) const; + + // Building the graph + void push_back(const gtsam::GaussianFactor* factor); + void push_back(const gtsam::GaussianConditional* factor); + void push_back(const gtsam::GaussianFactorGraph& graph); + void push_back(const gtsam::GaussianBayesNet& bayesNet); + void push_back(const gtsam::GaussianBayesTree& bayesTree); + void add(const gtsam::GaussianFactor& factor); + void add(Vector b); + void add(size_t key1, Matrix A1, Vector b, const gtsam::noiseModel::Diagonal* model); + void add(size_t key1, Matrix A1, size_t key2, Matrix A2, Vector b, + const gtsam::noiseModel::Diagonal* model); + void add(size_t key1, Matrix A1, size_t key2, Matrix A2, size_t key3, Matrix A3, + Vector b, const gtsam::noiseModel::Diagonal* model); + + // error and probability + double error(const gtsam::VectorValues& c) const; + double probPrime(const gtsam::VectorValues& c) const; + + gtsam::GaussianFactorGraph clone() const; + gtsam::GaussianFactorGraph negate() const; + + // Optimizing and linear algebra + gtsam::VectorValues optimize() const; + gtsam::VectorValues optimize(const gtsam::Ordering& ordering) const; + gtsam::VectorValues optimizeGradientSearch() const; + gtsam::VectorValues gradient(const gtsam::VectorValues& x0) const; + gtsam::VectorValues gradientAtZero() const; + + // Elimination and marginals + gtsam::GaussianBayesNet* eliminateSequential(); + gtsam::GaussianBayesNet* eliminateSequential(const gtsam::Ordering& ordering); + gtsam::GaussianBayesTree* eliminateMultifrontal(); + gtsam::GaussianBayesTree* eliminateMultifrontal(const gtsam::Ordering& ordering); + pair eliminatePartialSequential( + const gtsam::Ordering& ordering); + pair eliminatePartialSequential( + const gtsam::KeyVector& keys); + pair eliminatePartialMultifrontal( + const gtsam::Ordering& ordering); + pair eliminatePartialMultifrontal( + const gtsam::KeyVector& keys); + gtsam::GaussianBayesNet* marginalMultifrontalBayesNet(const gtsam::Ordering& variables); + gtsam::GaussianBayesNet* marginalMultifrontalBayesNet(const gtsam::KeyVector& variables); + gtsam::GaussianBayesNet* marginalMultifrontalBayesNet(const gtsam::Ordering& variables, + const gtsam::Ordering& marginalizedVariableOrdering); + gtsam::GaussianBayesNet* marginalMultifrontalBayesNet(const gtsam::KeyVector& variables, + const gtsam::Ordering& marginalizedVariableOrdering); + gtsam::GaussianFactorGraph* marginal(const gtsam::KeyVector& variables); + + // Conversion to matrices + Matrix sparseJacobian_() const; + Matrix augmentedJacobian() const; + Matrix augmentedJacobian(const gtsam::Ordering& ordering) const; + pair jacobian() const; + pair jacobian(const gtsam::Ordering& ordering) const; + Matrix augmentedHessian() const; + Matrix augmentedHessian(const gtsam::Ordering& ordering) const; + pair hessian() const; + pair hessian(const gtsam::Ordering& ordering) const; + + // enabling serialization functionality + void serialize() const; +}; + +#include +virtual class GaussianConditional : gtsam::GaussianFactor { + //Constructors + GaussianConditional(size_t key, Vector d, Matrix R, const gtsam::noiseModel::Diagonal* sigmas); + GaussianConditional(size_t key, Vector d, Matrix R, size_t name1, Matrix S, + const gtsam::noiseModel::Diagonal* sigmas); + GaussianConditional(size_t key, Vector d, Matrix R, size_t name1, Matrix S, + size_t name2, Matrix T, const gtsam::noiseModel::Diagonal* sigmas); + + //Constructors with no noise model + GaussianConditional(size_t key, Vector d, Matrix R); + GaussianConditional(size_t key, Vector d, Matrix R, size_t name1, Matrix S); + GaussianConditional(size_t key, Vector d, Matrix R, size_t name1, Matrix S, + size_t name2, Matrix T); + + //Standard Interface + void print(string s) const; + bool equals(const gtsam::GaussianConditional &cg, double tol) const; + + //Advanced Interface + gtsam::VectorValues solve(const gtsam::VectorValues& parents) const; + gtsam::VectorValues solveOtherRHS(const gtsam::VectorValues& parents, const gtsam::VectorValues& rhs) const; + void solveTransposeInPlace(gtsam::VectorValues& gy) const; + void scaleFrontalsBySigma(gtsam::VectorValues& gy) const; + + // enabling serialization functionality + void serialize() const; +}; + +#include +virtual class GaussianDensity : gtsam::GaussianConditional { + //Constructors + GaussianDensity(size_t key, Vector d, Matrix R, const gtsam::noiseModel::Diagonal* sigmas); + + //Standard Interface + void print(string s) const; + bool equals(const gtsam::GaussianDensity &cg, double tol) const; + Vector mean() const; + Matrix covariance() const; +}; + +#include +virtual class GaussianBayesNet { + //Constructors + GaussianBayesNet(); + GaussianBayesNet(const gtsam::GaussianConditional* conditional); + + // Testable + void print(string s) const; + bool equals(const gtsam::GaussianBayesNet& other, double tol) const; + size_t size() const; + + // FactorGraph derived interface + size_t size() const; + gtsam::GaussianConditional* at(size_t idx) const; + gtsam::KeySet keys() const; + bool exists(size_t idx) const; + + gtsam::GaussianConditional* front() const; + gtsam::GaussianConditional* back() const; + void push_back(gtsam::GaussianConditional* conditional); + void push_back(const gtsam::GaussianBayesNet& bayesNet); + + gtsam::VectorValues optimize() const; + gtsam::VectorValues optimize(gtsam::VectorValues& solutionForMissing) const; + gtsam::VectorValues optimizeGradientSearch() const; + gtsam::VectorValues gradient(const gtsam::VectorValues& x0) const; + gtsam::VectorValues gradientAtZero() const; + double error(const gtsam::VectorValues& x) const; + double determinant() const; + double logDeterminant() const; + gtsam::VectorValues backSubstitute(const gtsam::VectorValues& gx) const; + gtsam::VectorValues backSubstituteTranspose(const gtsam::VectorValues& gx) const; +}; + +#include +virtual class GaussianBayesTree { + // Standard Constructors and Named Constructors + GaussianBayesTree(); + GaussianBayesTree(const gtsam::GaussianBayesTree& other); + bool equals(const gtsam::GaussianBayesTree& other, double tol) const; + void print(string s); + size_t size() const; + bool empty() const; + size_t numCachedSeparatorMarginals() const; + void saveGraph(string s) const; + + gtsam::VectorValues optimize() const; + gtsam::VectorValues optimizeGradientSearch() const; + gtsam::VectorValues gradient(const gtsam::VectorValues& x0) const; + gtsam::VectorValues gradientAtZero() const; + double error(const gtsam::VectorValues& x) const; + double determinant() const; + double logDeterminant() const; + Matrix marginalCovariance(size_t key) const; + gtsam::GaussianConditional* marginalFactor(size_t key) const; + gtsam::GaussianFactorGraph* joint(size_t key1, size_t key2) const; + gtsam::GaussianBayesNet* jointBayesNet(size_t key1, size_t key2) const; +}; + +class Errors { + //Constructors + Errors(); + Errors(const gtsam::VectorValues& V); + + //Testable + void print(string s); + bool equals(const gtsam::Errors& expected, double tol) const; +}; + +class GaussianISAM { + //Constructor + GaussianISAM(); + + //Standard Interface + void update(const gtsam::GaussianFactorGraph& newFactors); + void saveGraph(string s) const; + void clear(); +}; + +#include +virtual class IterativeOptimizationParameters { + string getVerbosity() const; + void setVerbosity(string s) ; + void print() const; +}; + +//virtual class IterativeSolver { +// IterativeSolver(); +// gtsam::VectorValues optimize (); +//}; + +#include +virtual class ConjugateGradientParameters : gtsam::IterativeOptimizationParameters { + ConjugateGradientParameters(); + int getMinIterations() const ; + int getMaxIterations() const ; + int getReset() const; + double getEpsilon_rel() const; + double getEpsilon_abs() const; + + void setMinIterations(int value); + void setMaxIterations(int value); + void setReset(int value); + void setEpsilon_rel(double value); + void setEpsilon_abs(double value); + void print(); +}; + +#include +virtual class SubgraphSolverParameters : gtsam::ConjugateGradientParameters { + SubgraphSolverParameters(); + void print() const; +}; + +virtual class SubgraphSolver { + SubgraphSolver(const gtsam::GaussianFactorGraph &A, const gtsam::SubgraphSolverParameters ¶meters, const gtsam::Ordering& ordering); + SubgraphSolver(const gtsam::GaussianFactorGraph &Ab1, const gtsam::GaussianFactorGraph &Ab2, const gtsam::SubgraphSolverParameters ¶meters, const gtsam::Ordering& ordering); + gtsam::VectorValues optimize() const; +}; + +#include +class KalmanFilter { + KalmanFilter(size_t n); + // gtsam::GaussianDensity* init(Vector x0, const gtsam::SharedDiagonal& P0); + gtsam::GaussianDensity* init(Vector x0, Matrix P0); + void print(string s) const; + static size_t step(gtsam::GaussianDensity* p); + gtsam::GaussianDensity* predict(gtsam::GaussianDensity* p, Matrix F, + Matrix B, Vector u, const gtsam::noiseModel::Diagonal* modelQ); + gtsam::GaussianDensity* predictQ(gtsam::GaussianDensity* p, Matrix F, + Matrix B, Vector u, Matrix Q); + gtsam::GaussianDensity* predict2(gtsam::GaussianDensity* p, Matrix A0, + Matrix A1, Vector b, const gtsam::noiseModel::Diagonal* model); + gtsam::GaussianDensity* update(gtsam::GaussianDensity* p, Matrix H, + Vector z, const gtsam::noiseModel::Diagonal* model); + gtsam::GaussianDensity* updateQ(gtsam::GaussianDensity* p, Matrix H, + Vector z, Matrix Q); +}; + +//************************************************************************* +// nonlinear +//************************************************************************* + +#include +size_t symbol(char chr, size_t index); +char symbolChr(size_t key); +size_t symbolIndex(size_t key); + +// Default keyformatter +void PrintKeyList (const gtsam::KeyList& keys); +void PrintKeyList (const gtsam::KeyList& keys, string s); +void PrintKeyVector(const gtsam::KeyVector& keys); +void PrintKeyVector(const gtsam::KeyVector& keys, string s); +void PrintKeySet (const gtsam::KeySet& keys); +void PrintKeySet (const gtsam::KeySet& keys, string s); + +#include +class LabeledSymbol { + LabeledSymbol(size_t full_key); + LabeledSymbol(const gtsam::LabeledSymbol& key); + LabeledSymbol(unsigned char valType, unsigned char label, size_t j); + + size_t key() const; + unsigned char label() const; + unsigned char chr() const; + size_t index() const; + + gtsam::LabeledSymbol upper() const; + gtsam::LabeledSymbol lower() const; + gtsam::LabeledSymbol newChr(unsigned char c) const; + gtsam::LabeledSymbol newLabel(unsigned char label) const; + + void print(string s) const; +}; + +size_t mrsymbol(unsigned char c, unsigned char label, size_t j); +unsigned char mrsymbolChr(size_t key); +unsigned char mrsymbolLabel(size_t key); +size_t mrsymbolIndex(size_t key); + +#include +class Ordering { + // Standard Constructors and Named Constructors + Ordering(); + Ordering(const gtsam::Ordering& other); + + // Testable + void print(string s) const; + bool equals(const gtsam::Ordering& ord, double tol) const; + + // Standard interface + size_t size() const; + size_t at(size_t key) const; + void push_back(size_t key); + + // enabling serialization functionality + void serialize() const; +}; + +class NonlinearFactorGraph { + NonlinearFactorGraph(); + NonlinearFactorGraph(const gtsam::NonlinearFactorGraph& graph); + + // FactorGraph + void print(string s) const; + bool equals(const gtsam::NonlinearFactorGraph& fg, double tol) const; + size_t size() const; + bool empty() const; + void remove(size_t i); + size_t nrFactors() const; + gtsam::NonlinearFactor* at(size_t idx) const; + void push_back(const gtsam::NonlinearFactorGraph& factors); + void push_back(gtsam::NonlinearFactor* factor); + void add(gtsam::NonlinearFactor* factor); + bool exists(size_t idx) const; + gtsam::KeySet keys() const; + + // NonlinearFactorGraph + double error(const gtsam::Values& values) const; + double probPrime(const gtsam::Values& values) const; + gtsam::Ordering orderingCOLAMD() const; + // Ordering* orderingCOLAMDConstrained(const gtsam::Values& c, const std::map& constraints) const; + gtsam::GaussianFactorGraph* linearize(const gtsam::Values& values) const; + gtsam::NonlinearFactorGraph clone() const; + + // enabling serialization functionality + void serialize() const; +}; + +virtual class NonlinearFactor { + // Factor base class + size_t size() const; + gtsam::KeyVector keys() const; + void print(string s) const; + void printKeys(string s) const; + // NonlinearFactor + void equals(const gtsam::NonlinearFactor& other, double tol) const; + double error(const gtsam::Values& c) const; + size_t dim() const; + bool active(const gtsam::Values& c) const; + gtsam::GaussianFactor* linearize(const gtsam::Values& c) const; + gtsam::NonlinearFactor* clone() const; + // gtsam::NonlinearFactor* rekey(const gtsam::KeyVector& newKeys) const; //FIXME: Conversion from KeyVector to std::vector does not happen +}; + +virtual class NoiseModelFactor: gtsam::NonlinearFactor { + void equals(const gtsam::NoiseModelFactor& other, double tol) const; + gtsam::noiseModel::Base* get_noiseModel() const; + Vector unwhitenedError(const gtsam::Values& x) const; + Vector whitenedError(const gtsam::Values& x) const; +}; + +#include +class Values { + Values(); + Values(const gtsam::Values& other); + + size_t size() const; + bool empty() const; + void clear(); + size_t dim() const; + + void print(string s) const; + bool equals(const gtsam::Values& other, double tol) const; + + void insert(const gtsam::Values& values); + void update(const gtsam::Values& values); + void erase(size_t j); + void swap(gtsam::Values& values); + + bool exists(size_t j) const; + gtsam::KeyVector keys() const; + + gtsam::VectorValues zeroVectors() const; + + gtsam::Values retract(const gtsam::VectorValues& delta) const; + gtsam::VectorValues localCoordinates(const gtsam::Values& cp) const; + + // enabling serialization functionality + void serialize() const; + + // New in 4.0, we have to specialize every insert/update/at to generate wrappers + // Instead of the old: + // void insert(size_t j, const gtsam::Value& value); + // void update(size_t j, const gtsam::Value& val); + // gtsam::Value at(size_t j) const; + + void insert(size_t j, const gtsam::Point2& t); + void insert(size_t j, const gtsam::Point3& t); + void insert(size_t j, const gtsam::Rot2& t); + void insert(size_t j, const gtsam::Pose2& t); + void insert(size_t j, const gtsam::Rot3& t); + void insert(size_t j, const gtsam::Pose3& t); + void insert(size_t j, const gtsam::Cal3_S2& t); + void insert(size_t j, const gtsam::Cal3DS2& t); + void insert(size_t j, const gtsam::Cal3Bundler& t); + void insert(size_t j, const gtsam::EssentialMatrix& t); + void insert(size_t j, const gtsam::SimpleCamera& t); + void insert(size_t j, const gtsam::imuBias::ConstantBias& t); + void insert(size_t j, Vector t); + void insert(size_t j, Matrix t); + + // Fixed size version + void insertFixed(size_t j, Vector t, size_t n); + + void update(size_t j, const gtsam::Point2& t); + void update(size_t j, const gtsam::Point3& t); + void update(size_t j, const gtsam::Rot2& t); + void update(size_t j, const gtsam::Pose2& t); + void update(size_t j, const gtsam::Rot3& t); + void update(size_t j, const gtsam::Pose3& t); + void update(size_t j, const gtsam::Cal3_S2& t); + void update(size_t j, const gtsam::Cal3DS2& t); + void update(size_t j, const gtsam::Cal3Bundler& t); + void update(size_t j, const gtsam::EssentialMatrix& t); + void update(size_t j, const gtsam::imuBias::ConstantBias& t); + void update(size_t j, Vector t); + void update(size_t j, Matrix t); + + template + T at(size_t j); + + /// Fixed size versions, for n in 1..9 + void insertFixed(size_t j, Vector t, size_t n); + + /// Fixed size versions, for n in 1..9 + Vector atFixed(size_t j, size_t n); + + /// version for double + void insertDouble(size_t j, double c); + double atDouble(size_t j) const; +}; + +// Actually a FastList +#include +class KeyList { + KeyList(); + KeyList(const gtsam::KeyList& other); + + // Note: no print function + + // common STL methods + size_t size() const; + bool empty() const; + void clear(); + + // structure specific methods + size_t front() const; + size_t back() const; + void push_back(size_t key); + void push_front(size_t key); + void pop_back(); + void pop_front(); + void sort(); + void remove(size_t key); + + void serialize() const; +}; + +// Actually a FastSet +class KeySet { + KeySet(); + KeySet(const gtsam::KeySet& other); + KeySet(const gtsam::KeyVector& other); + KeySet(const gtsam::KeyList& other); + + // Testable + void print(string s) const; + bool equals(const gtsam::KeySet& other) const; + + // common STL methods + size_t size() const; + bool empty() const; + void clear(); + + // structure specific methods + void insert(size_t key); + void merge(gtsam::KeySet& other); + bool erase(size_t key); // returns true if value was removed + bool count(size_t key) const; // returns true if value exists + + void serialize() const; +}; + +// Actually a vector +class KeyVector { + KeyVector(); + KeyVector(const gtsam::KeyVector& other); + + // Note: no print function + + // common STL methods + size_t size() const; + bool empty() const; + void clear(); + + // structure specific methods + size_t at(size_t i) const; + size_t front() const; + size_t back() const; + void push_back(size_t key) const; + + void serialize() const; +}; + +// Actually a FastMap +class KeyGroupMap { + KeyGroupMap(); + + // Note: no print function + + // common STL methods + size_t size() const; + bool empty() const; + void clear(); + + // structure specific methods + size_t at(size_t key) const; + int erase(size_t key); + bool insert2(size_t key, int val); +}; + +#include +class Marginals { + Marginals(const gtsam::NonlinearFactorGraph& graph, + const gtsam::Values& solution); + + void print(string s) const; + Matrix marginalCovariance(size_t variable) const; + Matrix marginalInformation(size_t variable) const; + gtsam::JointMarginal jointMarginalCovariance(const gtsam::KeyVector& variables) const; + gtsam::JointMarginal jointMarginalInformation(const gtsam::KeyVector& variables) const; +}; + +class JointMarginal { + Matrix at(size_t iVariable, size_t jVariable) const; + Matrix fullMatrix() const; + void print(string s) const; + void print() const; +}; + +#include +virtual class LinearContainerFactor : gtsam::NonlinearFactor { + + LinearContainerFactor(gtsam::GaussianFactor* factor, const gtsam::Values& linearizationPoint); + LinearContainerFactor(gtsam::GaussianFactor* factor); + + gtsam::GaussianFactor* factor() const; +// const boost::optional& linearizationPoint() const; + + bool isJacobian() const; + gtsam::JacobianFactor* toJacobian() const; + gtsam::HessianFactor* toHessian() const; + + static gtsam::NonlinearFactorGraph convertLinearGraph(const gtsam::GaussianFactorGraph& linear_graph, + const gtsam::Values& linearizationPoint); + + static gtsam::NonlinearFactorGraph convertLinearGraph(const gtsam::GaussianFactorGraph& linear_graph); + + // enabling serialization functionality + void serializable() const; +}; // \class LinearContainerFactor + +// Summarization functionality +//#include +// +//// Uses partial QR approach by default +//gtsam::GaussianFactorGraph summarize( +// const gtsam::NonlinearFactorGraph& graph, const gtsam::Values& values, +// const gtsam::KeySet& saved_keys); +// +//gtsam::NonlinearFactorGraph summarizeAsNonlinearContainer( +// const gtsam::NonlinearFactorGraph& graph, const gtsam::Values& values, +// const gtsam::KeySet& saved_keys); + +//************************************************************************* +// Nonlinear optimizers +//************************************************************************* + +#include +#include +virtual class NonlinearOptimizerParams { + NonlinearOptimizerParams(); + void print(string s) const; + + int getMaxIterations() const; + double getRelativeErrorTol() const; + double getAbsoluteErrorTol() const; + double getErrorTol() const; + string getVerbosity() const; + + void setMaxIterations(int value); + void setRelativeErrorTol(double value); + void setAbsoluteErrorTol(double value); + void setErrorTol(double value); + void setVerbosity(string s); + + string getLinearSolverType() const; + + void setLinearSolverType(string solver); + void setOrdering(const gtsam::Ordering& ordering); + void setIterativeParams(gtsam::IterativeOptimizationParameters* params); + + bool isMultifrontal() const; + bool isSequential() const; + bool isCholmod() const; + bool isIterative() const; +}; + +bool checkConvergence(double relativeErrorTreshold, + double absoluteErrorTreshold, double errorThreshold, + double currentError, double newError); + +#include +virtual class GaussNewtonParams : gtsam::NonlinearOptimizerParams { + GaussNewtonParams(); +}; + +#include +virtual class LevenbergMarquardtParams : gtsam::NonlinearOptimizerParams { + LevenbergMarquardtParams(); + + double getlambdaInitial() const; + double getlambdaFactor() const; + double getlambdaUpperBound() const; + string getVerbosityLM() const; + + void setlambdaInitial(double value); + void setlambdaFactor(double value); + void setlambdaUpperBound(double value); + void setVerbosityLM(string s); +}; + +#include +virtual class DoglegParams : gtsam::NonlinearOptimizerParams { + DoglegParams(); + + double getDeltaInitial() const; + string getVerbosityDL() const; + + void setDeltaInitial(double deltaInitial) const; + void setVerbosityDL(string verbosityDL) const; +}; + +virtual class NonlinearOptimizer { + gtsam::Values optimize(); + gtsam::Values optimizeSafely(); + double error() const; + int iterations() const; + gtsam::Values values() const; + void iterate() const; +}; + +virtual class GaussNewtonOptimizer : gtsam::NonlinearOptimizer { + GaussNewtonOptimizer(const gtsam::NonlinearFactorGraph& graph, const gtsam::Values& initialValues); + GaussNewtonOptimizer(const gtsam::NonlinearFactorGraph& graph, const gtsam::Values& initialValues, const gtsam::GaussNewtonParams& params); +}; + +virtual class DoglegOptimizer : gtsam::NonlinearOptimizer { + DoglegOptimizer(const gtsam::NonlinearFactorGraph& graph, const gtsam::Values& initialValues); + DoglegOptimizer(const gtsam::NonlinearFactorGraph& graph, const gtsam::Values& initialValues, const gtsam::DoglegParams& params); + double getDelta() const; +}; + +virtual class LevenbergMarquardtOptimizer : gtsam::NonlinearOptimizer { + LevenbergMarquardtOptimizer(const gtsam::NonlinearFactorGraph& graph, const gtsam::Values& initialValues); + LevenbergMarquardtOptimizer(const gtsam::NonlinearFactorGraph& graph, const gtsam::Values& initialValues, const gtsam::LevenbergMarquardtParams& params); + double lambda() const; + void print(string str) const; +}; + +#include +class ISAM2GaussNewtonParams { + ISAM2GaussNewtonParams(); + + void print(string str) const; + + /** Getters and Setters for all properties */ + double getWildfireThreshold() const; + void setWildfireThreshold(double wildfireThreshold); +}; + +class ISAM2DoglegParams { + ISAM2DoglegParams(); + + void print(string str) const; + + /** Getters and Setters for all properties */ + double getWildfireThreshold() const; + void setWildfireThreshold(double wildfireThreshold); + double getInitialDelta() const; + void setInitialDelta(double initialDelta); + string getAdaptationMode() const; + void setAdaptationMode(string adaptationMode); + bool isVerbose() const; + void setVerbose(bool verbose); +}; + +class ISAM2ThresholdMapValue { + ISAM2ThresholdMapValue(char c, Vector thresholds); + ISAM2ThresholdMapValue(const gtsam::ISAM2ThresholdMapValue& other); +}; + +class ISAM2ThresholdMap { + ISAM2ThresholdMap(); + ISAM2ThresholdMap(const gtsam::ISAM2ThresholdMap& other); + + // Note: no print function + + // common STL methods + size_t size() const; + bool empty() const; + void clear(); + + // structure specific methods + void insert(const gtsam::ISAM2ThresholdMapValue& value) const; +}; + +class ISAM2Params { + ISAM2Params(); + + void print(string str) const; + + /** Getters and Setters for all properties */ + void setOptimizationParams(const gtsam::ISAM2GaussNewtonParams& params); + void setOptimizationParams(const gtsam::ISAM2DoglegParams& params); + void setRelinearizeThreshold(double relinearizeThreshold); + void setRelinearizeThreshold(const gtsam::ISAM2ThresholdMap& relinearizeThreshold); + int getRelinearizeSkip() const; + void setRelinearizeSkip(int relinearizeSkip); + bool isEnableRelinearization() const; + void setEnableRelinearization(bool enableRelinearization); + bool isEvaluateNonlinearError() const; + void setEvaluateNonlinearError(bool evaluateNonlinearError); + string getFactorization() const; + void setFactorization(string factorization); + bool isCacheLinearizedFactors() const; + void setCacheLinearizedFactors(bool cacheLinearizedFactors); + bool isEnableDetailedResults() const; + void setEnableDetailedResults(bool enableDetailedResults); + bool isEnablePartialRelinearizationCheck() const; + void setEnablePartialRelinearizationCheck(bool enablePartialRelinearizationCheck); +}; + +class ISAM2Clique { + + //Constructors + ISAM2Clique(); + + //Standard Interface + Vector gradientContribution() const; + void print(string s); +}; + +class ISAM2Result { + ISAM2Result(); + + void print(string str) const; + + /** Getters and Setters for all properties */ + size_t getVariablesRelinearized() const; + size_t getVariablesReeliminated() const; + size_t getCliques() const; +}; + +class ISAM2 { + ISAM2(); + ISAM2(const gtsam::ISAM2Params& params); + ISAM2(const gtsam::ISAM2& other); + + bool equals(const gtsam::ISAM2& other, double tol) const; + void print(string s) const; + void printStats() const; + void saveGraph(string s) const; + + gtsam::ISAM2Result update(); + gtsam::ISAM2Result update(const gtsam::NonlinearFactorGraph& newFactors, const gtsam::Values& newTheta); + gtsam::ISAM2Result update(const gtsam::NonlinearFactorGraph& newFactors, const gtsam::Values& newTheta, const gtsam::KeyVector& removeFactorIndices); + gtsam::ISAM2Result update(const gtsam::NonlinearFactorGraph& newFactors, const gtsam::Values& newTheta, const gtsam::KeyVector& removeFactorIndices, const gtsam::KeyGroupMap& constrainedKeys); + // TODO: wrap the full version of update + //void update(const gtsam::NonlinearFactorGraph& newFactors, const gtsam::Values& newTheta, const gtsam::KeyVector& removeFactorIndices, FastMap& constrainedKeys); + //void update(const gtsam::NonlinearFactorGraph& newFactors, const gtsam::Values& newTheta, const gtsam::KeyVector& removeFactorIndices, FastMap& constrainedKeys, bool force_relinearize); + + gtsam::Values getLinearizationPoint() const; + gtsam::Values calculateEstimate() const; + gtsam::Value calculateEstimate(size_t key) const; + gtsam::Values calculateBestEstimate() const; + Matrix marginalCovariance(size_t key) const; + gtsam::VectorValues getDelta() const; + gtsam::NonlinearFactorGraph getFactorsUnsafe() const; + gtsam::VariableIndex getVariableIndex() const; + gtsam::ISAM2Params params() const; +}; + +#include +class NonlinearISAM { + NonlinearISAM(); + NonlinearISAM(int reorderInterval); + void print(string s) const; + void printStats() const; + void saveGraph(string s) const; + gtsam::Values estimate() const; + Matrix marginalCovariance(size_t key) const; + int reorderInterval() const; + int reorderCounter() const; + void update(const gtsam::NonlinearFactorGraph& newFactors, const gtsam::Values& initialValues); + void reorder_relinearize(); + + // These might be expensive as instead of a reference the wrapper will make a copy + gtsam::GaussianISAM bayesTree() const; + gtsam::Values getLinearizationPoint() const; + gtsam::NonlinearFactorGraph getFactorsUnsafe() const; +}; + +//************************************************************************* +// Nonlinear factor types +//************************************************************************* +#include +#include +#include + +#include +template +virtual class PriorFactor : gtsam::NoiseModelFactor { + PriorFactor(size_t key, const T& prior, const gtsam::noiseModel::Base* noiseModel); + T prior() const; + + // enabling serialization functionality + void serialize() const; +}; + + +#include +template +virtual class BetweenFactor : gtsam::NoiseModelFactor { + BetweenFactor(size_t key1, size_t key2, const T& relativePose, const gtsam::noiseModel::Base* noiseModel); + T measured() const; + + // enabling serialization functionality + void serialize() const; +}; + + + +#include +template +virtual class NonlinearEquality : gtsam::NoiseModelFactor { + // Constructor - forces exact evaluation + NonlinearEquality(size_t j, const T& feasible); + // Constructor - allows inexact evaluation + NonlinearEquality(size_t j, const T& feasible, double error_gain); + + // enabling serialization functionality + void serialize() const; +}; + + +#include +template +virtual class RangeFactor : gtsam::NoiseModelFactor { + RangeFactor(size_t key1, size_t key2, double measured, const gtsam::noiseModel::Base* noiseModel); +}; + +typedef gtsam::RangeFactor RangeFactorPosePoint2; +typedef gtsam::RangeFactor RangeFactorPosePoint3; +typedef gtsam::RangeFactor RangeFactorPose2; +typedef gtsam::RangeFactor RangeFactorPose3; +typedef gtsam::RangeFactor RangeFactorCalibratedCameraPoint; +typedef gtsam::RangeFactor RangeFactorSimpleCameraPoint; +typedef gtsam::RangeFactor RangeFactorCalibratedCamera; +typedef gtsam::RangeFactor RangeFactorSimpleCamera; + + +#include +template +virtual class BearingFactor : gtsam::NoiseModelFactor { + BearingFactor(size_t key1, size_t key2, const BEARING& measured, const gtsam::noiseModel::Base* noiseModel); + + // enabling serialization functionality + void serialize() const; +}; + +typedef gtsam::BearingFactor BearingFactor2D; + +#include +template +virtual class BearingRangeFactor : gtsam::NoiseModelFactor { + BearingRangeFactor(size_t poseKey, size_t pointKey, + const BEARING& measuredBearing, const RANGE& measuredRange, + const gtsam::noiseModel::Base* noiseModel); + + // enabling serialization functionality + void serialize() const; +}; + +typedef gtsam::BearingRangeFactor BearingRangeFactor2D; + + +#include +template +virtual class GenericProjectionFactor : gtsam::NoiseModelFactor { + GenericProjectionFactor(const gtsam::Point2& measured, const gtsam::noiseModel::Base* noiseModel, + size_t poseKey, size_t pointKey, const CALIBRATION* k); + GenericProjectionFactor(const gtsam::Point2& measured, const gtsam::noiseModel::Base* noiseModel, + size_t poseKey, size_t pointKey, const CALIBRATION* k, const POSE& body_P_sensor); + + GenericProjectionFactor(const gtsam::Point2& measured, const gtsam::noiseModel::Base* noiseModel, + size_t poseKey, size_t pointKey, const CALIBRATION* k, bool throwCheirality, bool verboseCheirality); + GenericProjectionFactor(const gtsam::Point2& measured, const gtsam::noiseModel::Base* noiseModel, + size_t poseKey, size_t pointKey, const CALIBRATION* k, bool throwCheirality, bool verboseCheirality, + const POSE& body_P_sensor); + + gtsam::Point2 measured() const; + CALIBRATION* calibration() const; + bool verboseCheirality() const; + bool throwCheirality() const; + + // enabling serialization functionality + void serialize() const; +}; +typedef gtsam::GenericProjectionFactor GenericProjectionFactorCal3_S2; +typedef gtsam::GenericProjectionFactor GenericProjectionFactorCal3DS2; + + +#include +template +virtual class GeneralSFMFactor : gtsam::NoiseModelFactor { + GeneralSFMFactor(const gtsam::Point2& measured, const gtsam::noiseModel::Base* model, size_t cameraKey, size_t landmarkKey); + gtsam::Point2 measured() const; +}; +typedef gtsam::GeneralSFMFactor GeneralSFMFactorCal3_S2; +typedef gtsam::GeneralSFMFactor GeneralSFMFactorCal3DS2; + +template +virtual class GeneralSFMFactor2 : gtsam::NoiseModelFactor { + GeneralSFMFactor2(const gtsam::Point2& measured, const gtsam::noiseModel::Base* model, size_t poseKey, size_t landmarkKey, size_t calibKey); + gtsam::Point2 measured() const; + + // enabling serialization functionality + void serialize() const; +}; + +#include +class SmartProjectionParams { + SmartProjectionParams(); + // TODO(frank): make these work: + // void setLinearizationMode(LinearizationMode linMode); + // void setDegeneracyMode(DegeneracyMode degMode); + void setRankTolerance(double rankTol); + void setEnableEPI(bool enableEPI); + void setLandmarkDistanceThreshold(bool landmarkDistanceThreshold); + void setDynamicOutlierRejectionThreshold(bool dynOutRejectionThreshold); +}; + +#include +template +virtual class SmartProjectionPoseFactor: gtsam::NonlinearFactor { + + SmartProjectionPoseFactor(const gtsam::noiseModel::Base* noise, + const CALIBRATION* K); + SmartProjectionPoseFactor(const gtsam::noiseModel::Base* noise, + const CALIBRATION* K, + const gtsam::Pose3& body_P_sensor); + SmartProjectionPoseFactor(const gtsam::noiseModel::Base* noise, + const CALIBRATION* K, + const gtsam::Pose3& body_P_sensor, + const gtsam::SmartProjectionParams& params); + + void add(const gtsam::Point2& measured_i, size_t poseKey_i); + + // enabling serialization functionality + //void serialize() const; +}; + +typedef gtsam::SmartProjectionPoseFactor SmartProjectionPose3Factor; + + +#include +template +virtual class GenericStereoFactor : gtsam::NoiseModelFactor { + GenericStereoFactor(const gtsam::StereoPoint2& measured, const gtsam::noiseModel::Base* noiseModel, + size_t poseKey, size_t landmarkKey, const gtsam::Cal3_S2Stereo* K); + gtsam::StereoPoint2 measured() const; + gtsam::Cal3_S2Stereo* calibration() const; + + // enabling serialization functionality + void serialize() const; +}; +typedef gtsam::GenericStereoFactor GenericStereoFactor3D; + +#include +template +virtual class PoseTranslationPrior : gtsam::NoiseModelFactor { + PoseTranslationPrior(size_t key, const POSE& pose_z, const gtsam::noiseModel::Base* noiseModel); +}; + +typedef gtsam::PoseTranslationPrior PoseTranslationPrior2D; +typedef gtsam::PoseTranslationPrior PoseTranslationPrior3D; + +#include +template +virtual class PoseRotationPrior : gtsam::NoiseModelFactor { + PoseRotationPrior(size_t key, const POSE& pose_z, const gtsam::noiseModel::Base* noiseModel); +}; + +typedef gtsam::PoseRotationPrior PoseRotationPrior2D; +typedef gtsam::PoseRotationPrior PoseRotationPrior3D; + +#include +virtual class EssentialMatrixFactor : gtsam::NoiseModelFactor { + EssentialMatrixFactor(size_t key, const gtsam::Point2& pA, const gtsam::Point2& pB, + const gtsam::noiseModel::Base* noiseModel); +}; + +#include +pair load2D(string filename, + gtsam::noiseModel::Diagonal* model, int maxID, bool addNoise, bool smart); +pair load2D(string filename, + gtsam::noiseModel::Diagonal* model, int maxID, bool addNoise); +pair load2D(string filename, + gtsam::noiseModel::Diagonal* model, int maxID); +pair load2D(string filename, + gtsam::noiseModel::Diagonal* model); +pair load2D(string filename); +pair load2D_robust(string filename, + gtsam::noiseModel::Base* model); +void save2D(const gtsam::NonlinearFactorGraph& graph, + const gtsam::Values& config, gtsam::noiseModel::Diagonal* model, + string filename); + +pair readG2o(string filename); +void writeG2o(const gtsam::NonlinearFactorGraph& graph, + const gtsam::Values& estimate, string filename); + +//************************************************************************* +// Navigation +//************************************************************************* +namespace imuBias { +#include + +class ConstantBias { + // Standard Constructor + ConstantBias(); + ConstantBias(Vector biasAcc, Vector biasGyro); + + // Testable + void print(string s) const; + bool equals(const gtsam::imuBias::ConstantBias& expected, double tol) const; + + // Group + static gtsam::imuBias::ConstantBias identity(); + gtsam::imuBias::ConstantBias inverse() const; + gtsam::imuBias::ConstantBias compose(const gtsam::imuBias::ConstantBias& b) const; + gtsam::imuBias::ConstantBias between(const gtsam::imuBias::ConstantBias& b) const; + + // Manifold + gtsam::imuBias::ConstantBias retract(Vector v) const; + Vector localCoordinates(const gtsam::imuBias::ConstantBias& b) const; + + // Lie Group + static gtsam::imuBias::ConstantBias Expmap(Vector v); + static Vector Logmap(const gtsam::imuBias::ConstantBias& b); + + // Standard Interface + Vector vector() const; + Vector accelerometer() const; + Vector gyroscope() const; + Vector correctAccelerometer(Vector measurement) const; + Vector correctGyroscope(Vector measurement) const; +}; + +}///\namespace imuBias + +#include +class PoseVelocityBias{ + PoseVelocityBias(const gtsam::Pose3& pose, Vector velocity, const gtsam::imuBias::ConstantBias& bias); + }; +class PreintegratedImuMeasurements { + // Standard Constructor + PreintegratedImuMeasurements(const gtsam::imuBias::ConstantBias& bias, Matrix measuredAccCovariance,Matrix measuredOmegaCovariance, Matrix integrationErrorCovariance, bool use2ndOrderIntegration); + PreintegratedImuMeasurements(const gtsam::imuBias::ConstantBias& bias, Matrix measuredAccCovariance,Matrix measuredOmegaCovariance, Matrix integrationErrorCovariance); + // PreintegratedImuMeasurements(const gtsam::PreintegratedImuMeasurements& rhs); + + // Testable + void print(string s) const; + bool equals(const gtsam::PreintegratedImuMeasurements& expected, double tol); + + double deltaTij() const; + gtsam::Rot3 deltaRij() const; + Vector deltaPij() const; + Vector deltaVij() const; + Vector biasHatVector() const; + Matrix delPdelBiasAcc() const; + Matrix delPdelBiasOmega() const; + Matrix delVdelBiasAcc() const; + Matrix delVdelBiasOmega() const; + Matrix delRdelBiasOmega() const; + Matrix preintMeasCov() const; + + // Standard Interface + void integrateMeasurement(Vector measuredAcc, Vector measuredOmega, double deltaT); + gtsam::PoseVelocityBias predict(const gtsam::Pose3& pose_i, Vector vel_i, const gtsam::imuBias::ConstantBias& bias, + Vector gravity, Vector omegaCoriolis) const; +}; + +virtual class ImuFactor : gtsam::NonlinearFactor { + ImuFactor(size_t pose_i, size_t vel_i, size_t pose_j, size_t vel_j, size_t bias, + const gtsam::PreintegratedImuMeasurements& preintegratedMeasurements, Vector gravity, Vector omegaCoriolis); + ImuFactor(size_t pose_i, size_t vel_i, size_t pose_j, size_t vel_j, size_t bias, + const gtsam::PreintegratedImuMeasurements& preintegratedMeasurements, Vector gravity, Vector omegaCoriolis, + const gtsam::Pose3& body_P_sensor); + // Standard Interface + gtsam::PreintegratedImuMeasurements preintegratedMeasurements() const; +}; + +#include +class PreintegratedCombinedMeasurements { + // Standard Constructor + PreintegratedCombinedMeasurements( + const gtsam::imuBias::ConstantBias& bias, + Matrix measuredAccCovariance, + Matrix measuredOmegaCovariance, + Matrix integrationErrorCovariance, + Matrix biasAccCovariance, + Matrix biasOmegaCovariance, + Matrix biasAccOmegaInit); + PreintegratedCombinedMeasurements( + const gtsam::imuBias::ConstantBias& bias, + Matrix measuredAccCovariance, + Matrix measuredOmegaCovariance, + Matrix integrationErrorCovariance, + Matrix biasAccCovariance, + Matrix biasOmegaCovariance, + Matrix biasAccOmegaInit, + bool use2ndOrderIntegration); + // PreintegratedCombinedMeasurements(const gtsam::PreintegratedCombinedMeasurements& rhs); + + // Testable + void print(string s) const; + bool equals(const gtsam::PreintegratedCombinedMeasurements& expected, double tol); + + double deltaTij() const; + gtsam::Rot3 deltaRij() const; + Vector deltaPij() const; + Vector deltaVij() const; + Vector biasHatVector() const; + Matrix delPdelBiasAcc() const; + Matrix delPdelBiasOmega() const; + Matrix delVdelBiasAcc() const; + Matrix delVdelBiasOmega() const; + Matrix delRdelBiasOmega() const; + Matrix preintMeasCov() const; + + // Standard Interface + void integrateMeasurement(Vector measuredAcc, Vector measuredOmega, double deltaT); + gtsam::PoseVelocityBias predict(const gtsam::Pose3& pose_i, Vector vel_i, const gtsam::imuBias::ConstantBias& bias, + Vector gravity, Vector omegaCoriolis) const; +}; + +virtual class CombinedImuFactor : gtsam::NonlinearFactor { + CombinedImuFactor(size_t pose_i, size_t vel_i, size_t pose_j, size_t vel_j, size_t bias_i, size_t bias_j, + const gtsam::PreintegratedCombinedMeasurements& CombinedPreintegratedMeasurements, Vector gravity, Vector omegaCoriolis); + // Standard Interface + gtsam::PreintegratedCombinedMeasurements preintegratedMeasurements() const; +}; + +#include +class PreintegratedAhrsMeasurements { + // Standard Constructor + PreintegratedAhrsMeasurements(Vector bias, Matrix measuredOmegaCovariance); + PreintegratedAhrsMeasurements(Vector bias, Matrix measuredOmegaCovariance); + PreintegratedAhrsMeasurements(const gtsam::PreintegratedAhrsMeasurements& rhs); + + // Testable + void print(string s) const; + bool equals(const gtsam::PreintegratedAhrsMeasurements& expected, double tol); + + // get Data + gtsam::Rot3 deltaRij() const; + double deltaTij() const; + Vector biasHat() const; + + // Standard Interface + void integrateMeasurement(Vector measuredOmega, double deltaT); + void resetIntegration() ; +}; + +virtual class AHRSFactor : gtsam::NonlinearFactor { + AHRSFactor(size_t rot_i, size_t rot_j,size_t bias, + const gtsam::PreintegratedAhrsMeasurements& preintegratedMeasurements, Vector omegaCoriolis); + AHRSFactor(size_t rot_i, size_t rot_j, size_t bias, + const gtsam::PreintegratedAhrsMeasurements& preintegratedMeasurements, Vector omegaCoriolis, + const gtsam::Pose3& body_P_sensor); + + // Standard Interface + gtsam::PreintegratedAhrsMeasurements preintegratedMeasurements() const; + Vector evaluateError(const gtsam::Rot3& rot_i, const gtsam::Rot3& rot_j, + Vector bias) const; + gtsam::Rot3 predict(const gtsam::Rot3& rot_i, Vector bias, + const gtsam::PreintegratedAhrsMeasurements& preintegratedMeasurements, + Vector omegaCoriolis) const; +}; + +#include +//virtual class AttitudeFactor : gtsam::NonlinearFactor { +// AttitudeFactor(const Unit3& nZ, const Unit3& bRef); +// AttitudeFactor(); +//}; +virtual class Rot3AttitudeFactor : gtsam::NonlinearFactor{ + Rot3AttitudeFactor(size_t key, const gtsam::Unit3& nZ, const gtsam::noiseModel::Diagonal* model, + const gtsam::Unit3& bRef); + Rot3AttitudeFactor(size_t key, const gtsam::Unit3& nZ, const gtsam::noiseModel::Diagonal* model); + Rot3AttitudeFactor(); + void print(string s) const; + bool equals(const gtsam::NonlinearFactor& expected, double tol) const; + gtsam::Unit3 nZ() const; + gtsam::Unit3 bRef() const; +}; + +virtual class Pose3AttitudeFactor : gtsam::NonlinearFactor{ + Pose3AttitudeFactor(size_t key, const gtsam::Unit3& nZ, const gtsam::noiseModel::Diagonal* model, + const gtsam::Unit3& bRef); + Pose3AttitudeFactor(size_t key, const gtsam::Unit3& nZ, const gtsam::noiseModel::Diagonal* model); + Pose3AttitudeFactor(); + void print(string s) const; + bool equals(const gtsam::NonlinearFactor& expected, double tol) const; + gtsam::Unit3 nZ() const; + gtsam::Unit3 bRef() const; +}; + +//************************************************************************* +// Utilities +//************************************************************************* + +namespace utilities { + + #include + gtsam::KeyList createKeyList(Vector I); + gtsam::KeyList createKeyList(string s, Vector I); + gtsam::KeyVector createKeyVector(Vector I); + gtsam::KeyVector createKeyVector(string s, Vector I); + gtsam::KeySet createKeySet(Vector I); + gtsam::KeySet createKeySet(string s, Vector I); + Matrix extractPoint2(const gtsam::Values& values); + Matrix extractPoint3(const gtsam::Values& values); + Matrix extractPose2(const gtsam::Values& values); + gtsam::Values allPose3s(gtsam::Values& values); + Matrix extractPose3(const gtsam::Values& values); + void perturbPoint2(gtsam::Values& values, double sigma, int seed); + void perturbPose2 (gtsam::Values& values, double sigmaT, double sigmaR, int seed); + void perturbPoint3(gtsam::Values& values, double sigma, int seed); + void insertBackprojections(gtsam::Values& values, const gtsam::SimpleCamera& c, Vector J, Matrix Z, double depth); + void insertProjectionFactors(gtsam::NonlinearFactorGraph& graph, size_t i, Vector J, Matrix Z, const gtsam::noiseModel::Base* model, const gtsam::Cal3_S2* K); + void insertProjectionFactors(gtsam::NonlinearFactorGraph& graph, size_t i, Vector J, Matrix Z, const gtsam::noiseModel::Base* model, const gtsam::Cal3_S2* K, const gtsam::Pose3& body_P_sensor); + Matrix reprojectionErrors(const gtsam::NonlinearFactorGraph& graph, const gtsam::Values& values); + gtsam::Values localToWorld(const gtsam::Values& local, const gtsam::Pose2& base); + gtsam::Values localToWorld(const gtsam::Values& local, const gtsam::Pose2& base, const gtsam::KeyVector& keys); + +} //\namespace utilities + +} diff --git a/matlab.h b/matlab.h index 349cdeea4..4a9ac2309 100644 --- a/matlab.h +++ b/matlab.h @@ -71,16 +71,16 @@ FastVector createKeyVector(string s, const Vector& I) { } // Create a KeySet from indices -FastSet createKeySet(const Vector& I) { - FastSet set; +KeySet createKeySet(const Vector& I) { + KeySet set; for (int i = 0; i < I.size(); i++) set.insert(I[i]); return set; } // Create a KeySet from indices using symbol -FastSet createKeySet(string s, const Vector& I) { - FastSet set; +KeySet createKeySet(string s, const Vector& I) { + KeySet set; char c = s[0]; for (int i = 0; i < I.size(); i++) set.insert(symbol(c, I[i])); @@ -229,7 +229,7 @@ Values localToWorld(const Values& local, const Pose2& base, // if no keys given, get all keys from local values FastVector keys(user_keys); if (keys.size()==0) - keys = FastVector(local.keys()); + keys = local.keys(); // Loop over all keys BOOST_FOREACH(Key key, keys) { diff --git a/python/.gitignore b/python/.gitignore new file mode 100644 index 000000000..d16386367 --- /dev/null +++ b/python/.gitignore @@ -0,0 +1 @@ +build/ \ No newline at end of file diff --git a/python/CMakeLists.txt b/python/CMakeLists.txt new file mode 100644 index 000000000..f7ceb62b3 --- /dev/null +++ b/python/CMakeLists.txt @@ -0,0 +1,96 @@ +# Guard to avoid breaking this code in ccmake if by accident GTSAM_PYTHON_VERSION is set to an empty string +if(GTSAM_PYTHON_VERSION STREQUAL "") + set(GTSAM_PYTHON_VERSION "Default" CACHE STRING "Target python version for GTSAM python module. Use 'Default' to chose the default version" FORCE) +endif() + +# The code below allows to clear the PythonLibs cache if we change GTSAM_PYTHON_VERSION +# Inspired from the solution found here: http://blog.bethcodes.com/cmake-tips-tricks-drop-down-list +if(NOT DEFINED GTSAM_LAST_PYTHON_VERSION) + set(GTSAM_LAST_PYTHON_VERSION ${GTSAM_PYTHON_VERSION} CACHE STRING "Python version used in the last build") + mark_as_advanced(FORCE GTSAM_LAST_PYTHON_VERSION) +endif() +if(NOT (${GTSAM_PYTHON_VERSION} MATCHES ${GTSAM_LAST_PYTHON_VERSION})) + unset(PYTHON_INCLUDE_DIR CACHE) + unset(PYTHON_INCLUDE_DIR2 CACHE) + unset(PYTHON_LIBRARY CACHE) + unset(PYTHON_LIBRARY_DEBUG CACHE) + set(GTSAM_LAST_PYTHON_VERSION ${GTSAM_PYTHON_VERSION} CACHE STRING "Updating python version used in the last build" FORCE) +endif() + +if(GTSAM_PYTHON_VERSION STREQUAL "Default") + # Search the default version. + find_package(PythonInterp) + find_package(PythonLibs) +else() + find_package(PythonInterp ${GTSAM_PYTHON_VERSION}) + find_package(PythonLibs ${GTSAM_PYTHON_VERSION}) +endif() + +# Find NumPy C-API -- this is part of the numpy package +find_package(NumPy) + +# Compose strings used to specify the boost python version. They will be empty if we want to use the defaut +if(NOT GTSAM_PYTHON_VERSION STREQUAL "Default") + string(REPLACE "." "" BOOST_PYTHON_VERSION_SUFFIX ${GTSAM_PYTHON_VERSION}) # Remove '.' from version + string(SUBSTRING ${BOOST_PYTHON_VERSION_SUFFIX} 0 2 BOOST_PYTHON_VERSION_SUFFIX) # Trim version number to 2 digits + set(BOOST_PYTHON_VERSION_SUFFIX "-py${BOOST_PYTHON_VERSION_SUFFIX}") # Append '-py' prefix + string(TOUPPER ${BOOST_PYTHON_VERSION_SUFFIX} BOOST_PYTHON_VERSION_SUFFIX_UPPERCASE) # Get uppercase string +else() + set(BOOST_PYTHON_VERSION_SUFFIX "") + set(BOOST_PYTHON_VERSION_SUFFIX_UPPERCASE "") +endif() + +# Find Boost Python +find_package(Boost COMPONENTS python${BOOST_PYTHON_VERSION_SUFFIX}) + +if(Boost_PYTHON${BOOST_PYTHON_VERSION_SUFFIX_UPPERCASE}_FOUND AND PYTHONLIBS_FOUND AND NUMPY_FOUND) + # Build library + include_directories(${NUMPY_INCLUDE_DIRS}) + include_directories(${PYTHON_INCLUDE_DIRS}) + include_directories(${Boost_INCLUDE_DIRS}) + include_directories(${CMAKE_CURRENT_SOURCE_DIR}/include/) + + # Build the python module library + add_subdirectory(handwritten) + + # Create and invoke setup.py, see https://bloerg.net/2012/11/10/cmake-and-distutils.html + set(SETUP_PY_IN "${CMAKE_CURRENT_SOURCE_DIR}/setup.py.in") + set(SETUP_PY "${CMAKE_CURRENT_BINARY_DIR}/setup.py") + + # Hacky way to figure out install folder - valid for Linux & Mac + # default pattern: prefix/lib/pythonX.Y/site-packages from https://docs.python.org/2/install/ + SET(PY_INSTALL_FOLDER "${CMAKE_INSTALL_PREFIX}/lib/python${PYTHON_VERSION_MAJOR}.${PYTHON_VERSION_MINOR}/site-packages") + + configure_file(${SETUP_PY_IN} ${SETUP_PY}) + + # TODO(frank): possibly support a different prefix a la matlab wrapper + install(CODE "execute_process(WORKING_DIRECTORY ${CMAKE_CURRENT_BINARY_DIR} COMMAND ${PYTHON_EXECUTABLE} setup.py -v install --prefix ${CMAKE_INSTALL_PREFIX})") +else() + # Disable python module if we didn't find required libraries + # message will print at end of main CMakeLists.txt + SET(GTSAM_PYTHON_WARNINGS "Python dependencies not found - Python module will not be built. Set GTSAM_BUILD_PYTHON to 'Off' to disable this warning. Details:") + + if(NOT PYTHONLIBS_FOUND) + if(GTSAM_PYTHON_VERSION STREQUAL "Default") + SET(GTSAM_PYTHON_WARNINGS "${GTSAM_PYTHON_WARNINGS}\n -- Default PythonLibs not found") + else() + SET(GTSAM_PYTHON_WARNINGS "${GTSAM_PYTHON_WARNINGS}\n -- PythonLibs version ${GTSAM_PYTHON_VERSION} not found") + endif() + endif() + + if(NOT NUMPY_FOUND) + SET(GTSAM_PYTHON_WARNINGS "${GTSAM_PYTHON_WARNINGS}\n -- Numpy not found") + endif() + + if(NOT Boost_PYTHON${BOOST_PYTHON_VERSION_SUFFIX_UPPERCASE}_FOUND) + if(GTSAM_PYTHON_VERSION STREQUAL "Default") + SET(GTSAM_PYTHON_WARNINGS "${GTSAM_PYTHON_WARNINGS}\n -- Default Boost python not found") + else() + SET(GTSAM_PYTHON_WARNINGS "${GTSAM_PYTHON_WARNINGS}\n -- Boost Python for python ${GTSAM_PYTHON_VERSION} not found") + endif() + endif() + + # make available at top-level + SET(GTSAM_PYTHON_WARNINGS ${GTSAM_PYTHON_WARNINGS} PARENT_SCOPE) + +endif() diff --git a/python/README.md b/python/README.md new file mode 100644 index 000000000..f1c218cfb --- /dev/null +++ b/python/README.md @@ -0,0 +1,18 @@ +Python Wrapper and Packaging +============================ + +This directory contains the basic setup script and directory structure for the gtsam python module. +During the build of gtsam, when GTSAM_BUILD_PYTHON is enabled, the following instructions will run. + +* The handwritten module source files are compiled and linked with Boost Python, generating a shared + library which can then be imported by python +* A setup.py script is configured from setup.py.in +* The gtsam packages 'gtsam', 'gtsam_utils', 'gtsam_examples', and 'gtsam_tests' are installed into + the site-packages folder within the (possibly non-default) installation prefix folder. If + installing to a non-standard prefix, make sure that _prefix_/lib/pythonX.Y/site-packages is + present in your $PYTHONPATH + +The target version of Python to create the module can be set by defining GTSAM_PYTHON_VERSION to 'X.Y' (Example: 2.7 or 3.4), or 'Default' if you want to use the default python installed in your system. Note that if you specify a target version of python, you should also have the correspondening Boost +Python version installed (Example: libboost_python-py27.so or libboost_python-py34.so on Linux). +If you're using the default version, your default Boost Python library (Example: libboost_python.so on Linux) should correspond to the default python version in your system. + diff --git a/python/gtsam/__init__.py b/python/gtsam/__init__.py new file mode 100644 index 000000000..f9e40517d --- /dev/null +++ b/python/gtsam/__init__.py @@ -0,0 +1 @@ +from ._libgtsam_python import * diff --git a/python/gtsam_examples/ImuFactorExample.py b/python/gtsam_examples/ImuFactorExample.py new file mode 100644 index 000000000..ca5e524ee --- /dev/null +++ b/python/gtsam_examples/ImuFactorExample.py @@ -0,0 +1,105 @@ +""" +A script validating the ImuFactor inference. +""" + +from __future__ import print_function +import math +import matplotlib.pyplot as plt +import numpy as np + +from mpl_toolkits.mplot3d import Axes3D + +import gtsam +from gtsam_utils import plotPose3 +from PreintegrationExample import PreintegrationExample, POSES_FIG + +# shorthand symbols: +BIAS_KEY = int(gtsam.Symbol('b', 0)) +V = lambda j: int(gtsam.Symbol('v', j)) +X = lambda i: int(gtsam.Symbol('x', i)) + +class ImuFactorExample(PreintegrationExample): + + def __init__(self): + self.velocity = np.array([2, 0, 0]) + self.priorNoise = gtsam.noiseModel.Isotropic.Sigma(6, 0.1) + self.velNoise = gtsam.noiseModel.Isotropic.Sigma(3, 0.1) + + forward_twist = (np.zeros(3), self.velocity) + loop_twist = (np.array([0, -math.radians(30), 0]), self.velocity) + + accBias = np.array([-0.3, 0.1, 0.2]) + gyroBias = np.array([0.1, 0.3, -0.1]) + bias = gtsam.ConstantBias(accBias, gyroBias) + + super(ImuFactorExample, self).__init__(loop_twist, bias) + + def addPrior(self, i, graph): + state = self.scenario.navState(i) + graph.push_back(gtsam.PriorFactorPose3(X(i), state.pose(), self.priorNoise)) + graph.push_back(gtsam.PriorFactorVector3(V(i), state.velocity(), self.velNoise)) + + def run(self): + graph = gtsam.NonlinearFactorGraph() + + i = 0 # state index + + # initialize data structure for pre-integrated IMU measurements + pim = gtsam.PreintegratedImuMeasurements(self.params, self.actualBias) + + # simulate the loop + T = 12 + actual_state_i = self.scenario.navState(0) + for k, t in enumerate(np.arange(0, T, self.dt)): + # get measurements and add them to PIM + measuredOmega = self.runner.measuredAngularVelocity(t) + measuredAcc = self.runner.measuredSpecificForce(t) + pim.integrateMeasurement(measuredAcc, measuredOmega, self.dt) + + # Plot IMU many times + if k % 10 == 0: + self.plotImu(t, measuredOmega, measuredAcc) + + # Plot every second + if k % 100 == 0: + self.plotGroundTruthPose(t) + + # create IMU factor every second + if (k + 1) % 100 == 0: + factor = gtsam.ImuFactor(X(i), V(i), X(i + 1), V(i + 1), BIAS_KEY, pim) + graph.push_back(factor) + pim.resetIntegration() + actual_state_i = self.scenario.navState(t + self.dt) + i += 1 + + # add priors on beginning and end + num_poses = i + 1 + self.addPrior(0, graph) + self.addPrior(num_poses - 1, graph) + + initial = gtsam.Values() + initial.insert(BIAS_KEY, self.actualBias) + for i in range(num_poses): + state_i = self.scenario.navState(float(i)) + initial.insert(X(i), state_i.pose()) + initial.insert(V(i), state_i.velocity()) + + # optimize using Levenberg-Marquardt optimization + params = gtsam.LevenbergMarquardtParams() + params.setVerbosityLM("SUMMARY") + optimizer = gtsam.LevenbergMarquardtOptimizer(graph, initial, params) + result = optimizer.optimize() + + # Plot resulting poses + i = 0 + while result.exists(X(i)): + pose_i = result.atPose3(X(i)) + plotPose3(POSES_FIG, pose_i, 0.1) + i += 1 + print(result.atConstantBias(BIAS_KEY)) + + plt.ioff() + plt.show() + +if __name__ == '__main__': + ImuFactorExample().run() diff --git a/python/gtsam_examples/OdometryExample.py b/python/gtsam_examples/OdometryExample.py new file mode 100644 index 000000000..0800bab4e --- /dev/null +++ b/python/gtsam_examples/OdometryExample.py @@ -0,0 +1,36 @@ +#!/usr/bin/env python +from __future__ import print_function +import gtsam +import numpy as np + +# Create an empty nonlinear factor graph +graph = gtsam.NonlinearFactorGraph() + +# Add a prior on the first pose, setting it to the origin +# A prior factor consists of a mean and a noise model (covariance matrix) +priorMean = gtsam.Pose2(0.0, 0.0, 0.0) # prior at origin +priorNoise = gtsam.noiseModel.Diagonal.Sigmas(np.array([0.3, 0.3, 0.1])) +graph.add(gtsam.PriorFactorPose2(1, priorMean, priorNoise)) + +# Add odometry factors +odometry = gtsam.Pose2(2.0, 0.0, 0.0) +# For simplicity, we will use the same noise model for each odometry factor +odometryNoise = gtsam.noiseModel.Diagonal.Sigmas(np.array([0.2, 0.2, 0.1])) +# Create odometry (Between) factors between consecutive poses +graph.add(gtsam.BetweenFactorPose2(1, 2, odometry, odometryNoise)) +graph.add(gtsam.BetweenFactorPose2(2, 3, odometry, odometryNoise)) +graph.print("\nFactor Graph:\n") + +# Create the data structure to hold the initialEstimate estimate to the solution +# For illustrative purposes, these have been deliberately set to incorrect values +initial = gtsam.Values() +initial.insert(1, gtsam.Pose2(0.5, 0.0, 0.2)) +initial.insert(2, gtsam.Pose2(2.3, 0.1, -0.2)) +initial.insert(3, gtsam.Pose2(4.1, 0.1, 0.1)) +initial.print("\nInitial Estimate:\n") + +# optimize using Levenberg-Marquardt optimization +params = gtsam.LevenbergMarquardtParams() +optimizer = gtsam.LevenbergMarquardtOptimizer(graph, initial, params) +result = optimizer.optimize() +result.print("\nFinal Result:\n") diff --git a/python/gtsam_examples/PreintegrationExample.py b/python/gtsam_examples/PreintegrationExample.py new file mode 100644 index 000000000..7095dc59e --- /dev/null +++ b/python/gtsam_examples/PreintegrationExample.py @@ -0,0 +1,129 @@ +""" +A script validating the Preintegration of IMU measurements +""" + +import math +import matplotlib.pyplot as plt +import numpy as np + +from mpl_toolkits.mplot3d import Axes3D + +import gtsam +from gtsam_utils import plotPose3 + +IMU_FIG = 1 +POSES_FIG = 2 + +class PreintegrationExample(object): + + @staticmethod + def defaultParams(g): + """Create default parameters with Z *up* and realistic noise parameters""" + params = gtsam.PreintegrationParams.MakeSharedU(g) + kGyroSigma = math.radians(0.5) / 60 # 0.5 degree ARW + kAccelSigma = 0.1 / 60 # 10 cm VRW + params.gyroscopeCovariance = kGyroSigma ** 2 * np.identity(3, np.float) + params.accelerometerCovariance = kAccelSigma ** 2 * np.identity(3, np.float) + params.integrationCovariance = 0.0000001 ** 2 * np.identity(3, np.float) + return params + + def __init__(self, twist=None, bias=None): + """Initialize with given twist, a pair(angularVelocityVector, velocityVector).""" + + # setup interactive plotting + plt.ion() + + # Setup loop as default scenario + if twist is not None: + (W, V) = twist + else: + # default = loop with forward velocity 2m/s, while pitching up + # with angular velocity 30 degree/sec (negative in FLU) + W = np.array([0, -math.radians(30), 0]) + V = np.array([2, 0, 0]) + + self.scenario = gtsam.ConstantTwistScenario(W, V) + self.dt = 1e-2 + + self.maxDim = 5 + self.labels = list('xyz') + self.colors = list('rgb') + + # Create runner + self.g = 10 # simple gravity constant + self.params = self.defaultParams(self.g) + ptr = gtsam.ScenarioPointer(self.scenario) + + if bias is not None: + self.actualBias = bias + else: + accBias = np.array([0, 0.1, 0]) + gyroBias = np.array([0, 0, 0]) + self.actualBias = gtsam.ConstantBias(accBias, gyroBias) + + self.runner = gtsam.ScenarioRunner(ptr, self.params, self.dt, self.actualBias) + + def plotImu(self, t, measuredOmega, measuredAcc): + plt.figure(IMU_FIG) + + # plot angular velocity + omega_b = self.scenario.omega_b(t) + for i, (label, color) in enumerate(zip(self.labels, self.colors)): + plt.subplot(4, 3, i + 1) + plt.scatter(t, omega_b[i], color='k', marker='.') + plt.scatter(t, measuredOmega[i], color=color, marker='.') + plt.xlabel('angular velocity ' + label) + + # plot acceleration in nav + acceleration_n = self.scenario.acceleration_n(t) + for i, (label, color) in enumerate(zip(self.labels, self.colors)): + plt.subplot(4, 3, i + 4) + plt.scatter(t, acceleration_n[i], color=color, marker='.') + plt.xlabel('acceleration in nav ' + label) + + # plot acceleration in body + acceleration_b = self.scenario.acceleration_b(t) + for i, (label, color) in enumerate(zip(self.labels, self.colors)): + plt.subplot(4, 3, i + 7) + plt.scatter(t, acceleration_b[i], color=color, marker='.') + plt.xlabel('acceleration in body ' + label) + + # plot actual specific force, as well as corrupted + actual = self.runner.actualSpecificForce(t) + for i, (label, color) in enumerate(zip(self.labels, self.colors)): + plt.subplot(4, 3, i + 10) + plt.scatter(t, actual[i], color='k', marker='.') + plt.scatter(t, measuredAcc[i], color=color, marker='.') + plt.xlabel('specific force ' + label) + + def plotGroundTruthPose(self, t): + # plot ground truth pose, as well as prediction from integrated IMU measurements + actualPose = self.scenario.pose(t) + plotPose3(POSES_FIG, actualPose, 0.3) + t = actualPose.translation() + self.maxDim = max([abs(t.x()), abs(t.y()), abs(t.z()), self.maxDim]) + ax = plt.gca() + ax.set_xlim3d(-self.maxDim, self.maxDim) + ax.set_ylim3d(-self.maxDim, self.maxDim) + ax.set_zlim3d(-self.maxDim, self.maxDim) + + plt.pause(0.01) + + def run(self): + # simulate the loop + T = 12 + for i, t in enumerate(np.arange(0, T, self.dt)): + measuredOmega = self.runner.measuredAngularVelocity(t) + measuredAcc = self.runner.measuredSpecificForce(t) + if i % 25 == 0: + self.plotImu(t, measuredOmega, measuredAcc) + self.plotGroundTruthPose(t) + pim = self.runner.integrate(t, self.actualBias, True) + predictedNavState = self.runner.predict(pim, self.actualBias) + plotPose3(POSES_FIG, predictedNavState.pose(), 0.1) + + plt.ioff() + plt.show() + +if __name__ == '__main__': + PreintegrationExample().run() diff --git a/python/gtsam_examples/SFMdata.py b/python/gtsam_examples/SFMdata.py new file mode 100644 index 000000000..21a438226 --- /dev/null +++ b/python/gtsam_examples/SFMdata.py @@ -0,0 +1,32 @@ + + # A structure-from-motion example with landmarks + # - The landmarks form a 10 meter cube + # - The robot rotates around the landmarks, always facing towards the cube + +import gtsam +import numpy as np + +def createPoints(): + # Create the set of ground-truth landmarks + points = [gtsam.Point3(10.0,10.0,10.0), + gtsam.Point3(-10.0,10.0,10.0), + gtsam.Point3(-10.0,-10.0,10.0), + gtsam.Point3(10.0,-10.0,10.0), + gtsam.Point3(10.0,10.0,-10.0), + gtsam.Point3(-10.0,10.0,-10.0), + gtsam.Point3(-10.0,-10.0,-10.0), + gtsam.Point3(10.0,-10.0,-10.0)] + return points + +def createPoses(): + # Create the set of ground-truth poses + radius = 30.0 + angles = np.linspace(0,2*np.pi,8,endpoint=False) + up = gtsam.Point3(0,0,1) + target = gtsam.Point3(0,0,0) + poses = [] + for theta in angles: + position = gtsam.Point3(radius*np.cos(theta), radius*np.sin(theta), 0.0) + camera = gtsam.PinholeCameraCal3_S2.Lookat(position, target, up) + poses.append(camera.pose()) + return poses diff --git a/python/gtsam_examples/VisualISAM2Example.py b/python/gtsam_examples/VisualISAM2Example.py new file mode 100644 index 000000000..9dafa13e7 --- /dev/null +++ b/python/gtsam_examples/VisualISAM2Example.py @@ -0,0 +1,132 @@ +from __future__ import print_function + +import matplotlib.pyplot as plt +from mpl_toolkits.mplot3d import Axes3D +import numpy as np +import time # for sleep() + +import gtsam +from gtsam_examples import SFMdata +import gtsam_utils + +# shorthand symbols: +X = lambda i: int(gtsam.Symbol('x', i)) +L = lambda j: int(gtsam.Symbol('l', j)) + +def visual_ISAM2_plot(poses, points, result): + # VisualISAMPlot plots current state of ISAM2 object + # Author: Ellon Paiva + # Based on MATLAB version by: Duy Nguyen Ta and Frank Dellaert + + # Declare an id for the figure + fignum = 0 + + fig = plt.figure(fignum) + ax = fig.gca(projection='3d') + plt.cla() + + # Plot points + # Can't use data because current frame might not see all points + # marginals = Marginals(isam.getFactorsUnsafe(), isam.calculateEstimate()) # TODO - this is slow + # gtsam.plot3DPoints(result, [], marginals) + gtsam_utils.plot3DPoints(fignum, result, 'rx') + + # Plot cameras + i = 0 + while result.exists(X(i)): + pose_i = result.atPose3(X(i)) + gtsam_utils.plotPose3(fignum, pose_i, 10) + i += 1 + + # draw + ax.set_xlim3d(-40, 40) + ax.set_ylim3d(-40, 40) + ax.set_zlim3d(-40, 40) + plt.pause(1) + +def visual_ISAM2_example(): + plt.ion() + + # Define the camera calibration parameters + K = gtsam.Cal3_S2(50.0, 50.0, 0.0, 50.0, 50.0) + + # Define the camera observation noise model + measurementNoise = gtsam.noiseModel.Isotropic.Sigma(2, 1.0) # one pixel in u and v + + # Create the set of ground-truth landmarks + points = SFMdata.createPoints() + + # Create the set of ground-truth poses + poses = SFMdata.createPoses() + + # Create an iSAM2 object. Unlike iSAM1, which performs periodic batch steps to maintain proper linearization + # and efficient variable ordering, iSAM2 performs partial relinearization/reordering at each step. A parameter + # structure is available that allows the user to set various properties, such as the relinearization threshold + # and type of linear solver. For this example, we we set the relinearization threshold small so the iSAM2 result + # will approach the batch result. + parameters = gtsam.ISAM2Params() + parameters.relinearize_threshold = 0.01 + parameters.relinearize_skip = 1 + isam = gtsam.ISAM2(parameters) + + # Create a Factor Graph and Values to hold the new data + graph = gtsam.NonlinearFactorGraph() + initialEstimate = gtsam.Values() + + # Loop over the different poses, adding the observations to iSAM incrementally + for i, pose in enumerate(poses): + + # Add factors for each landmark observation + for j, point in enumerate(points): + camera = gtsam.PinholeCameraCal3_S2(pose, K) + measurement = camera.project(point) + graph.push_back(gtsam.GenericProjectionFactorCal3_S2(measurement, measurementNoise, X(i), L(j), K)) + + # Add an initial guess for the current pose + # Intentionally initialize the variables off from the ground truth + initialEstimate.insert(X(i), pose.compose(gtsam.Pose3(gtsam.Rot3.Rodrigues(-0.1, 0.2, 0.25), gtsam.Point3(0.05, -0.10, 0.20)))) + + # If this is the first iteration, add a prior on the first pose to set the coordinate frame + # and a prior on the first landmark to set the scale + # Also, as iSAM solves incrementally, we must wait until each is observed at least twice before + # adding it to iSAM. + if(i == 0): + # Add a prior on pose x0 + poseNoise = gtsam.noiseModel.Diagonal.Sigmas(np.array([0.3, 0.3, 0.3, 0.1, 0.1, 0.1])) # 30cm std on x,y,z 0.1 rad on roll,pitch,yaw + graph.push_back(gtsam.PriorFactorPose3(X(0), poses[0], poseNoise)) + + # Add a prior on landmark l0 + pointNoise = gtsam.noiseModel.Isotropic.Sigma(3, 0.1) + graph.push_back(gtsam.PriorFactorPoint3(L(0), points[0], pointNoise)) # add directly to graph + + # Add initial guesses to all observed landmarks + # Intentionally initialize the variables off from the ground truth + for j, point in enumerate(points): + initialEstimate.insert(L(j), point + gtsam.Point3(-0.25, 0.20, 0.15)) + else: + # Update iSAM with the new factors + isam.update(graph, initialEstimate) + # Each call to iSAM2 update(*) performs one iteration of the iterative nonlinear solver. + # If accuracy is desired at the expense of time, update(*) can be called additional times + # to perform multiple optimizer iterations every step. + isam.update() + currentEstimate = isam.calculate_estimate() + print("****************************************************") + print("Frame", i, ":") + for j in range(i + 1): + print(X(j), ":", currentEstimate.atPose3(X(j))) + + for j in range(len(points)): + print(L(j), ":", currentEstimate.atPoint3(L(j))) + + visual_ISAM2_plot(poses, points, currentEstimate) + + # Clear the factor graph and values for the next iteration + graph.resize(0) + initialEstimate.clear() + + plt.ioff() + plt.show() + +if __name__ == '__main__': + visual_ISAM2_example() diff --git a/python/gtsam_examples/__init__.py b/python/gtsam_examples/__init__.py new file mode 100644 index 000000000..f9d032d54 --- /dev/null +++ b/python/gtsam_examples/__init__.py @@ -0,0 +1,2 @@ +from . import SFMdata +from . import VisualISAM2Example diff --git a/python/gtsam_tests/__init__.py b/python/gtsam_tests/__init__.py new file mode 100644 index 000000000..8b1378917 --- /dev/null +++ b/python/gtsam_tests/__init__.py @@ -0,0 +1 @@ + diff --git a/python/gtsam_tests/testPoint2.py b/python/gtsam_tests/testPoint2.py new file mode 100644 index 000000000..80a6f6cbf --- /dev/null +++ b/python/gtsam_tests/testPoint2.py @@ -0,0 +1,13 @@ +import unittest +from gtsam import * + +#https://docs.python.org/2/library/unittest.html +class TestPoint2(unittest.TestCase): + def setUp(self): + self.point = Point2() + + def test_constructor(self): + pass + +if __name__ == '__main__': + unittest.main() diff --git a/python/gtsam_tests/testScenario.py b/python/gtsam_tests/testScenario.py new file mode 100644 index 000000000..e78121241 --- /dev/null +++ b/python/gtsam_tests/testScenario.py @@ -0,0 +1,32 @@ +import math +import unittest +import numpy as np + +import gtsam + +class TestScenario(unittest.TestCase): + def setUp(self): + pass + + def test_loop(self): + # Forward velocity 2m/s + # Pitch up with angular velocity 6 degree/sec (negative in FLU) + v = 2 + w = math.radians(6) + W = np.array([0, -w, 0]) + V = np.array([v, 0, 0]) + scenario = gtsam.ConstantTwistScenario(W, V) + + T = 30 + np.testing.assert_almost_equal(W, scenario.omega_b(T)) + np.testing.assert_almost_equal(V, scenario.velocity_b(T)) + np.testing.assert_almost_equal(np.cross(W, V), scenario.acceleration_b(T)) + + # R = v/w, so test if loop crests at 2*R + R = v / w + T30 = scenario.pose(T) + np.testing.assert_almost_equal(np.array([-math.pi, 0, -math.pi]), T30.rotation().xyz()) + self.assert_(gtsam.Point3(0, 0, 2 * R).equals(T30.translation())) + +if __name__ == '__main__': + unittest.main() diff --git a/python/gtsam_tests/testScenarioRunner.py b/python/gtsam_tests/testScenarioRunner.py new file mode 100644 index 000000000..2e1b47202 --- /dev/null +++ b/python/gtsam_tests/testScenarioRunner.py @@ -0,0 +1,30 @@ +import math +import unittest +import numpy as np + +import gtsam + +class TestScenarioRunner(unittest.TestCase): + def setUp(self): + self.g = 10 # simple gravity constant + + def test_loop_runner(self): + # Forward velocity 2m/s + # Pitch up with angular velocity 6 degree/sec (negative in FLU) + v = 2 + w = math.radians(6) + W = np.array([0, -w, 0]) + V = np.array([v, 0, 0]) + scenario = gtsam.ConstantTwistScenario(W, V) + + dt = 0.1 + params = gtsam.PreintegrationParams.MakeSharedU(self.g) + runner = gtsam.ScenarioRunner(gtsam.ScenarioPointer(scenario), params, dt) + + # Test specific force at time 0: a is pointing up + t = 0.0 + a = w * v + np.testing.assert_almost_equal(np.array([0, 0, a + self.g]), runner.actualSpecificForce(t)) + +if __name__ == '__main__': + unittest.main() diff --git a/python/gtsam_utils/__init__.py b/python/gtsam_utils/__init__.py new file mode 100644 index 000000000..56c55aa94 --- /dev/null +++ b/python/gtsam_utils/__init__.py @@ -0,0 +1 @@ +from .plot import * diff --git a/python/gtsam_utils/plot.py b/python/gtsam_utils/plot.py new file mode 100644 index 000000000..84a388bbb --- /dev/null +++ b/python/gtsam_utils/plot.py @@ -0,0 +1,59 @@ +import numpy as np +import matplotlib.pyplot as plt +from mpl_toolkits.mplot3d import Axes3D as _Axes3D + +def plotPoint3(fignum, point, linespec): + fig = plt.figure(fignum) + ax = fig.gca(projection='3d') + ax.plot([point.x()], [point.y()], [point.z()], linespec) + + +def plot3DPoints(fignum, values, linespec, marginals=None): + # PLOT3DPOINTS Plots the Point3's in a values, with optional covariances + # Finds all the Point3 objects in the given Values object and plots them. + # If a Marginals object is given, this function will also plot marginal + # covariance ellipses for each point. + + keys = values.keys() + + # Plot points and covariance matrices + for key in keys: + try: + p = values.atPoint3(key); + # if haveMarginals + # P = marginals.marginalCovariance(key); + # gtsam.plotPoint3(p, linespec, P); + # else + plotPoint3(fignum, p, linespec); + except RuntimeError: + continue + # I guess it's not a Point3 + +def plotPose3(fignum, pose, axisLength=0.1): + # get figure object + fig = plt.figure(fignum) + ax = fig.gca(projection='3d') + + # get rotation and translation (center) + gRp = pose.rotation().matrix() # rotation from pose to global + C = pose.translation().vector() + + # draw the camera axes + xAxis = C + gRp[:, 0] * axisLength + L = np.append(C[np.newaxis], xAxis[np.newaxis], axis=0) + ax.plot(L[:, 0], L[:, 1], L[:, 2], 'r-') + + yAxis = C + gRp[:, 1] * axisLength + L = np.append(C[np.newaxis], yAxis[np.newaxis], axis=0) + ax.plot(L[:, 0], L[:, 1], L[:, 2], 'g-') + + zAxis = C + gRp[:, 2] * axisLength + L = np.append(C[np.newaxis], zAxis[np.newaxis], axis=0) + ax.plot(L[:, 0], L[:, 1], L[:, 2], 'b-') + + # # plot the covariance + # if (nargin>2) && (~isempty(P)) + # pPp = P(4:6,4:6); % covariance matrix in pose coordinate frame + # gPp = gRp*pPp*gRp'; % convert the covariance matrix to global coordinate frame + # gtsam.covarianceEllipse3D(C,gPp); + # end diff --git a/python/handwritten/CMakeLists.txt b/python/handwritten/CMakeLists.txt new file mode 100644 index 000000000..9d4f9151a --- /dev/null +++ b/python/handwritten/CMakeLists.txt @@ -0,0 +1,30 @@ +# get subdirectories list +subdirlist(SUBDIRS ${CMAKE_CURRENT_SOURCE_DIR}) + +# get the sources needed to compile gtsam python module +set(gtsam_python_srcs "") +foreach(subdir ${SUBDIRS}) + file(GLOB ${subdir}_src "${subdir}/*.cpp") + list(APPEND gtsam_python_srcs ${${subdir}_src}) +endforeach() + +# Create the library +add_library(gtsam_python SHARED exportgtsam.cpp ${gtsam_python_srcs}) +set_target_properties(gtsam_python PROPERTIES + OUTPUT_NAME gtsam_python + SKIP_BUILD_RPATH TRUE + CLEAN_DIRECT_OUTPUT 1 +) +target_link_libraries(gtsam_python + ${Boost_PYTHON${BOOST_PYTHON_VERSION_SUFFIX_UPPERCASE}_LIBRARY} + ${PYTHON_LIBRARY} gtsam) + +# Cause the library to be output in the correct directory. +# TODO: Change below to work on different systems (currently works only with Linux) +add_custom_command( + OUTPUT ${CMAKE_BINARY_DIR}/python/gtsam/_libgtsam_python.so + DEPENDS gtsam_python + COMMAND ${CMAKE_COMMAND} -E copy $ ${CMAKE_BINARY_DIR}/python/gtsam/_libgtsam_python.so + COMMENT "Copying extension module to python/gtsam/_libgtsam_python.so" +) +add_custom_target(copy_gtsam_python_module ALL DEPENDS ${CMAKE_BINARY_DIR}/python/gtsam/_libgtsam_python.so) \ No newline at end of file diff --git a/python/handwritten/base/FastVector.cpp b/python/handwritten/base/FastVector.cpp new file mode 100644 index 000000000..1c3582813 --- /dev/null +++ b/python/handwritten/base/FastVector.cpp @@ -0,0 +1,37 @@ + /* ---------------------------------------------------------------------------- + + * 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 + + * -------------------------------------------------------------------------- */ + +/** + * @brief wraps FastVector instances to python + * @author Ellon Paiva Mendes (LAAS-CNRS) + **/ + +#include +#include + +#define NO_IMPORT_ARRAY +#include + +#include "gtsam/base/FastVector.h" +#include "gtsam/base/types.h" // for Key definition + +using namespace boost::python; +using namespace gtsam; + +void exportFastVectors(){ + + typedef FastVector KeyVector; + + class_("KeyVector") + .def(vector_indexing_suite()) + ; + +} \ No newline at end of file diff --git a/python/handwritten/exportgtsam.cpp b/python/handwritten/exportgtsam.cpp new file mode 100644 index 000000000..7e8c22a82 --- /dev/null +++ b/python/handwritten/exportgtsam.cpp @@ -0,0 +1,105 @@ +/* ---------------------------------------------------------------------------- + + * 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 + + * -------------------------------------------------------------------------- */ + +/** + * @brief exports the python module + * @author Andrew Melim + * @author Ellon Paiva Mendes (LAAS-CNRS) + **/ + +#include +#include + +#include + +// base +void exportFastVectors(); + +// geometry +void exportPoint2(); +void exportPoint3(); +void exportRot2(); +void exportRot3(); +void exportPose2(); +void exportPose3(); +void exportPinholeBaseK(); +void exportPinholeCamera(); +void exportCal3_S2(); + +// inference +void exportSymbol(); + +// linear +void exportNoiseModels(); + +// nonlinear +void exportValues(); +void exportNonlinearFactor(); +void exportNonlinearFactorGraph(); +void exportLevenbergMarquardtOptimizer(); +void exportISAM2(); + +// slam +void exportPriorFactors(); +void exportBetweenFactors(); +void exportGenericProjectionFactor(); + +// navigation +void exportImuFactor(); +void exportScenario(); + + +// Utils (or Python wrapper specific functions) +void registerNumpyEigenConversions(); + +//-----------------------------------// + +BOOST_PYTHON_MODULE(_libgtsam_python){ + + // NOTE: We need to call import_array1() instead of import_array() to support both python 2 + // and 3. The reason is that BOOST_PYTHON_MODULE puts all its contents in a function + // returning void, and import_array() is a macro that when expanded for python 3, adds + // a 'return __null' statement to that function. For more info check files: + // boost/python/module_init.hpp and numpy/__multiarray_api.h (bottom of the file). + // Should be the first thing to be done + import_array1(); + + registerNumpyEigenConversions(); + + exportFastVectors(); + + exportPoint2(); + exportPoint3(); + exportRot2(); + exportRot3(); + exportPose2(); + exportPose3(); + exportPinholeBaseK(); + exportPinholeCamera(); + exportCal3_S2(); + + exportSymbol(); + + exportNoiseModels(); + + exportValues(); + exportNonlinearFactor(); + exportNonlinearFactorGraph(); + exportLevenbergMarquardtOptimizer(); + exportISAM2(); + + exportPriorFactors(); + exportBetweenFactors(); + exportGenericProjectionFactor(); + + exportImuFactor(); + exportScenario(); +} diff --git a/python/handwritten/geometry/Cal3_S2.cpp b/python/handwritten/geometry/Cal3_S2.cpp new file mode 100644 index 000000000..339cd6a3c --- /dev/null +++ b/python/handwritten/geometry/Cal3_S2.cpp @@ -0,0 +1,62 @@ +/* ---------------------------------------------------------------------------- + + * 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 + + * -------------------------------------------------------------------------- */ + +/** + * @brief wraps Cal3_S2 class to python + * @author Ellon Paiva Mendes (LAAS-CNRS) + **/ + +#include + +#define NO_IMPORT_ARRAY +#include + +#include "gtsam/geometry/Cal3_S2.h" + +using namespace boost::python; +using namespace gtsam; + +BOOST_PYTHON_MEMBER_FUNCTION_OVERLOADS(print_overloads, Cal3_S2::print, 0, 1) +BOOST_PYTHON_MEMBER_FUNCTION_OVERLOADS(equals_overloads, Cal3_S2::equals, 1, 2) +BOOST_PYTHON_MEMBER_FUNCTION_OVERLOADS(uncalibrate_overloads, Cal3_S2::uncalibrate, 1, 3) +BOOST_PYTHON_MEMBER_FUNCTION_OVERLOADS(calibrate_overloads, Cal3_S2::calibrate, 1, 3) +BOOST_PYTHON_MEMBER_FUNCTION_OVERLOADS(between_overloads, Cal3_S2::between, 1, 3) + +// Function pointers to desambiguate Cal3_S2::calibrate calls +Point2 (Cal3_S2::*calibrate1)(const Point2 &, OptionalJacobian< 2, 5 > Dcal, OptionalJacobian< 2, 2 > Dp) const = &Cal3_S2::calibrate; +Vector3 (Cal3_S2::*calibrate2)(const Vector3 &) const = &Cal3_S2::calibrate; + +void exportCal3_S2(){ + +class_("Cal3_S2", init<>()) + .def(init()) + .def(init()) + .def(init()) + .def(init()) + .def("print", &Cal3_S2::print, print_overloads(args("s"))) + .def("equals", &Cal3_S2::equals, equals_overloads(args("q","tol"))) + .def("fx",&Cal3_S2::fx) + .def("fy",&Cal3_S2::fy) + .def("skew",&Cal3_S2::skew) + .def("px",&Cal3_S2::px) + .def("py",&Cal3_S2::py) + .def("principal_point",&Cal3_S2::principalPoint) + .def("vector",&Cal3_S2::vector) + .def("k",&Cal3_S2::K) + .def("matrix",&Cal3_S2::matrix) + .def("matrix_inverse",&Cal3_S2::matrix_inverse) + .def("uncalibrate",&Cal3_S2::uncalibrate, uncalibrate_overloads()) + .def("calibrate",calibrate1, calibrate_overloads()) + .def("calibrate",calibrate2) + .def("between",&Cal3_S2::between, between_overloads()) +; + +} \ No newline at end of file diff --git a/python/handwritten/geometry/PinholeBaseK.cpp b/python/handwritten/geometry/PinholeBaseK.cpp new file mode 100644 index 000000000..da98783e2 --- /dev/null +++ b/python/handwritten/geometry/PinholeBaseK.cpp @@ -0,0 +1,66 @@ +/* ---------------------------------------------------------------------------- + + * 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 + + * -------------------------------------------------------------------------- */ + +/** + * @brief wraps PinholeCamera classes to python + * @author Ellon Paiva Mendes (LAAS-CNRS) + **/ + +#include + +#define NO_IMPORT_ARRAY +#include + +#include "gtsam/geometry/PinholeCamera.h" +#include "gtsam/geometry/Cal3_S2.h" + + +using namespace boost::python; +using namespace gtsam; + +typedef PinholeBaseK PinholeBaseKCal3_S2; + +// Wrapper on PinholeBaseK because it has pure virtual method calibration() +struct PinholeBaseKCal3_S2Callback : PinholeBaseKCal3_S2, wrapper +{ + const Cal3_S2 & calibration () const { + return this->get_override("calibration")(); + } +}; + +BOOST_PYTHON_MEMBER_FUNCTION_OVERLOADS(project_overloads, PinholeBaseKCal3_S2::project, 2, 4) +BOOST_PYTHON_MEMBER_FUNCTION_OVERLOADS(range_overloads, PinholeBaseKCal3_S2::range, 1, 3) + +// Function pointers to desambiguate project() calls +Point2 (PinholeBaseKCal3_S2::*project1) (const Point3 &pw) const = &PinholeBaseKCal3_S2::project; +Point2 (PinholeBaseKCal3_S2::*project2) (const Point3 &pw, OptionalJacobian< 2, 6 > Dpose, OptionalJacobian< 2, 3 > Dpoint, OptionalJacobian< 2, FixedDimension::value > Dcal) const = &PinholeBaseKCal3_S2::project; +Point2 (PinholeBaseKCal3_S2::*project3) (const Unit3 &pw, OptionalJacobian< 2, 6 > Dpose, OptionalJacobian< 2, 2 > Dpoint, OptionalJacobian< 2, FixedDimension::value > Dcal) const = &PinholeBaseKCal3_S2::project; + +// function pointers to desambiguate range() calls +double (PinholeBaseKCal3_S2::*range1) (const Point3 &point, OptionalJacobian< 1, 6 > Dcamera, OptionalJacobian< 1, 3 > Dpoint) const = &PinholeBaseKCal3_S2::range; +double (PinholeBaseKCal3_S2::*range2) (const Pose3 &pose, OptionalJacobian< 1, 6 > Dcamera, OptionalJacobian< 1, 6 > Dpose) const = &PinholeBaseKCal3_S2::range; +double (PinholeBaseKCal3_S2::*range3) (const CalibratedCamera &camera, OptionalJacobian< 1, 6 > Dcamera, OptionalJacobian< 1, 6 > Dother) const = &PinholeBaseKCal3_S2::range; + +void exportPinholeBaseK(){ + + class_("PinholeBaseKCal3_S2", no_init) + .def("calibration", pure_virtual(&PinholeBaseKCal3_S2::calibration), return_value_policy()) + .def("project", project1) + .def("project", project2, project_overloads()) + .def("project", project3, project_overloads()) + .def("backproject", &PinholeBaseKCal3_S2::backproject) + .def("backproject_point_at_infinity", &PinholeBaseKCal3_S2::backprojectPointAtInfinity) + .def("range", range1, range_overloads()) + .def("range", range2, range_overloads()) + .def("range", range3, range_overloads()) + ; + +} \ No newline at end of file diff --git a/python/handwritten/geometry/PinholeCamera.cpp b/python/handwritten/geometry/PinholeCamera.cpp new file mode 100644 index 000000000..21ffcdeb7 --- /dev/null +++ b/python/handwritten/geometry/PinholeCamera.cpp @@ -0,0 +1,51 @@ +/* ---------------------------------------------------------------------------- + + * 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 + + * -------------------------------------------------------------------------- */ + +/** + * @brief wraps PinholeCamera classes to python + * @author Ellon Paiva Mendes (LAAS-CNRS) + **/ + +#include + +#define NO_IMPORT_ARRAY +#include + +#include "gtsam/geometry/PinholeCamera.h" +#include "gtsam/geometry/Cal3_S2.h" + +using namespace boost::python; +using namespace gtsam; + +typedef PinholeBaseK PinholeBaseKCal3_S2; +typedef PinholeCamera PinholeCameraCal3_S2; + +BOOST_PYTHON_MEMBER_FUNCTION_OVERLOADS(print_overloads, PinholeCameraCal3_S2::print, 0, 1) +BOOST_PYTHON_MEMBER_FUNCTION_OVERLOADS(equals_overloads, PinholeCameraCal3_S2::equals, 1, 2) +BOOST_PYTHON_FUNCTION_OVERLOADS(Lookat_overloads, PinholeCameraCal3_S2::Lookat, 3, 4) + +void exportPinholeCamera(){ + +class_ >("PinholeCameraCal3_S2", init<>()) + .def(init()) + .def(init()) + .def(init()) + .def(init()) + .def("print", &PinholeCameraCal3_S2::print, print_overloads(args("s"))) + .def("equals", &PinholeCameraCal3_S2::equals, equals_overloads(args("q","tol"))) + .def("pose", &PinholeCameraCal3_S2::pose, return_value_policy()) + // We don't need to define calibration() here because it's already defined as virtual in the base class PinholeBaseKCal3_S2 + // .def("calibration", &PinholeCameraCal3_S2::calibration, return_value_policy()) + .def("Lookat", &PinholeCameraCal3_S2::Lookat, Lookat_overloads()) + .staticmethod("Lookat") +; + +} \ No newline at end of file diff --git a/python/handwritten/geometry/Point2.cpp b/python/handwritten/geometry/Point2.cpp new file mode 100644 index 000000000..7af3f8cf6 --- /dev/null +++ b/python/handwritten/geometry/Point2.cpp @@ -0,0 +1,58 @@ +/* ---------------------------------------------------------------------------- + + * 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 + + * -------------------------------------------------------------------------- */ + +/** + * @brief wraps Point2 class to python + * @author Andrew Melim + * @author Ellon Paiva Mendes (LAAS-CNRS) + **/ + +#include + +#define NO_IMPORT_ARRAY +#include + +#include "gtsam/geometry/Point2.h" + +using namespace boost::python; +using namespace gtsam; + +BOOST_PYTHON_MEMBER_FUNCTION_OVERLOADS(print_overloads, Point2::print, 0, 1) +BOOST_PYTHON_MEMBER_FUNCTION_OVERLOADS(equals_overloads, Point2::equals, 1, 2) +BOOST_PYTHON_MEMBER_FUNCTION_OVERLOADS(compose_overloads, Point2::compose, 1, 3) + +void exportPoint2(){ + + class_("Point2", init<>()) + .def(init()) + .def(init()) + .def("identity", &Point2::identity) + .def("dist", &Point2::dist) + .def("distance", &Point2::distance) + .def("equals", &Point2::equals, equals_overloads(args("q","tol"))) + .def("norm", &Point2::norm) + .def("print", &Point2::print, print_overloads(args("s"))) + .def("unit", &Point2::unit) + .def("vector", &Point2::vector) + .def("x", &Point2::x) + .def("y", &Point2::y) + .def(self * other()) // __mult__ + .def(other() * self) // __mult__ + .def(self + self) + .def(-self) + .def(self - self) + .def(self / other()) + .def(self_ns::str(self)) + .def(repr(self)) + .def(self == self) + ; + +} \ No newline at end of file diff --git a/python/handwritten/geometry/Point3.cpp b/python/handwritten/geometry/Point3.cpp new file mode 100644 index 000000000..664b4ffda --- /dev/null +++ b/python/handwritten/geometry/Point3.cpp @@ -0,0 +1,64 @@ +/* ---------------------------------------------------------------------------- + + * 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 + + * -------------------------------------------------------------------------- */ + +/** + * @brief wraps Point3 class to python + * @author Andrew Melim + * @author Ellon Paiva Mendes (LAAS-CNRS) + **/ + +#include + +#define NO_IMPORT_ARRAY +#include + +#include "gtsam/geometry/Point3.h" + +using namespace boost::python; +using namespace gtsam; + +BOOST_PYTHON_MEMBER_FUNCTION_OVERLOADS(print_overloads, Point3::print, 0, 1) +BOOST_PYTHON_MEMBER_FUNCTION_OVERLOADS(equals_overloads, Point3::equals, 1, 2) + +void exportPoint3(){ + +class_("Point3") + .def(init<>()) + .def(init()) + .def(init()) + .def("identity", &Point3::identity) + .staticmethod("identity") + .def("add", &Point3::add) + .def("cross", &Point3::cross) + .def("dist", &Point3::dist) + .def("distance", &Point3::distance) + .def("dot", &Point3::dot) + .def("equals", &Point3::equals, equals_overloads(args("q","tol"))) + .def("norm", &Point3::norm) + .def("normalize", &Point3::normalize) + .def("print", &Point3::print, print_overloads(args("s"))) + .def("sub", &Point3::sub) + .def("vector", &Point3::vector) + .def("x", &Point3::x) + .def("y", &Point3::y) + .def("z", &Point3::z) + .def(self * other()) + .def(other() * self) + .def(self + self) + .def(-self) + .def(self - self) + .def(self / other()) + .def(self_ns::str(self)) + .def(repr(self)) + .def(self == self) +; + +} \ No newline at end of file diff --git a/python/handwritten/geometry/Pose2.cpp b/python/handwritten/geometry/Pose2.cpp new file mode 100644 index 000000000..4f402df7e --- /dev/null +++ b/python/handwritten/geometry/Pose2.cpp @@ -0,0 +1,93 @@ +/* ---------------------------------------------------------------------------- + + * 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 + + * -------------------------------------------------------------------------- */ + +/** + * @brief wraps Pose2 class to python + * @author Andrew Melim + * @author Ellon Paiva Mendes (LAAS-CNRS) + **/ + +#include + +#define NO_IMPORT_ARRAY +#include + +#include "gtsam/geometry/Pose2.h" + +using namespace boost::python; +using namespace gtsam; + +BOOST_PYTHON_MEMBER_FUNCTION_OVERLOADS(print_overloads, Pose2::print, 0, 1) +BOOST_PYTHON_MEMBER_FUNCTION_OVERLOADS(equals_overloads, Pose2::equals, 1, 2) +BOOST_PYTHON_MEMBER_FUNCTION_OVERLOADS(compose_overloads, Pose2::compose, 1, 3) +BOOST_PYTHON_MEMBER_FUNCTION_OVERLOADS(between_overloads, Pose2::between, 1, 3) +BOOST_PYTHON_MEMBER_FUNCTION_OVERLOADS(transform_to_overloads, Pose2::transform_to, 1, 3) +BOOST_PYTHON_MEMBER_FUNCTION_OVERLOADS(transform_from_overloads, Pose2::transform_from, 1, 3) +BOOST_PYTHON_MEMBER_FUNCTION_OVERLOADS(bearing_overloads, Pose2::bearing, 1, 3) +BOOST_PYTHON_MEMBER_FUNCTION_OVERLOADS(range_overloads, Pose2::range, 1, 3) + +// Manually wrap + +void exportPose2(){ + + // double (Pose2::*range1)(const Pose2&, boost::optional, boost::optional) const + // = &Pose2::range; + // double (Pose2::*range2)(const Point2&, boost::optional, boost::optional) const + // = &Pose2::range; + + // Rot2 (Pose2::*bearing1)(const Pose2&, boost::optional, boost::optional) const + // = &Pose2::bearing; + // Rot2 (Pose2::*bearing2)(const Point2&, boost::optional, boost::optional) const + // = &Pose2::bearing; + + class_("Pose2", init<>()) + .def(init()) + .def(init()) + .def(init()) + .def("print", &Pose2::print, print_overloads(args("s"))) + + .def("equals", &Pose2::equals, equals_overloads(args("pose","tol"))) + // .def("inverse", &Pose2::inverse) + // .def("compose", &Pose2::compose, compose_overloads(args("p2", "H1", "H2"))) + // .def("between", &Pose2::between, between_overloads(args("p2", "H1", "H2"))) + // .def("dim", &Pose2::dim) + // .def("retract", &Pose2::retract) + + .def("transform_to", &Pose2::transform_to, + transform_to_overloads(args("point", "H1", "H2"))) + .def("transform_from", &Pose2::transform_from, + transform_to_overloads(args("point", "H1", "H2"))) + + .def("x", &Pose2::x) + .def("y", &Pose2::y) + .def("theta", &Pose2::theta) + // See documentation on call policy for more information + // https://wiki.python.org/moin/boost.python/CallPolicy + .def("t", &Pose2::t, return_value_policy()) + .def("r", &Pose2::r, return_value_policy()) + .def("translation", &Pose2::translation, return_value_policy()) + .def("rotation", &Pose2::rotation, return_value_policy()) + + // .def("bearing", bearing1, bearing_overloads()) + // .def("bearing", bearing2, bearing_overloads()) + + // Function overload example + // .def("range", range1, range_overloads()) + // .def("range", range2, range_overloads()) + + + .def("Expmap", &Pose2::Expmap) + .staticmethod("Expmap") + + .def(self * self) // __mult__ + ; + +} \ No newline at end of file diff --git a/python/handwritten/geometry/Pose3.cpp b/python/handwritten/geometry/Pose3.cpp new file mode 100644 index 000000000..dfdfe8ad1 --- /dev/null +++ b/python/handwritten/geometry/Pose3.cpp @@ -0,0 +1,92 @@ +/* ---------------------------------------------------------------------------- + + * 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 + + * -------------------------------------------------------------------------- */ + +/** + * @brief wraps Pose3 class to python + * @author Andrew Melim + * @author Ellon Paiva Mendes (LAAS-CNRS) + **/ + +#include + +#define NO_IMPORT_ARRAY +#include + +#include "gtsam/geometry/Pose3.h" +#include "gtsam/geometry/Pose2.h" +#include "gtsam/geometry/Point3.h" +#include "gtsam/geometry/Rot3.h" + +using namespace boost::python; +using namespace gtsam; + +BOOST_PYTHON_MEMBER_FUNCTION_OVERLOADS(print_overloads, Pose3::print, 0, 1) +BOOST_PYTHON_MEMBER_FUNCTION_OVERLOADS(equals_overloads, Pose3::equals, 1, 2) +BOOST_PYTHON_MEMBER_FUNCTION_OVERLOADS(transform_to_overloads, Pose3::transform_to, 1, 3) +BOOST_PYTHON_MEMBER_FUNCTION_OVERLOADS(transform_from_overloads, Pose3::transform_from, 1, 3) +BOOST_PYTHON_MEMBER_FUNCTION_OVERLOADS(translation_overloads, Pose3::translation, 0, 1) +BOOST_PYTHON_MEMBER_FUNCTION_OVERLOADS(compose_overloads, Pose3::compose, 2, 3) +BOOST_PYTHON_MEMBER_FUNCTION_OVERLOADS(between_overloads, Pose3::between, 2, 3) +BOOST_PYTHON_MEMBER_FUNCTION_OVERLOADS(bearing_overloads, Pose3::bearing, 1, 3) +BOOST_PYTHON_MEMBER_FUNCTION_OVERLOADS(range_overloads, Pose3::range, 1, 3) + +void exportPose3(){ + + // function pointers to desambiguate transform_to() calls + Point3 (Pose3::*transform_to1)(const Point3&, OptionalJacobian< 3, 6 >, OptionalJacobian< 3, 3 > ) const = &Pose3::transform_to; + Pose3 (Pose3::*transform_to2)(const Pose3&) const = &Pose3::transform_to; + // function pointers to desambiguate compose() calls + Pose3 (Pose3::*compose1)(const Pose3 &g) const = &Pose3::compose; + Pose3 (Pose3::*compose2)(const Pose3 &g, typename Pose3::ChartJacobian, typename Pose3::ChartJacobian) const = &Pose3::compose; + // function pointers to desambiguate between() calls + Pose3 (Pose3::*between1)(const Pose3 &g) const = &Pose3::between; + Pose3 (Pose3::*between2)(const Pose3 &g, typename Pose3::ChartJacobian, typename Pose3::ChartJacobian) const = &Pose3::between; + // function pointers to desambiguate range() calls + double (Pose3::*range1)(const Point3 &, OptionalJacobian<1,6>, OptionalJacobian<1,3>) const = &Pose3::range; + double (Pose3::*range2)(const Pose3 &, OptionalJacobian<1,6>, OptionalJacobian<1,6>) const = &Pose3::range; + + class_("Pose3") + .def(init<>()) + .def(init()) + .def(init()) + .def(init()) + .def(init()) + .def(init()) + .def("print", &Pose3::print, print_overloads(args("s"))) + .def("equals", &Pose3::equals, equals_overloads(args("pose","tol"))) + .def("identity", &Pose3::identity) + .staticmethod("identity") + .def("bearing", &Pose3::bearing) + .def("matrix", &Pose3::matrix) + .def("transform_from", &Pose3::transform_from, + transform_from_overloads(args("point", "H1", "H2"))) + .def("transform_to", transform_to1, + transform_to_overloads(args("point", "H1", "H2"))) + .def("transform_to", transform_to2) + .def("x", &Pose3::x) + .def("y", &Pose3::y) + .def("z", &Pose3::z) + .def("translation", &Pose3::translation, + translation_overloads()[return_value_policy()]) + .def("rotation", &Pose3::rotation, return_value_policy()) + .def(self * self) // __mult__ + .def(self * other()) // __mult__ + .def(self_ns::str(self)) // __str__ + .def(repr(self)) // __repr__ + .def("compose", compose1) + .def("compose", compose2, compose_overloads()) + .def("between", between1) + .def("between", between2, between_overloads()) + .def("range", range1, range_overloads()) + .def("range", range2, range_overloads()) + .def("bearing", &Pose3::bearing, bearing_overloads()) + ; +} \ No newline at end of file diff --git a/python/handwritten/geometry/Rot2.cpp b/python/handwritten/geometry/Rot2.cpp new file mode 100644 index 000000000..59b4ce4e8 --- /dev/null +++ b/python/handwritten/geometry/Rot2.cpp @@ -0,0 +1,65 @@ +/* ---------------------------------------------------------------------------- + + * 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 + + * -------------------------------------------------------------------------- */ + +/** + * @brief wraps Rot2 class to python + * @author Andrew Melim + * @author Ellon Paiva Mendes (LAAS-CNRS) + **/ + +#include + +#define NO_IMPORT_ARRAY +#include + +#include "gtsam/geometry/Rot2.h" + +using namespace boost::python; +using namespace gtsam; + +BOOST_PYTHON_MEMBER_FUNCTION_OVERLOADS(print_overloads, Rot2::print, 0, 1) +BOOST_PYTHON_MEMBER_FUNCTION_OVERLOADS(equals_overloads, Rot2::equals, 1, 2) +BOOST_PYTHON_MEMBER_FUNCTION_OVERLOADS(compose_overloads, Rot2::compose, 1, 3) +BOOST_PYTHON_MEMBER_FUNCTION_OVERLOADS(relativeBearing_overloads, Rot2::relativeBearing, 1, 3) + +void exportRot2(){ + + class_("Rot2", init<>()) + .def(init()) + .def("Expmap", &Rot2::Expmap) + .staticmethod("Expmap") + .def("Logmap", &Rot2::Logmap) + .staticmethod("Logmap") + .def("atan2", &Rot2::atan2) + .staticmethod("atan2") + .def("fromAngle", &Rot2::fromAngle) + .staticmethod("fromAngle") + .def("fromCosSin", &Rot2::fromCosSin) + .staticmethod("fromCosSin") + .def("fromDegrees", &Rot2::fromDegrees) + .staticmethod("fromDegrees") + .def("identity", &Rot2::identity) + .staticmethod("identity") + .def("relativeBearing", &Rot2::relativeBearing) + .staticmethod("relativeBearing") + .def("c", &Rot2::c) + .def("degrees", &Rot2::degrees) + .def("equals", &Rot2::equals, equals_overloads(args("q","tol"))) + .def("matrix", &Rot2::matrix) + .def("print", &Rot2::print, print_overloads(args("s"))) + .def("rotate", &Rot2::rotate) + .def("s", &Rot2::s) + .def("theta", &Rot2::theta) + .def("unrotate", &Rot2::unrotate) + .def(self * self) // __mult__ + ; + +} \ No newline at end of file diff --git a/python/handwritten/geometry/Rot3.cpp b/python/handwritten/geometry/Rot3.cpp new file mode 100644 index 000000000..68643fe2c --- /dev/null +++ b/python/handwritten/geometry/Rot3.cpp @@ -0,0 +1,111 @@ +/* ---------------------------------------------------------------------------- + + * 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 + + * -------------------------------------------------------------------------- */ + +/** + * @brief wraps Rot3 class to python + * @author Andrew Melim + * @author Ellon Paiva Mendes (LAAS-CNRS) + **/ + +#include + +#define NO_IMPORT_ARRAY +#include + +#include "gtsam/geometry/Rot3.h" + +using namespace boost::python; +using namespace gtsam; + +static Rot3 Quaternion_0(const Vector4& q) +{ + return Rot3::Quaternion(q[0],q[1],q[2],q[3]); +} + +static Rot3 Quaternion_1(double w, double x, double y, double z) +{ + return Rot3::Quaternion(w,x,y,z); +} + +// Prototypes used to perform overloading +// See: http://www.boost.org/doc/libs/1_59_0/libs/python/doc/tutorial/doc/html/python/functions.html +gtsam::Rot3 (*AxisAngle_0)(const Vector3&, double) = &Rot3::AxisAngle; +gtsam::Rot3 (*AxisAngle_1)(const gtsam::Point3&, double) = &Rot3::AxisAngle; +gtsam::Rot3 (*Rodrigues_0)(const Vector3&) = &Rot3::Rodrigues; +gtsam::Rot3 (*Rodrigues_1)(double, double, double) = &Rot3::Rodrigues; +gtsam::Rot3 (*RzRyRx_0)(double, double, double) = &Rot3::RzRyRx; +gtsam::Rot3 (*RzRyRx_1)(const Vector&) = &Rot3::RzRyRx; +Vector (Rot3::*quaternion_0)() const = &Rot3::quaternion; + +BOOST_PYTHON_MEMBER_FUNCTION_OVERLOADS(print_overloads, Rot3::print, 0, 1) +BOOST_PYTHON_MEMBER_FUNCTION_OVERLOADS(equals_overloads, Rot3::equals, 1, 2) + +void exportRot3(){ + + class_("Rot3") + .def(init()) + .def(init()) + .def(init()) + .def(init()) + .def("Quaternion", Quaternion_0, arg("q"), "Creates a Rot3 from an array [w,x,y,z] representing a quaternion") + .def("Quaternion", Quaternion_1, (arg("w"),arg("x"),arg("y"),arg("z")) ) + .staticmethod("Quaternion") + .def("AxisAngle", AxisAngle_0) + .def("AxisAngle", AxisAngle_1) + .staticmethod("AxisAngle") + .def("Expmap", &Rot3::Expmap) + .staticmethod("Expmap") + .def("ExpmapDerivative", &Rot3::ExpmapDerivative) + .staticmethod("ExpmapDerivative") + .def("Logmap", &Rot3::Logmap) + .staticmethod("Logmap") + .def("LogmapDerivative", &Rot3::LogmapDerivative) + .staticmethod("LogmapDerivative") + .def("Rodrigues", Rodrigues_0) + .def("Rodrigues", Rodrigues_1) + .staticmethod("Rodrigues") + .def("Rx", &Rot3::Rx) + .staticmethod("Rx") + .def("Ry", &Rot3::Ry) + .staticmethod("Ry") + .def("Rz", &Rot3::Rz) + .staticmethod("Rz") + .def("RzRyRx", RzRyRx_0, (arg("x"),arg("y"),arg("z")), "Rotations around Z, Y, then X axes as in http://en.wikipedia.org/wiki/Rotation_matrix, counterclockwise when looking from unchanging axis" ) + .def("RzRyRx", RzRyRx_1, arg("xyz"), "Rotations around Z, Y, then X axes as in http://en.wikipedia.org/wiki/Rotation_matrix, counterclockwise when looking from unchanging axis" ) + .staticmethod("RzRyRx") + .def("identity", &Rot3::identity) + .staticmethod("identity") + .def("AdjointMap", &Rot3::AdjointMap) + .def("column", &Rot3::column) + .def("conjugate", &Rot3::conjugate) + .def("equals", &Rot3::equals, equals_overloads(args("q","tol"))) +#ifndef GTSAM_USE_QUATERNIONS + .def("localCayley", &Rot3::localCayley) + .def("retractCayley", &Rot3::retractCayley) +#endif + .def("matrix", &Rot3::matrix) + .def("print", &Rot3::print, print_overloads(args("s"))) + .def("r1", &Rot3::r1) + .def("r2", &Rot3::r2) + .def("r3", &Rot3::r3) + .def("rpy", &Rot3::rpy) + .def("slerp", &Rot3::slerp) + .def("transpose", &Rot3::transpose) + .def("xyz", &Rot3::xyz) + .def("quaternion", quaternion_0) + .def(self * self) + .def(self * other()) + .def(self * other()) + .def(self_ns::str(self)) // __str__ + .def(repr(self)) // __repr__ + ; + +} diff --git a/python/handwritten/inference/Symbol.cpp b/python/handwritten/inference/Symbol.cpp new file mode 100644 index 000000000..9fc5b74e7 --- /dev/null +++ b/python/handwritten/inference/Symbol.cpp @@ -0,0 +1,83 @@ + /* ---------------------------------------------------------------------------- + + * 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 + + * -------------------------------------------------------------------------- */ + +/** + * @brief wraps Symbol class to python + * @author Ellon Paiva Mendes (LAAS-CNRS) + **/ + +#include +#include + +#define NO_IMPORT_ARRAY +#include + +#include // for stringstream + +#include "gtsam/inference/Symbol.h" + +using namespace boost::python; +using namespace gtsam; + +BOOST_PYTHON_MEMBER_FUNCTION_OVERLOADS(print_overloads, Symbol::print, 0, 1) +BOOST_PYTHON_MEMBER_FUNCTION_OVERLOADS(equals_overloads, Symbol::equals, 1, 2) + +// Helper function to allow building a symbol from a python string and a index. +static boost::shared_ptr makeSymbol(const std::string &str, size_t j) +{ + if(str.size() > 1) + throw std::runtime_error("string argument must have one character only"); + + return boost::make_shared(str.at(0),j); +} + +// Helper function to print the symbol as "char-and-index" in python +std::string selfToString(const Symbol & self) +{ + return (std::string)self; +} + +// Helper function to convert a Symbol to int using int() cast in python +size_t selfToKey(const Symbol & self) +{ + return self.key(); +} + +// Helper function to recover symbol's unsigned char as string +std::string chrFromSelf(const Symbol & self) +{ + std::stringstream ss; + ss << self.chr(); + return ss.str(); +} + +void exportSymbol(){ + +class_ >("Symbol") + .def(init<>()) + .def(init()) + .def("__init__", make_constructor(makeSymbol)) + .def(init()) + .def("print", &Symbol::print, print_overloads(args("s"))) + .def("equals", &Symbol::equals, equals_overloads(args("q","tol"))) + .def("key", &Symbol::key) + .def("index", &Symbol::index) + .def(self < self) + .def(self == self) + .def(self == other()) + .def(self != self) + .def(self != other()) + .def("__repr__", &selfToString) + .def("__int__", &selfToKey) + .def("chr", &chrFromSelf) +; + +} \ No newline at end of file diff --git a/python/handwritten/linear/NoiseModel.cpp b/python/handwritten/linear/NoiseModel.cpp new file mode 100644 index 000000000..3453184bd --- /dev/null +++ b/python/handwritten/linear/NoiseModel.cpp @@ -0,0 +1,137 @@ +/* ---------------------------------------------------------------------------- + + * 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 + + * -------------------------------------------------------------------------- */ + +/** + * @brief wraps the noise model classes into the noiseModel module + * @author Ellon Paiva Mendes (LAAS-CNRS) + **/ + + /** TODOs Summary: + * + * TODO(Ellon): Don't know yet it it's worth/needed to add 'Wrap structs' for each of the noise models. + * I think it's only worthy if we want to access virtual the virtual functions from python. + * TODO(Ellon): Wrap non-pure virtual methods of Base on BaseWrap + */ + +#include + +#define NO_IMPORT_ARRAY +#include + +#include "gtsam/linear/NoiseModel.h" + +using namespace boost::python; +using namespace gtsam; +using namespace gtsam::noiseModel; + +// Wrap around pure virtual class Base. +// All pure virtual methods should be wrapped. Non-pure may be wrapped if we want to mimic the +// overloading through inheritance in Python. +// See: http://www.boost.org/doc/libs/1_59_0/libs/python/doc/tutorial/doc/html/python/exposing.html#python.class_virtual_functions +struct BaseCallback : Base, wrapper +{ + void print (const std::string & name="") const { + this->get_override("print")(); + } + bool equals (const Base & expected, double tol=1e-9) const { + return this->get_override("equals")(); + } + Vector whiten (const Vector & v) const { + return this->get_override("whiten")(); + } + Matrix Whiten (const Matrix & v) const { + return this->get_override("Whiten")(); + } + Vector unwhiten (const Vector & v) const { + return this->get_override("unwhiten")(); + } + double distance (const Vector & v) const { + return this->get_override("distance")(); + } + void WhitenSystem (std::vector< Matrix > &A, Vector &b) const { + this->get_override("WhitenSystem")(); + } + void WhitenSystem (Matrix &A, Vector &b) const { + this->get_override("WhitenSystem")(); + } + void WhitenSystem (Matrix &A1, Matrix &A2, Vector &b) const { + this->get_override("WhitenSystem")(); + } + void WhitenSystem (Matrix &A1, Matrix &A2, Matrix &A3, Vector &b) const { + this->get_override("WhitenSystem")(); + } + + // TODO(Ellon): Wrap non-pure virtual methods should go here. + // See: http://www.boost.org/doc/libs/1_59_0/libs/python/doc/tutorial/doc/html/python/exposing.html#python.virtual_functions_with_default_implementations + +}; + +// Overloads for named constructors. Named constructors are static, so we declare them +// using BOOST_PYTHON_FUNCTION_OVERLOADS instead of BOOST_PYTHON_MEMBER_FUNCTION_OVERLOADS +// See: http://www.boost.org/doc/libs/1_59_0/libs/python/doc/tutorial/doc/html/python/functions.html#python.default_arguments +BOOST_PYTHON_FUNCTION_OVERLOADS(Gaussian_SqrtInformation_overloads, Gaussian::SqrtInformation, 1, 2) +BOOST_PYTHON_FUNCTION_OVERLOADS(Gaussian_Information_overloads, Gaussian::Information, 1, 2) +BOOST_PYTHON_FUNCTION_OVERLOADS(Gaussian_Covariance_overloads, Gaussian::Covariance, 1, 2) +BOOST_PYTHON_FUNCTION_OVERLOADS(Diagonal_Sigmas_overloads, Diagonal::Sigmas, 1, 2) +BOOST_PYTHON_FUNCTION_OVERLOADS(Diagonal_Variances_overloads, Diagonal::Variances, 1, 2) +BOOST_PYTHON_FUNCTION_OVERLOADS(Diagonal_Precisions_overloads, Diagonal::Precisions, 1, 2) +BOOST_PYTHON_FUNCTION_OVERLOADS(Isotropic_Sigma_overloads, Isotropic::Sigma, 2, 3) +BOOST_PYTHON_FUNCTION_OVERLOADS(Isotropic_Variance_overloads, Isotropic::Variance, 2, 3) +BOOST_PYTHON_FUNCTION_OVERLOADS(Isotropic_Precision_overloads, Isotropic::Precision, 2, 3) + + +void exportNoiseModels(){ + + // Create a scope "noiseModel". See: http://isolation-nation.blogspot.fr/2008/09/packages-in-python-extension-modules.html + std::string noiseModel_name = extract(scope().attr("__name__") + ".noiseModel"); + object noiseModel_module(handle<>(borrowed(PyImport_AddModule(noiseModel_name.c_str())))); + scope().attr("noiseModel") = noiseModel_module; + scope noiseModel_scope = noiseModel_module; + + // Then export our classes in the noiseModel scope + class_("Base") + .def("print", pure_virtual(&Base::print)) + ; + + // NOTE: We should use "Base" in "bases<...>", and not "BaseCallback" (it was not clear at the begining) + class_, bases >("Gaussian", no_init) + .def("SqrtInformation",&Gaussian::SqrtInformation, Gaussian_SqrtInformation_overloads()) + .staticmethod("SqrtInformation") + .def("Information",&Gaussian::Information, Gaussian_Information_overloads()) + .staticmethod("Information") + .def("Covariance",&Gaussian::Covariance, Gaussian_Covariance_overloads()) + .staticmethod("Covariance") + ; + + class_, bases >("Diagonal", no_init) + .def("Sigmas",&Diagonal::Sigmas, Diagonal_Sigmas_overloads()) + .staticmethod("Sigmas") + .def("Variances",&Diagonal::Variances, Diagonal_Variances_overloads()) + .staticmethod("Variances") + .def("Precisions",&Diagonal::Precisions, Diagonal_Precisions_overloads()) + .staticmethod("Precisions") + ; + + class_, bases >("Isotropic", no_init) + .def("Sigma",&Isotropic::Sigma, Isotropic_Sigma_overloads()) + .staticmethod("Sigma") + .def("Variance",&Isotropic::Variance, Isotropic_Variance_overloads()) + .staticmethod("Variance") + .def("Precision",&Isotropic::Precision, Isotropic_Precision_overloads()) + .staticmethod("Precision") + ; + + class_, bases >("Unit", no_init) + .def("Create",&Unit::Create) + .staticmethod("Create") + ; + +} \ No newline at end of file diff --git a/python/handwritten/navigation/ImuFactor.cpp b/python/handwritten/navigation/ImuFactor.cpp new file mode 100644 index 000000000..c947ae9ee --- /dev/null +++ b/python/handwritten/navigation/ImuFactor.cpp @@ -0,0 +1,94 @@ +/* ---------------------------------------------------------------------------- + + * 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 + + * -------------------------------------------------------------------------- */ + +/** + * @brief wraps ConstantTwistScenario class to python + * @author Frank Dellaert + **/ + +#include + +#define NO_IMPORT_ARRAY +#include + +#include "gtsam/navigation/ImuFactor.h" + +using namespace boost::python; +using namespace gtsam; + +typedef gtsam::OptionalJacobian<3, 9> OptionalJacobian39; +typedef gtsam::OptionalJacobian<9, 6> OptionalJacobian96; +typedef gtsam::OptionalJacobian<9, 9> OptionalJacobian9; + +BOOST_PYTHON_MEMBER_FUNCTION_OVERLOADS(print_overloads, print, 0, 1) +BOOST_PYTHON_MEMBER_FUNCTION_OVERLOADS(attitude_overloads, attitude, 0, 1) +BOOST_PYTHON_MEMBER_FUNCTION_OVERLOADS(position_overloads, position, 0, 1) +BOOST_PYTHON_MEMBER_FUNCTION_OVERLOADS(velocity_overloads, velocity, 0, 1) + +void exportImuFactor() { + class_("OptionalJacobian39", init<>()); + class_("OptionalJacobian96", init<>()); + class_("OptionalJacobian9", init<>()); + + class_("NavState", init<>()) + // TODO(frank): overload with jacobians + .def("print", &NavState::print, print_overloads()) + .def("attitude", &NavState::attitude, + attitude_overloads()[return_value_policy()]) + .def("position", &NavState::position, + position_overloads()[return_value_policy()]) + .def("velocity", &NavState::velocity, + velocity_overloads()[return_value_policy()]) + .def(repr(self)) + .def("pose", &NavState::pose); + + class_("ConstantBias", init<>()) + .def(init()) + .def(repr(self)); + + class_>( + "PreintegrationParams", init()) + .def_readwrite("gyroscopeCovariance", + &PreintegrationParams::gyroscopeCovariance) + .def_readwrite("omegaCoriolis", &PreintegrationParams::omegaCoriolis) + .def_readwrite("body_P_sensor", &PreintegrationParams::body_P_sensor) + .def_readwrite("accelerometerCovariance", + &PreintegrationParams::accelerometerCovariance) + .def_readwrite("integrationCovariance", + &PreintegrationParams::integrationCovariance) + .def_readwrite("use2ndOrderCoriolis", + &PreintegrationParams::use2ndOrderCoriolis) + .def_readwrite("n_gravity", &PreintegrationParams::n_gravity) + + .def("MakeSharedD", &PreintegrationParams::MakeSharedD) + .staticmethod("MakeSharedD") + .def("MakeSharedU", &PreintegrationParams::MakeSharedU) + .staticmethod("MakeSharedU"); + + class_( + "PreintegratedImuMeasurements", + init&, + const imuBias::ConstantBias&>()) + .def(repr(self)) + .def("predict", &PreintegratedImuMeasurements::predict) + .def("computeError", &PreintegratedImuMeasurements::computeError) + .def("resetIntegration", &PreintegratedImuMeasurements::resetIntegration) + .def("integrateMeasurement", + &PreintegratedImuMeasurements::integrateMeasurement) + .def("preintMeasCov", &PreintegratedImuMeasurements::preintMeasCov); + + // NOTE(frank): Abstract classes need boost::noncopyable + class_, boost::shared_ptr>( + "ImuFactor") + .def("error", &ImuFactor::error) + .def(init()) + .def(repr(self)); +} diff --git a/python/handwritten/navigation/Scenario.cpp b/python/handwritten/navigation/Scenario.cpp new file mode 100644 index 000000000..e11f04a57 --- /dev/null +++ b/python/handwritten/navigation/Scenario.cpp @@ -0,0 +1,64 @@ +/* ---------------------------------------------------------------------------- + + * 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 + + * -------------------------------------------------------------------------- */ + +/** + * @brief wraps ConstantTwistScenario class to python + * @author Frank Dellaert + **/ + +#include + +#define NO_IMPORT_ARRAY +#include + +#include "gtsam/navigation/ScenarioRunner.h" + +using namespace boost::python; +using namespace gtsam; + +// Create const Scenario pointer from ConstantTwistScenario +static const Scenario* ScenarioPointer(const ConstantTwistScenario& scenario) { + return static_cast(&scenario); +} + +void exportScenario() { + // NOTE(frank): Abstract classes need boost::noncopyable + class_("Scenario", no_init); + + // TODO(frank): figure out how to do inheritance + class_("ConstantTwistScenario", + init()) + .def("pose", &Scenario::pose) + .def("omega_b", &Scenario::omega_b) + .def("velocity_n", &Scenario::velocity_n) + .def("acceleration_n", &Scenario::acceleration_n) + .def("navState", &Scenario::navState) + .def("rotation", &Scenario::rotation) + .def("velocity_b", &Scenario::velocity_b) + .def("acceleration_b", &Scenario::acceleration_b); + + // NOTE(frank): https://wiki.python.org/moin/boost.python/CallPolicy + def("ScenarioPointer", &ScenarioPointer, + return_value_policy()); + + class_( + "ScenarioRunner", + init&, + double, const imuBias::ConstantBias&>()) + .def("actualSpecificForce", &ScenarioRunner::actualSpecificForce) + .def("measuredAngularVelocity", &ScenarioRunner::measuredAngularVelocity) + .def("measuredSpecificForce", &ScenarioRunner::measuredSpecificForce) + .def("imuSampleTime", &ScenarioRunner::imuSampleTime, + return_value_policy()) + .def("integrate", &ScenarioRunner::integrate) + .def("predict", &ScenarioRunner::predict) + .def("estimateCovariance", &ScenarioRunner::estimateCovariance); +} diff --git a/python/handwritten/nonlinear/ISAM2.cpp b/python/handwritten/nonlinear/ISAM2.cpp new file mode 100644 index 000000000..f80c5df99 --- /dev/null +++ b/python/handwritten/nonlinear/ISAM2.cpp @@ -0,0 +1,67 @@ +/* ---------------------------------------------------------------------------- + + * 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 + + * -------------------------------------------------------------------------- */ + +/** + * @brief exports ISAM2 class to python + * @author Ellon Paiva Mendes (LAAS-CNRS) + **/ + +#include + +#define NO_IMPORT_ARRAY +#include + +#include "gtsam/nonlinear/ISAM2.h" +#include "gtsam/geometry/Pose3.h" + +using namespace boost::python; +using namespace gtsam; + +BOOST_PYTHON_MEMBER_FUNCTION_OVERLOADS(update_overloads, ISAM2::update, 0, 7) + +void exportISAM2(){ + +// TODO(Ellon): Export all properties of ISAM2Params +class_("ISAM2Params") + .add_property("relinearize_skip", &ISAM2Params::getRelinearizeSkip, &ISAM2Params::setRelinearizeSkip) + .add_property("enable_relinearization", &ISAM2Params::isEnableRelinearization, &ISAM2Params::setEnableRelinearization) + .add_property("evaluate_non_linear_error", &ISAM2Params::isEvaluateNonlinearError, &ISAM2Params::setEvaluateNonlinearError) + .add_property("factorization", &ISAM2Params::getFactorization, &ISAM2Params::setFactorization) + .add_property("cache_linearized_factors", &ISAM2Params::isCacheLinearizedFactors, &ISAM2Params::setCacheLinearizedFactors) + .add_property("enable_detailed_results", &ISAM2Params::isEnableDetailedResults, &ISAM2Params::setEnableDetailedResults) + .add_property("enable_partial_linearization_check", &ISAM2Params::isEnablePartialRelinearizationCheck, &ISAM2Params::setEnablePartialRelinearizationCheck) + // TODO(Ellon): Check if it works with FastMap; Implement properly if it doesn't. + .add_property("relinearization_threshold", &ISAM2Params::getRelinearizeThreshold, &ISAM2Params::setRelinearizeThreshold) + // TODO(Ellon): Wrap the following setters/getters: + // void setOptimizationParams (OptimizationParams optimizationParams) + // OptimizationParams getOptimizationParams () const + // void setKeyFormatter (KeyFormatter keyFormatter) + // KeyFormatter getKeyFormatter () const + // GaussianFactorGraph::Eliminate getEliminationFunction () const +; + +// TODO(Ellon): Export useful methods/properties of ISAM2Result +class_("ISAM2Result") +; + +// Function pointers for overloads in ISAM2 +Values (ISAM2::*calculateEstimate_0)() const = &ISAM2::calculateEstimate; + +class_("ISAM2") + .def(init()) + // TODO(Ellon): wrap all optional values of update + .def("update",&ISAM2::update, update_overloads()) + .def("calculate_estimate", calculateEstimate_0) + .def("calculate_pose3_estimate", &ISAM2::calculateEstimate, (arg("self"), arg("key")) ) + .def("value_exists", &ISAM2::valueExists) +; + +} \ No newline at end of file diff --git a/python/handwritten/nonlinear/LevenbergMarquardtOptimizer.cpp b/python/handwritten/nonlinear/LevenbergMarquardtOptimizer.cpp new file mode 100644 index 000000000..7c7cdf3cc --- /dev/null +++ b/python/handwritten/nonlinear/LevenbergMarquardtOptimizer.cpp @@ -0,0 +1,27 @@ +#include + +#define NO_IMPORT_ARRAY +#include + +#include + +using namespace boost::python; +using namespace gtsam; + +void exportLevenbergMarquardtOptimizer(){ + class_("LevenbergMarquardtParams", init<>()) + .def("setDiagonalDamping", &LevenbergMarquardtParams::setDiagonalDamping) + .def("setlambdaFactor", &LevenbergMarquardtParams::setlambdaFactor) + .def("setlambdaInitial", &LevenbergMarquardtParams::setlambdaInitial) + .def("setlambdaLowerBound", &LevenbergMarquardtParams::setlambdaLowerBound) + .def("setlambdaUpperBound", &LevenbergMarquardtParams::setlambdaUpperBound) + .def("setLogFile", &LevenbergMarquardtParams::setLogFile) + .def("setUseFixedLambdaFactor", &LevenbergMarquardtParams::setUseFixedLambdaFactor) + .def("setVerbosityLM", &LevenbergMarquardtParams::setVerbosityLM) + ; + + class_("LevenbergMarquardtOptimizer", + init()) + .def("optimize", &LevenbergMarquardtOptimizer::optimize, return_value_policy()) + ; +} diff --git a/python/handwritten/nonlinear/NonlinearFactor.cpp b/python/handwritten/nonlinear/NonlinearFactor.cpp new file mode 100644 index 000000000..9a130d8e9 --- /dev/null +++ b/python/handwritten/nonlinear/NonlinearFactor.cpp @@ -0,0 +1,49 @@ +/* ---------------------------------------------------------------------------- + + * 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 + + * -------------------------------------------------------------------------- */ + +/** + * @brief exports virtual class NonlinearFactor to python + * @author Ellon Paiva Mendes (LAAS-CNRS) + **/ + +#include + +#define NO_IMPORT_ARRAY +#include + +#include "gtsam/nonlinear/NonlinearFactor.h" + +using namespace boost::python; +using namespace gtsam; + +// Wrap around pure virtual class NonlinearFactor. +// All pure virtual methods should be wrapped. Non-pure may be wrapped if we want to mimic the +// overloading through inheritance in Python. +// See: http://www.boost.org/doc/libs/1_59_0/libs/python/doc/tutorial/doc/html/python/exposing.html#python.class_virtual_functions +struct NonlinearFactorCallback : NonlinearFactor, wrapper +{ + double error (const Values & values) const { + return this->get_override("error")(values); + } + size_t dim () const { + return this->get_override("dim")(); + } + boost::shared_ptr linearize(const Values & values) const { + return this->get_override("linearize")(values); + } +}; + +void exportNonlinearFactor(){ + + class_("NonlinearFactor") + ; + +} \ No newline at end of file diff --git a/python/handwritten/nonlinear/NonlinearFactorGraph.cpp b/python/handwritten/nonlinear/NonlinearFactorGraph.cpp new file mode 100644 index 000000000..4ba4ba008 --- /dev/null +++ b/python/handwritten/nonlinear/NonlinearFactorGraph.cpp @@ -0,0 +1,56 @@ +/* ---------------------------------------------------------------------------- + + * 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 + + * -------------------------------------------------------------------------- */ + +/** + * @brief exports NonlinearFactorGraph class to python + * @author Andrew Melim + * @author Ellon Paiva Mendes (LAAS-CNRS) + **/ + +#include + +#define NO_IMPORT_ARRAY +#include + +#include "gtsam/nonlinear/NonlinearFactorGraph.h" +#include "gtsam/nonlinear/NonlinearFactor.h" + +using namespace boost::python; +using namespace gtsam; + +BOOST_PYTHON_MEMBER_FUNCTION_OVERLOADS(print_overloads, NonlinearFactorGraph::print, 0, 1); + +boost::shared_ptr getNonlinearFactor( + const NonlinearFactorGraph& graph, size_t idx) { + auto p = boost::dynamic_pointer_cast(graph.at(idx)); + if (!p) throw std::runtime_error("No NonlinearFactor at requested index"); + return p; +}; + +void exportNonlinearFactorGraph(){ + + typedef NonlinearFactorGraph::sharedFactor sharedFactor; + + void (NonlinearFactorGraph::*push_back1)(const sharedFactor&) = &NonlinearFactorGraph::push_back; + void (NonlinearFactorGraph::*add1)(const sharedFactor&) = &NonlinearFactorGraph::add; + + class_("NonlinearFactorGraph", init<>()) + .def("size",&NonlinearFactorGraph::size) + .def("push_back", push_back1) + .def("add", add1) + .def("resize", &NonlinearFactorGraph::resize) + .def("empty", &NonlinearFactorGraph::empty) + .def("print", &NonlinearFactorGraph::print, print_overloads(args("s"))) + ; + + def("getNonlinearFactor", getNonlinearFactor); + +} diff --git a/python/handwritten/nonlinear/Values.cpp b/python/handwritten/nonlinear/Values.cpp new file mode 100644 index 000000000..84e82f376 --- /dev/null +++ b/python/handwritten/nonlinear/Values.cpp @@ -0,0 +1,80 @@ +/* ---------------------------------------------------------------------------- + + * 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 + + * -------------------------------------------------------------------------- */ + +/** + * @brief wraps Values class to python + * @author Ellon Paiva Mendes (LAAS-CNRS) + **/ + +#include + +#define NO_IMPORT_ARRAY +#include + +#include "gtsam/nonlinear/Values.h" +#include "gtsam/geometry/Point2.h" +#include "gtsam/geometry/Rot2.h" +#include "gtsam/geometry/Pose2.h" +#include "gtsam/geometry/Point3.h" +#include "gtsam/geometry/Rot3.h" +#include "gtsam/geometry/Pose3.h" +#include "gtsam/navigation/ImuBias.h" + +using namespace boost::python; +using namespace gtsam; + +BOOST_PYTHON_MEMBER_FUNCTION_OVERLOADS(print_overloads, Values::print, 0, 1); + +void exportValues(){ + + typedef imuBias::ConstantBias Bias; + + bool (Values::*exists1)(Key) const = &Values::exists; + void (Values::*insert_point2)(Key, const gtsam::Point2&) = &Values::insert; + void (Values::*insert_rot2) (Key, const gtsam::Rot2&) = &Values::insert; + void (Values::*insert_pose2) (Key, const gtsam::Pose2&) = &Values::insert; + void (Values::*insert_point3)(Key, const gtsam::Point3&) = &Values::insert; + void (Values::*insert_rot3) (Key, const gtsam::Rot3&) = &Values::insert; + void (Values::*insert_pose3) (Key, const gtsam::Pose3&) = &Values::insert; + void (Values::*insert_bias) (Key, const Bias&) = &Values::insert; + void (Values::*insert_vector3) (Key, const gtsam::Vector3&) = &Values::insert; + + class_("Values", init<>()) + .def(init()) + .def("clear", &Values::clear) + .def("dim", &Values::dim) + .def("empty", &Values::empty) + .def("equals", &Values::equals) + .def("erase", &Values::erase) + .def("insert_fixed", &Values::insertFixed) + .def("print", &Values::print, print_overloads(args("s"))) + .def("size", &Values::size) + .def("swap", &Values::swap) + .def("insert", insert_point2) + .def("insert", insert_rot2) + .def("insert", insert_pose2) + .def("insert", insert_point3) + .def("insert", insert_rot3) + .def("insert", insert_pose3) + .def("insert", insert_bias) + .def("insert", insert_vector3) + .def("atPoint2", &Values::at, return_value_policy()) + .def("atRot2", &Values::at, return_value_policy()) + .def("atPose2", &Values::at, return_value_policy()) + .def("atPoint3", &Values::at, return_value_policy()) + .def("atRot3", &Values::at, return_value_policy()) + .def("atPose3", &Values::at, return_value_policy()) + .def("atConstantBias", &Values::at, return_value_policy()) + .def("atVector3", &Values::at, return_value_policy()) + .def("exists", exists1) + .def("keys", &Values::keys) + ; +} diff --git a/python/handwritten/slam/BearingFactor.cpp b/python/handwritten/slam/BearingFactor.cpp new file mode 100644 index 000000000..2d4688bde --- /dev/null +++ b/python/handwritten/slam/BearingFactor.cpp @@ -0,0 +1,16 @@ +#include + +#define NO_IMPORT_ARRAY +#include + +#include + +using namespace boost::python; +using namespace gtsam; + +using namespace std; + +template +void exportBearingFactor(const std::string& name) { + class_(name, init<>()); +} diff --git a/python/handwritten/slam/BetweenFactor.cpp b/python/handwritten/slam/BetweenFactor.cpp new file mode 100644 index 000000000..0e0949fb5 --- /dev/null +++ b/python/handwritten/slam/BetweenFactor.cpp @@ -0,0 +1,57 @@ +/* ---------------------------------------------------------------------------- + + * 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 + + * -------------------------------------------------------------------------- */ + +/** + * @brief wraps BetweenFactor for several values to python + * @author Andrew Melim + * @author Ellon Paiva Mendes (LAAS-CNRS) + **/ + +#include + +#define NO_IMPORT_ARRAY +#include + +#include "gtsam/slam/BetweenFactor.h" +#include "gtsam/geometry/Point2.h" +#include "gtsam/geometry/Rot2.h" +#include "gtsam/geometry/Pose2.h" +#include "gtsam/geometry/Point3.h" +#include "gtsam/geometry/Rot3.h" +#include "gtsam/geometry/Pose3.h" + +using namespace boost::python; +using namespace gtsam; + +using namespace std; + +// template +// void exportBetweenFactor(const std::string& name){ +// class_(name, init<>()) +// .def(init()) +// ; +// } + +#define BETWEENFACTOR(T) \ + class_< BetweenFactor, bases, boost::shared_ptr< BetweenFactor > >("BetweenFactor"#T) \ + .def(init()) \ + .def("measured", &BetweenFactor::measured, return_internal_reference<>()) \ +; + +void exportBetweenFactors() +{ + BETWEENFACTOR(Point2) + BETWEENFACTOR(Rot2) + BETWEENFACTOR(Pose2) + BETWEENFACTOR(Point3) + BETWEENFACTOR(Rot3) + BETWEENFACTOR(Pose3) +} diff --git a/python/handwritten/slam/GenericProjectionFactor.cpp b/python/handwritten/slam/GenericProjectionFactor.cpp new file mode 100644 index 000000000..dd932ccd4 --- /dev/null +++ b/python/handwritten/slam/GenericProjectionFactor.cpp @@ -0,0 +1,54 @@ +/* ---------------------------------------------------------------------------- + + * 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 + + * -------------------------------------------------------------------------- */ + +/** + * @brief wraps GenericProjectionFactor for several values to python + * @author Ellon Paiva Mendes (LAAS-CNRS) + **/ + +#include + +#define NO_IMPORT_ARRAY +#include + +#include "gtsam/slam/ProjectionFactor.h" +#include "gtsam/geometry/Pose3.h" +#include "gtsam/geometry/Point3.h" +#include "gtsam/geometry/Cal3_S2.h" + +using namespace boost::python; +using namespace gtsam; + +using namespace std; + +typedef GenericProjectionFactor GenericProjectionFactorCal3_S2; + +BOOST_PYTHON_MEMBER_FUNCTION_OVERLOADS(print_overloads, GenericProjectionFactorCal3_S2::print, 0, 1) +BOOST_PYTHON_MEMBER_FUNCTION_OVERLOADS(equals_overloads, GenericProjectionFactorCal3_S2::equals, 1, 2) +BOOST_PYTHON_MEMBER_FUNCTION_OVERLOADS(evaluateError_overloads, GenericProjectionFactorCal3_S2::evaluateError, 2, 4) + +void exportGenericProjectionFactor() +{ + + class_ >("GenericProjectionFactorCal3_S2", init<>()) + .def(init &, optional >()) + .def(init &, bool, bool, optional >()) + .def("print", &GenericProjectionFactorCal3_S2::print, print_overloads(args("s"))) + .def("equals", &GenericProjectionFactorCal3_S2::equals, equals_overloads(args("q","tol"))) + .def("evaluate_error", &GenericProjectionFactorCal3_S2::evaluateError, evaluateError_overloads()) + .def("measured", &GenericProjectionFactorCal3_S2::measured, return_value_policy()) + // TODO(Ellon): Find the right return policy when returning a 'const shared_ptr<...> &' + // .def("calibration", &GenericProjectionFactorCal3_S2::calibration, return_value_policy()) + .def("verbose_cheirality", &GenericProjectionFactorCal3_S2::verboseCheirality) + .def("throw_cheirality", &GenericProjectionFactorCal3_S2::throwCheirality) + ; + +} diff --git a/python/handwritten/slam/PriorFactor.cpp b/python/handwritten/slam/PriorFactor.cpp new file mode 100644 index 000000000..3ada91f43 --- /dev/null +++ b/python/handwritten/slam/PriorFactor.cpp @@ -0,0 +1,58 @@ +/* ---------------------------------------------------------------------------- + + * 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 + + * -------------------------------------------------------------------------- */ + +/** + * @brief wraps PriorFactor for several values to python + * @author Andrew Melim + * @author Ellon Paiva Mendes (LAAS-CNRS) + **/ + +#include + +#define NO_IMPORT_ARRAY +#include + +#include "gtsam/slam/PriorFactor.h" +#include "gtsam/geometry/Point2.h" +#include "gtsam/geometry/Rot2.h" +#include "gtsam/geometry/Pose2.h" +#include "gtsam/geometry/Point3.h" +#include "gtsam/geometry/Rot3.h" +#include "gtsam/geometry/Pose3.h" + +using namespace boost::python; +using namespace gtsam; + +using namespace std; + +// template< class FACTOR, class VALUE > +// void exportPriorFactor(const std::string& name){ +// class_< FACTOR >(name.c_str(), init<>()) +// .def(init< Key, VALUE&, SharedNoiseModel >()) +// ; +// } + +#define PRIORFACTOR(VALUE) \ + class_< PriorFactor, bases, boost::shared_ptr< PriorFactor > >("PriorFactor"#VALUE) \ + .def(init()) \ + .def("prior", &PriorFactor::prior, return_internal_reference<>()) \ +; + +void exportPriorFactors() +{ + PRIORFACTOR(Point2) + PRIORFACTOR(Rot2) + PRIORFACTOR(Pose2) + PRIORFACTOR(Point3) + PRIORFACTOR(Rot3) + PRIORFACTOR(Pose3) + PRIORFACTOR(Vector3) +} diff --git a/python/handwritten/utils/NumpyEigen.cpp b/python/handwritten/utils/NumpyEigen.cpp new file mode 100644 index 000000000..d7cebe7ad --- /dev/null +++ b/python/handwritten/utils/NumpyEigen.cpp @@ -0,0 +1,54 @@ + /* ---------------------------------------------------------------------------- + + * 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 + + * -------------------------------------------------------------------------- */ + +/** + * @brief register conversion matrix between numpy and Eigen + * @author Ellon Paiva Mendes (LAAS-CNRS) + **/ + +#include + +#define NO_IMPORT_ARRAY +#include + +#include "gtsam/base/Matrix.h" +#include "gtsam/base/Vector.h" + +using namespace boost::python; +using namespace gtsam; + +void registerNumpyEigenConversions() +{ + // NOTE: import array should be called only in the cpp defining the module + // import_array(); + NumpyEigenConverter::register_converter(); + NumpyEigenConverter::register_converter(); + NumpyEigenConverter::register_converter(); + NumpyEigenConverter::register_converter(); + NumpyEigenConverter::register_converter(); + NumpyEigenConverter::register_converter(); + NumpyEigenConverter::register_converter(); + NumpyEigenConverter::register_converter(); + NumpyEigenConverter::register_converter(); + NumpyEigenConverter::register_converter(); + NumpyEigenConverter::register_converter(); + + NumpyEigenConverter::register_converter(); + NumpyEigenConverter::register_converter(); + NumpyEigenConverter::register_converter(); + NumpyEigenConverter::register_converter(); + NumpyEigenConverter::register_converter(); + NumpyEigenConverter::register_converter(); + NumpyEigenConverter::register_converter(); + NumpyEigenConverter::register_converter(); + NumpyEigenConverter::register_converter(); + +} diff --git a/python/include/numpy_eigen/NumpyEigenConverter.hpp b/python/include/numpy_eigen/NumpyEigenConverter.hpp new file mode 100755 index 000000000..4cf16a974 --- /dev/null +++ b/python/include/numpy_eigen/NumpyEigenConverter.hpp @@ -0,0 +1,334 @@ +/** + * @file NumpyEigenConverter.hpp + * @author Paul Furgale + * @date Fri Feb 4 11:17:25 2011 + * + * @brief Classes to support conversion from numpy arrays in Python + * to Eigen3 matrices in c++ + * + * + */ + +#ifndef NUMPY_EIGEN_CONVERTER_HPP +#define NUMPY_EIGEN_CONVERTER_HPP + +#include +//#include + +#include "numpy/numpyconfig.h" +#ifdef NPY_1_7_API_VERSION +#define NPY_NO_DEPRECATED_API NPY_1_7_API_VERSION +#define NPE_PY_ARRAY_OBJECT PyArrayObject +#else +//TODO Remove this as soon as support for Numpy version before 1.7 is dropped +#define NPE_PY_ARRAY_OBJECT PyObject +#endif + +#define PY_ARRAY_UNIQUE_SYMBOL NP_Eigen_AS +#include + +#include "type_traits.hpp" +#include +#include "copy_routines.hpp" + + + +/** + * @class NumpyEigenConverter + * @tparam the Eigen3 matrix type this class is specialized for + * + * adapted from http://misspent.wordpress.com/2009/09/27/how-to-write-boost-python-converters/ + * General help available http://docs.scipy.org/doc/numpy/reference/c-api.array.html + * + * To use: + * + * #include + * + * + * BOOST_PYTHON_MODULE(libmy_module_python) + * { + * // The converters will cause a segfault unless import_array() is called before the first one + * import_array(); + * NumpyEigenConverter >::register_converter(); + * NumpyEigenConverter >::register_converter(); + * } + * + */ +template +struct NumpyEigenConverter +{ + + typedef EIGEN_MATRIX_T matrix_t; + typedef typename matrix_t::Scalar scalar_t; + + enum { + RowsAtCompileTime = matrix_t::RowsAtCompileTime, + ColsAtCompileTime = matrix_t::ColsAtCompileTime, + MaxRowsAtCompileTime = matrix_t::MaxRowsAtCompileTime, + MaxColsAtCompileTime = matrix_t::MaxColsAtCompileTime, + NpyType = TypeToNumPy::NpyType, + //Flags = ei_compute_matrix_flags<_Scalar, _Rows, _Cols, _Options, _MaxRows, _MaxCols>::ret, + //CoeffReadCost = NumTraits::ReadCost, + Options = matrix_t::Options + //InnerStrideAtCompileTime = 1, + //OuterStrideAtCompileTime = (Options&RowMajor) ? ColsAtCompileTime : RowsAtCompileTime + }; + + static std::string castSizeOption(int option) + { + if(option == Eigen::Dynamic) + return "Dynamic"; + else + return boost::lexical_cast(option); + } + + static std::string toString() + { + return std::string() + "Eigen::Matrix<" + TypeToNumPy::typeString() + ", " + + castSizeOption(RowsAtCompileTime) + ", " + + castSizeOption(ColsAtCompileTime) + ", " + + boost::lexical_cast((int)Options) + ", " + + castSizeOption(MaxRowsAtCompileTime) + ", " + + castSizeOption(MaxColsAtCompileTime) + ">"; + } + + // The "Convert from C to Python" API + static PyObject * convert(const matrix_t & M) + { + PyObject * P = NULL; + if(RowsAtCompileTime == 1 || ColsAtCompileTime == 1) + { + // Create a 1D array + npy_intp dimensions[1]; + dimensions[0] = M.size(); + P = PyArray_SimpleNew(1, dimensions, TypeToNumPy::NpyType); + numpyTypeDemuxer< CopyEigenToNumpyVector >(&M, reinterpret_cast(P)); + } + else + { + // create a 2D array. + npy_intp dimensions[2]; + dimensions[0] = M.rows(); + dimensions[1] = M.cols(); + P = PyArray_SimpleNew(2, dimensions, TypeToNumPy::NpyType); + numpyTypeDemuxer< CopyEigenToNumpyMatrix >(&M, reinterpret_cast(P)); + } + + // incrementing the reference seems to cause a memory leak. + // boost::python::incref(P); + // This agrees with the sample code found here: + // http://mail.python.org/pipermail/cplusplus-sig/2008-October/013825.html + return P; + } + + static bool isDimensionValid(int requestedSize, int sizeAtCompileTime, int maxSizeAtCompileTime) + { + bool valid = true; + if(sizeAtCompileTime == Eigen::Dynamic) + { + // Check for dynamic fixed size + // http://eigen.tuxfamily.org/dox-devel/TutorialMatrixClass.html#TutorialMatrixOptTemplParams + if(!(maxSizeAtCompileTime == Eigen::Dynamic || requestedSize <= maxSizeAtCompileTime)) + { + valid = false; + } + } + else if(sizeAtCompileTime != requestedSize) + { + valid = false; + } + return valid; + } + + static void checkMatrixSizes(NPE_PY_ARRAY_OBJECT * obj_ptr) + { + int rows = PyArray_DIM(obj_ptr, 0); + int cols = PyArray_DIM(obj_ptr, 1); + + bool rowsValid = isDimensionValid(rows, RowsAtCompileTime, MaxRowsAtCompileTime); + bool colsValid = isDimensionValid(cols, ColsAtCompileTime, MaxColsAtCompileTime); + if(!rowsValid || !colsValid) + { + THROW_TYPE_ERROR("Can not convert " << npyArrayTypeString(obj_ptr) << " to " << toString() + << ". Mismatched sizes."); + } + } + + static void checkRowVectorSizes(NPE_PY_ARRAY_OBJECT * obj_ptr, int cols) + { + if(!isDimensionValid(cols, ColsAtCompileTime, MaxColsAtCompileTime)) + { + THROW_TYPE_ERROR("Can not convert " << npyArrayTypeString(obj_ptr) << " to " << toString() + << ". Mismatched sizes."); + } + } + + static void checkColumnVectorSizes(NPE_PY_ARRAY_OBJECT * obj_ptr, int rows) + { + // Check if the type can accomidate one column. + if(ColsAtCompileTime == Eigen::Dynamic || ColsAtCompileTime == 1) + { + if(!isDimensionValid(rows, RowsAtCompileTime, MaxRowsAtCompileTime)) + { + THROW_TYPE_ERROR("Can not convert " << npyArrayTypeString(obj_ptr) << " to " << toString() + << ". Mismatched sizes."); + } + } + else + { + THROW_TYPE_ERROR("Can not convert " << npyArrayTypeString(obj_ptr) << " to " << toString() + << ". Mismatched sizes."); + } + + } + + static void checkVectorSizes(NPE_PY_ARRAY_OBJECT * obj_ptr) + { + int size = PyArray_DIM(obj_ptr, 0); + + // If the number of rows is fixed at 1, assume that is the sense of the vector. + // Otherwise, assume it is a column. + if(RowsAtCompileTime == 1) + { + checkRowVectorSizes(obj_ptr, size); + } + else + { + checkColumnVectorSizes(obj_ptr, size); + } + } + + + static void* convertible(PyObject *obj_ptr) + { + // Check for a null pointer. + if(!obj_ptr) + { + //THROW_TYPE_ERROR("PyObject pointer was null"); + return 0; + } + + // Make sure this is a numpy array. + if (!PyArray_Check(obj_ptr)) + { + //THROW_TYPE_ERROR("Conversion is only defined for numpy array and matrix types"); + return 0; + } + + NPE_PY_ARRAY_OBJECT * array_ptr = reinterpret_cast(obj_ptr); + + // Check the type of the array. + int npyType = getNpyType(array_ptr); + + if(!TypeToNumPy::canConvert(npyType)) + { + //THROW_TYPE_ERROR("Can not convert " << npyArrayTypeString(obj_ptr) << " to " << toString() + // << ". Mismatched types."); + return 0; + } + + + + // Check the array dimensions. + int nd = PyArray_NDIM(array_ptr); + + if(nd != 1 && nd != 2) + { + THROW_TYPE_ERROR("Conversion is only valid for arrays with 1 or 2 dimensions. Argument has " << nd << " dimensions"); + } + + if(nd == 1) + { + checkVectorSizes(array_ptr); + } + else + { + // Two-dimensional matrix type. + checkMatrixSizes(array_ptr); + } + + + return obj_ptr; + } + + + static void construct(PyObject *obj_ptr, boost::python::converter::rvalue_from_python_stage1_data *data) + { + boost::python::converter::rvalue_from_python_storage * matData = reinterpret_cast * >(data); + void* storage = matData->storage.bytes; + + // Make sure storage is 16byte aligned. With help from code from Memory.h + void * aligned = reinterpret_cast((reinterpret_cast(storage) & ~(size_t(15))) + 16); + + matrix_t * Mp = new (aligned) matrix_t(); + // Stash the memory chunk pointer for later use by boost.python + // This signals boost::python that the new value must be deleted eventually + data->convertible = storage; + + + // std::cout << "Creating aligned pointer " << aligned << " from storage " << storage << std::endl; + // std::cout << "matrix size: " << sizeof(matrix_t) << std::endl; + // std::cout << "referent size: " << boost::python::detail::referent_size< matrix_t & >::value << std::endl; + // std::cout << "sizeof(storage): " << sizeof(matData->storage) << std::endl; + // std::cout << "sizeof(bytes): " << sizeof(matData->storage.bytes) << std::endl; + + + + matrix_t & M = *Mp; + + if (!PyArray_Check(obj_ptr)) + { + THROW_TYPE_ERROR("construct is only defined for numpy array and matrix types"); + } + + NPE_PY_ARRAY_OBJECT * array_ptr = reinterpret_cast(obj_ptr); + + int nd = PyArray_NDIM(array_ptr); + if(nd == 1) + { + int size = PyArray_DIM(array_ptr, 0); + // This is a vector type + if(RowsAtCompileTime == 1) + { + // Row Vector + M.resize(1,size); + } + else + { + // Column Vector + M.resize(size,1); + } + numpyTypeDemuxer< CopyNumpyToEigenVector >(&M, array_ptr); + } + else + { + int rows = PyArray_DIM(array_ptr, 0); + int cols = PyArray_DIM(array_ptr, 1); + + M.resize(rows,cols); + numpyTypeDemuxer< CopyNumpyToEigenMatrix >(&M, array_ptr); + } + + + + + } + + + // The registration function. + static void register_converter() + { + boost::python::to_python_converter(); + boost::python::converter::registry::push_back( + &NumpyEigenConverter::convertible, + &NumpyEigenConverter::construct, + boost::python::type_id()); + + } + +}; + + + + +#endif /* NUMPY_EIGEN_CONVERTER_HPP */ diff --git a/python/include/numpy_eigen/README.md b/python/include/numpy_eigen/README.md new file mode 100644 index 000000000..bd5a3f44d --- /dev/null +++ b/python/include/numpy_eigen/README.md @@ -0,0 +1,6 @@ +numpy_eigen +=========== + +A boost python converter that handles the copy of matrices from the Eigen linear algebra library in C++ to numpy in Python. + +This is a minimal version based on the original from Paul Furgale (https://github.com/ethz-asl/Schweizer-Messer/tree/master/numpy_eigen) \ No newline at end of file diff --git a/python/include/numpy_eigen/boost_python_headers.hpp b/python/include/numpy_eigen/boost_python_headers.hpp new file mode 100755 index 000000000..5499d2917 --- /dev/null +++ b/python/include/numpy_eigen/boost_python_headers.hpp @@ -0,0 +1,250 @@ +/** + * @file boost_python_headers.hpp + * @author Paul Furgale + * @date Mon Dec 12 10:36:03 2011 + * + * @brief A header that specializes boost-python to work with fixed-sized Eigen types. + * + * The original version of this library did not include these specializations and this caused + * assert failures when running on Ubuntu 10.04 32-bit. More information about fixed-size + * vectorizable types in Eigen is available here: + * http://eigen.tuxfamily.org/dox-devel/TopicFixedSizeVectorizable.html + * + * This code has been tested on Ubunutu 10.04 64 and 32 bit, OSX Snow Leopard and OSX Lion. + * + * This code is derived from boost/python/converter/arg_from_python.hpp + * Copyright David Abrahams 2002. + * Distributed under the Boost Software License, Version 1.0. (See http://www.boost.org/LICENSE_1_0.txt) + * + */ +#ifndef NUMPY_EIGEN_CONVERTERS_HPP +#define NUMPY_EIGEN_CONVERTERS_HPP + +#include +#include +#include +#include +#include +#include + + +namespace boost { namespace python { namespace detail { + template + struct referent_size; + + // This bit of code makes sure we have 16 extra bytes to do the pointer alignment for fixed-sized Eigen types + template + struct referent_size< Eigen::Matrix& > + { + // Add 16 bytes so we can get alignment + BOOST_STATIC_CONSTANT( std::size_t, value = sizeof(Eigen::Matrix) + 16); + }; + + // This bit of code makes sure we have 16 extra bytes to do the pointer alignment for fixed-sized Eigen types + template + struct referent_size< Eigen::Matrix const & > + { + // Add 16 bytes so we can get alignment + BOOST_STATIC_CONSTANT( std::size_t, value = sizeof(Eigen::Matrix) + 16); + }; + + // This bit of code makes sure we have 16 extra bytes to do the pointer alignment for fixed-sized Eigen types + template + struct referent_size< Eigen::Matrix > + { + // Add 16 bytes so we can get alignment + BOOST_STATIC_CONSTANT( std::size_t, value = sizeof(Eigen::Matrix) + 16); + }; + + + }}} + +namespace boost { namespace python { namespace converter { + + + template + struct rvalue_from_python_data< Eigen::Matrix const &> : rvalue_from_python_storage< Eigen::Matrix const & > + { + typedef typename Eigen::Matrix T; +# if (!defined(__MWERKS__) || __MWERKS__ >= 0x3000) \ + && (!defined(__EDG_VERSION__) || __EDG_VERSION__ >= 245) \ + && (!defined(__DECCXX_VER) || __DECCXX_VER > 60590014) \ + && !defined(BOOST_PYTHON_SYNOPSIS) /* Synopsis' OpenCXX has trouble parsing this */ + // This must always be a POD struct with m_data its first member. + BOOST_STATIC_ASSERT(BOOST_PYTHON_OFFSETOF(rvalue_from_python_storage,stage1) == 0); +# endif + + // The usual constructor + rvalue_from_python_data(rvalue_from_python_stage1_data const & _stage1) + { + this->stage1 = _stage1; + } + + + // This constructor just sets m_convertible -- used by + // implicitly_convertible<> to perform the final step of the + // conversion, where the construct() function is already known. + rvalue_from_python_data(void* convertible) + { + this->stage1.convertible = convertible; + } + + // Destroys any object constructed in the storage. + ~rvalue_from_python_data() + { + // Realign the pointer and destroy + if (this->stage1.convertible == this->storage.bytes) + { + void * storage = reinterpret_cast(this->storage.bytes); + T * aligned = reinterpret_cast(reinterpret_cast((reinterpret_cast(storage) & ~(size_t(15))) + 16)); + + //std::cout << "Destroying " << (void*)aligned << std::endl; + aligned->T::~T(); + } + } + private: + typedef typename add_reference::type>::type ref_type; + }; + + + + + + // Used when T is a plain value (non-pointer, non-reference) type or + // a (non-volatile) const reference to a plain value type. + template + struct arg_rvalue_from_python< Eigen::Matrix > + { + typedef Eigen::Matrix const & T; + typedef typename boost::add_reference< + T + // We can't add_const here, or it would be impossible to pass + // auto_ptr args from Python to C++ + >::type result_type; + + arg_rvalue_from_python(PyObject * obj) : m_data(converter::rvalue_from_python_stage1(obj, registered::converters)) + , m_source(obj) + { + + } + bool convertible() const + { + return m_data.stage1.convertible != 0; + } + + +# if BOOST_MSVC < 1301 || _MSC_FULL_VER > 13102196 + typename arg_rvalue_from_python:: +# endif + result_type operator()() + { + if (m_data.stage1.construct != 0) + m_data.stage1.construct(m_source, &m_data.stage1); + + // Here is the magic... + // Realign the pointer + void * storage = reinterpret_cast(m_data.storage.bytes); + void * aligned = reinterpret_cast((reinterpret_cast(storage) & ~(size_t(15))) + 16); + + return python::detail::void_ptr_to_reference(aligned, (result_type(*)())0); + } + + private: + rvalue_from_python_data m_data; + PyObject* m_source; + }; + + + // Used when T is a plain value (non-pointer, non-reference) type or + // a (non-volatile) const reference to a plain value type. + template + struct arg_rvalue_from_python< Eigen::Matrix const & > + { + typedef Eigen::Matrix const & T; + typedef typename boost::add_reference< + T + // We can't add_const here, or it would be impossible to pass + // auto_ptr args from Python to C++ + >::type result_type; + + arg_rvalue_from_python(PyObject * obj) : m_data(converter::rvalue_from_python_stage1(obj, registered::converters)) + , m_source(obj) + { + + } + bool convertible() const + { + return m_data.stage1.convertible != 0; + } + + +# if BOOST_MSVC < 1301 || _MSC_FULL_VER > 13102196 + typename arg_rvalue_from_python:: +# endif + result_type operator()() + { + if (m_data.stage1.construct != 0) + m_data.stage1.construct(m_source, &m_data.stage1); + + // Here is the magic... + // Realign the pointer + void * storage = reinterpret_cast(m_data.storage.bytes); + void * aligned = reinterpret_cast((reinterpret_cast(storage) & ~(size_t(15))) + 16); + + return python::detail::void_ptr_to_reference(aligned, (result_type(*)())0); + } + + private: + rvalue_from_python_data m_data; + PyObject* m_source; + }; + + // Used when T is a plain value (non-pointer, non-reference) type or + // a (non-volatile) const reference to a plain value type. + template + struct arg_rvalue_from_python< Eigen::Matrix const > + { + typedef Eigen::Matrix const & T; + typedef typename boost::add_reference< + T + // We can't add_const here, or it would be impossible to pass + // auto_ptr args from Python to C++ + >::type result_type; + + arg_rvalue_from_python(PyObject * obj) : m_data(converter::rvalue_from_python_stage1(obj, registered::converters)) + , m_source(obj) + { + + } + bool convertible() const + { + return m_data.stage1.convertible != 0; + } + + +# if BOOST_MSVC < 1301 || _MSC_FULL_VER > 13102196 + typename arg_rvalue_from_python:: +# endif + result_type operator()() + { + if (m_data.stage1.construct != 0) + m_data.stage1.construct(m_source, &m_data.stage1); + + // Here is the magic... + // Realign the pointer + void * storage = reinterpret_cast(m_data.storage.bytes); + void * aligned = reinterpret_cast((reinterpret_cast(storage) & ~(size_t(15))) + 16); + + return python::detail::void_ptr_to_reference(aligned, (result_type(*)())0); + } + + private: + rvalue_from_python_data m_data; + PyObject* m_source; + }; + + + }}} + + +#endif /* NUMPY_EIGEN_CONVERTERS_HPP */ diff --git a/python/include/numpy_eigen/copy_routines.hpp b/python/include/numpy_eigen/copy_routines.hpp new file mode 100755 index 000000000..b112a7426 --- /dev/null +++ b/python/include/numpy_eigen/copy_routines.hpp @@ -0,0 +1,149 @@ +#ifndef NUMPY_EIGEN_COPY_ROUTINES_HPP +#define NUMPY_EIGEN_COPY_ROUTINES_HPP + + +template +struct CopyNumpyToEigenMatrix +{ + typedef EIGEN_T matrix_t; + typedef typename matrix_t::Scalar scalar_t; + + template + void exec(EIGEN_T * M_, NPE_PY_ARRAY_OBJECT * P_) + { + // Assumes M is already initialized. + for(int r = 0; r < M_->rows(); r++) + { + for(int c = 0; c < M_->cols(); c++) + { + T * p = static_cast(PyArray_GETPTR2(P_, r, c)); + (*M_)(r,c) = static_cast(*p); + } + } + } + +}; + +template +struct CopyEigenToNumpyMatrix +{ + typedef EIGEN_T matrix_t; + typedef typename matrix_t::Scalar scalar_t; + + template + void exec(EIGEN_T * M_, NPE_PY_ARRAY_OBJECT * P_) + { + // Assumes M is already initialized. + for(int r = 0; r < M_->rows(); r++) + { + for(int c = 0; c < M_->cols(); c++) + { + T * p = static_cast(PyArray_GETPTR2(P_, r, c)); + *p = static_cast((*M_)(r,c)); + } + } + } + +}; + +template +struct CopyEigenToNumpyVector +{ + typedef EIGEN_T matrix_t; + typedef typename matrix_t::Scalar scalar_t; + + template + void exec(EIGEN_T * M_, NPE_PY_ARRAY_OBJECT * P_) + { + // Assumes M is already initialized. + for(int i = 0; i < M_->size(); i++) + { + T * p = static_cast(PyArray_GETPTR1(P_, i)); + *p = static_cast((*M_)(i)); + } + } + +}; + + +template +struct CopyNumpyToEigenVector +{ + typedef EIGEN_T matrix_t; + typedef typename matrix_t::Scalar scalar_t; + + template + void exec(EIGEN_T * M_, NPE_PY_ARRAY_OBJECT * P_) + { + // Assumes M is already initialized. + for(int i = 0; i < M_->size(); i++) + { + T * p = static_cast(PyArray_GETPTR1(P_, i)); + (*M_)(i) = static_cast(*p); + } + } + +}; + + + + +// Crazy syntax in this function was found here: +// http://stackoverflow.com/questions/1840253/c-template-member-function-of-template-class-called-from-template-function/1840318#1840318 +template< typename FUNCTOR_T> +inline void numpyTypeDemuxer(typename FUNCTOR_T::matrix_t * M, NPE_PY_ARRAY_OBJECT * P) +{ + FUNCTOR_T f; + + int npyType = getNpyType(P); + switch(npyType) + { + case NPY_BOOL: + f.template exec(M,P); + break; + case NPY_BYTE: + f.template exec(M,P); + break; + case NPY_UBYTE: + f.template exec(M,P); + break; + case NPY_SHORT: + f.template exec(M,P); + break; + case NPY_USHORT: + f.template exec(M,P); + break; + case NPY_INT: + f.template exec(M,P); + break; + case NPY_UINT: + f.template exec(M,P); + break; + case NPY_LONG: + f.template exec(M,P); + break; + case NPY_ULONG: + f.template exec(M,P); + break; + case NPY_LONGLONG: + f.template exec(M,P); + break; + case NPY_ULONGLONG: + f.template exec(M,P); + break; + case NPY_FLOAT: + f.template exec(M,P); + break; + case NPY_DOUBLE: + f.template exec(M,P); + break; + case NPY_LONGDOUBLE: + f.template exec(M,P); + break; + default: + THROW_TYPE_ERROR("Unsupported type: " << npyTypeToString(npyType)); + } +} + + +#endif /* NUMPY_EIGEN_COPY_ROUTINES_HPP */ diff --git a/python/include/numpy_eigen/type_traits.hpp b/python/include/numpy_eigen/type_traits.hpp new file mode 100755 index 000000000..97e4bb5a0 --- /dev/null +++ b/python/include/numpy_eigen/type_traits.hpp @@ -0,0 +1,191 @@ +#ifndef NUMPY_EIGEN_TYPE_TRAITS_HPP +#define NUMPY_EIGEN_TYPE_TRAITS_HPP + +#define THROW_TYPE_ERROR(msg) \ + { \ + std::stringstream type_error_ss; \ + type_error_ss << msg; \ + PyErr_SetString(PyExc_TypeError, type_error_ss.str().c_str()); \ + throw boost::python::error_already_set(); \ + } + + +//////////////////////////////////////////////// +// TypeToNumPy +// Defines helper functions based on the Eigen3 matrix type that +// decide what conversions can happen Eigen3 --> NumPy +// Also, converts a type to a NumPy enum. +template struct TypeToNumPy; + +template<> struct TypeToNumPy +{ + enum { NpyType = NPY_INT }; + static const char * npyString() { return "NPY_INT"; } + static const char * typeString() { return "int"; } + static bool canConvert(int type) + { + return type == NPY_INT || type == NPY_LONG; + } +}; + +template<> struct TypeToNumPy +{ + enum { NpyType = NPY_LONG }; + static const char * npyString() { return "NPY_LONG"; } + static const char * typeString() { return "long"; } + static bool canConvert(int type) + { + return type == NPY_INT || type == NPY_LONG; + } +}; + +template<> struct TypeToNumPy +{ + enum { NpyType = NPY_UINT64 }; + static const char * npyString() { return "NPY_UINT64"; } + static const char * typeString() { return "uint64"; } + static bool canConvert(int type) + { + return type == NPY_UINT8 || type == NPY_USHORT || + type == NPY_UINT16 || type == NPY_UINT32 || + type == NPY_ULONG || type == NPY_ULONGLONG || + type == NPY_UINT64; + } +}; + +template<> struct TypeToNumPy +{ + enum { NpyType = NPY_UBYTE }; + static const char * npyString() { return "NPY_UBYTE"; } + static const char * typeString() { return "unsigned char"; } + static bool canConvert(int type) + { + return type == NPY_UBYTE || type == NPY_BYTE || type == NPY_CHAR; + } +}; + +template<> struct TypeToNumPy +{ + enum { NpyType = NPY_BYTE }; + static const char * npyString() { return "NPY_BYTE"; } + static const char * typeString() { return "char"; } + static bool canConvert(int type) + { + return type == NPY_UBYTE || type == NPY_BYTE || type == NPY_CHAR; + } +}; + + +template<> struct TypeToNumPy +{ + enum { NpyType = NPY_FLOAT }; + static const char * npyString() { return "NPY_FLOAT"; } + static const char * typeString() { return "float"; } + static bool canConvert(int type) + { + return type == NPY_INT || type == NPY_FLOAT || type == NPY_LONG; + } +}; + +template<> struct TypeToNumPy +{ + enum { NpyType = NPY_DOUBLE }; + static const char * npyString() { return "NPY_DOUBLE"; } + static const char * typeString() { return "double"; } + static bool canConvert(int type) + { + return type == NPY_INT || type == NPY_FLOAT || type == NPY_DOUBLE || type == NPY_LONG; + } +}; + + +inline int getNpyType(PyObject * obj_ptr){ + return PyArray_ObjectType(obj_ptr, 0); +} + +#ifdef NPY_1_7_API_VERSION +inline int getNpyType(PyArrayObject * obj_ptr){ + PyArray_Descr * descr = PyArray_MinScalarType(obj_ptr); + if (descr == NULL){ + THROW_TYPE_ERROR("Unsupported type: PyArray_MinScalarType returned null!"); + } + return descr->type_num; +} +#endif + +inline const char * npyTypeToString(int npyType) +{ + switch(npyType) + { + case NPY_BOOL: + return "NPY_BOOL"; + case NPY_BYTE: + return "NPY_BYTE"; + case NPY_UBYTE: + return "NPY_UBYTE"; + case NPY_SHORT: + return "NPY_SHORT"; + case NPY_USHORT: + return "NPY_USHORT"; + case NPY_INT: + return "NPY_INT"; + case NPY_UINT: + return "NPY_UINT"; + case NPY_LONG: + return "NPY_LONG"; + case NPY_ULONG: + return "NPY_ULONG"; + case NPY_LONGLONG: + return "NPY_LONGLONG"; + case NPY_ULONGLONG: + return "NPY_ULONGLONG"; + case NPY_FLOAT: + return "NPY_FLOAT"; + case NPY_DOUBLE: + return "NPY_DOUBLE"; + case NPY_LONGDOUBLE: + return "NPY_LONGDOUBLE"; + case NPY_CFLOAT: + return "NPY_CFLOAT"; + case NPY_CDOUBLE: + return "NPY_CDOUBLE"; + case NPY_CLONGDOUBLE: + return "NPY_CLONGDOUBLE"; + case NPY_OBJECT: + return "NPY_OBJECT"; + case NPY_STRING: + return "NPY_STRING"; + case NPY_UNICODE: + return "NPY_UNICODE"; + case NPY_VOID: + return "NPY_VOID"; + case NPY_NTYPES: + return "NPY_NTYPES"; + case NPY_NOTYPE: + return "NPY_NOTYPE"; + case NPY_CHAR: + return "NPY_CHAR"; + default: + return "Unknown type"; + } +} + +inline std::string npyArrayTypeString(NPE_PY_ARRAY_OBJECT * obj_ptr) +{ + std::stringstream ss; + int nd = PyArray_NDIM(obj_ptr); + ss << "numpy.array<" << npyTypeToString(getNpyType(obj_ptr)) << ">["; + if(nd > 0) + { + ss << PyArray_DIM(obj_ptr, 0); + for(int i = 1; i < nd; i++) + { + ss << ", " << PyArray_DIM(obj_ptr, i); + } + } + ss << "]"; + return ss.str(); +} + + +#endif /* NUMPY_EIGEN_TYPE_TRAITS_HPP */ diff --git a/python/setup.py.in b/python/setup.py.in new file mode 100644 index 000000000..d3b5fcde4 --- /dev/null +++ b/python/setup.py.in @@ -0,0 +1,15 @@ +from distutils.core import setup + +setup(name='gtsam', + version='${GTSAM_VERSION_STRING}', + description='GTSAM Python wrapper', + license = "BSD", + author='Frank Dellaert et. al', + author_email='frank.dellaert@gatech.edu', + maintainer_email='gtsam@lists.gatech.edu', + url='https://collab.cc.gatech.edu/borg/gtsam', + package_dir={ '': '${CMAKE_CURRENT_SOURCE_DIR}' }, + packages=['gtsam', 'gtsam_utils', 'gtsam_examples', 'gtsam_tests'], + #package_data={'gtsam' : ['_libgtsam_python.so']}, # location of .so file is relative to package_dir + data_files=[('${PY_INSTALL_FOLDER}/gtsam/', ['gtsam/_libgtsam_python.so'])], # location of .so file relative to setup.py + ) diff --git a/gtsam/nonlinear/tests/testExpressionFactor.cpp b/tests/testExpressionFactor.cpp similarity index 75% rename from gtsam/nonlinear/tests/testExpressionFactor.cpp rename to tests/testExpressionFactor.cpp index 2fb544edf..bef69edb6 100644 --- a/gtsam/nonlinear/tests/testExpressionFactor.cpp +++ b/tests/testExpressionFactor.cpp @@ -21,6 +21,7 @@ #include #include #include +#include #include #include #include @@ -37,6 +38,10 @@ using namespace gtsam; Point2 measured(-17, 30); SharedNoiseModel model = noiseModel::Unit::Create(2); +// This deals with the overload problem and makes the expressions factor +// understand that we work on Point3 +Point2 (*Project)(const Point3&, OptionalJacobian<2, 3>) = &PinholeBase::Project; + namespace leaf { // Create some values struct MyValues: public Values { @@ -313,7 +318,7 @@ TEST(ExpressionFactor, tree) { // Create expression tree Point3_ p_cam(x, &Pose3::transform_to, p); - Point2_ xy_hat(PinholeCamera::project_to_camera, p_cam); + Point2_ xy_hat(Project, p_cam); Point2_ uv_hat(K, &Cal3_S2::uncalibrate, xy_hat); // Create factor and check value, dimension, linearization @@ -331,8 +336,6 @@ TEST(ExpressionFactor, tree) { boost::shared_ptr gf2 = f2.linearize(values); EXPECT( assert_equal(*expected, *gf2, 1e-9)); - Expression::TernaryFunction::type fff = project6; - // Try ternary version ExpressionFactor f3(model, measured, project3(x, p, K)); EXPECT_DOUBLES_EQUAL(expected_error, f3.error(values), 1e-9); @@ -342,7 +345,6 @@ TEST(ExpressionFactor, tree) { } /* ************************************************************************* */ - TEST(ExpressionFactor, Compose1) { // Create expression @@ -489,7 +491,7 @@ TEST(ExpressionFactor, tree_finite_differences) { // Create expression tree Point3_ p_cam(x, &Pose3::transform_to, p); - Point2_ xy_hat(PinholeCamera::project_to_camera, p_cam); + Point2_ xy_hat(Project, p_cam); Point2_ uv_hat(K, &Cal3_S2::uncalibrate, xy_hat); const double fd_step = 1e-5; @@ -502,6 +504,161 @@ TEST(ExpressionFactor, push_back) { graph.addExpressionFactor(model, Point2(0, 0), leaf::p); } +/* ************************************************************************* */ +// Test with multiple compositions on duplicate keys +struct Combine { + double a, b; + Combine(double a, double b) : a(a), b(b) {} + double operator()(const double& x, const double& y, OptionalJacobian<1, 1> H1, + OptionalJacobian<1, 1> H2) { + if (H1) (*H1) << a; + if (H2) (*H2) << b; + return a * x + b * y; + } +}; + +TEST(Expression, testMultipleCompositions) { + const double tolerance = 1e-5; + const double fd_step = 1e-5; + + Values values; + values.insert(1, 10.0); + values.insert(2, 20.0); + + Expression v1_(Key(1)); + Expression v2_(Key(2)); + + // BinaryExpression(1,2) + // Leaf, key = 1 + // Leaf, key = 2 + Expression sum1_(Combine(1, 2), v1_, v2_); + EXPECT(sum1_.keys() == list_of(1)(2)); + EXPECT_CORRECT_EXPRESSION_JACOBIANS(sum1_, values, fd_step, tolerance); + + // BinaryExpression(3,4) + // BinaryExpression(1,2) + // Leaf, key = 1 + // Leaf, key = 2 + // Leaf, key = 1 + Expression sum2_(Combine(3, 4), sum1_, v1_); + EXPECT(sum2_.keys() == list_of(1)(2)); + EXPECT_CORRECT_EXPRESSION_JACOBIANS(sum2_, values, fd_step, tolerance); + + // BinaryExpression(5,6) + // BinaryExpression(3,4) + // BinaryExpression(1,2) + // Leaf, key = 1 + // Leaf, key = 2 + // Leaf, key = 1 + // BinaryExpression(1,2) + // Leaf, key = 1 + // Leaf, key = 2 + Expression sum3_(Combine(5, 6), sum1_, sum2_); + EXPECT(sum3_.keys() == list_of(1)(2)); + EXPECT_CORRECT_EXPRESSION_JACOBIANS(sum3_, values, fd_step, tolerance); +} + +/* ************************************************************************* */ +// Another test, with Ternary Expressions +static double combine3(const double& x, const double& y, const double& z, + OptionalJacobian<1, 1> H1, OptionalJacobian<1, 1> H2, + OptionalJacobian<1, 1> H3) { + if (H1) (*H1) << 1.0; + if (H2) (*H2) << 2.0; + if (H3) (*H3) << 3.0; + return x + 2.0 * y + 3.0 * z; +} + +TEST(Expression, testMultipleCompositions2) { + const double tolerance = 1e-5; + const double fd_step = 1e-5; + + Values values; + values.insert(1, 10.0); + values.insert(2, 20.0); + values.insert(3, 30.0); + + Expression v1_(Key(1)); + Expression v2_(Key(2)); + Expression v3_(Key(3)); + + Expression sum1_(Combine(4,5), v1_, v2_); + EXPECT(sum1_.keys() == list_of(1)(2)); + EXPECT_CORRECT_EXPRESSION_JACOBIANS(sum1_, values, fd_step, tolerance); + + Expression sum2_(combine3, v1_, v2_, v3_); + EXPECT(sum2_.keys() == list_of(1)(2)(3)); + EXPECT_CORRECT_EXPRESSION_JACOBIANS(sum2_, values, fd_step, tolerance); + + Expression sum3_(combine3, v3_, v2_, v1_); + EXPECT(sum3_.keys() == list_of(1)(2)(3)); + EXPECT_CORRECT_EXPRESSION_JACOBIANS(sum3_, values, fd_step, tolerance); + + Expression sum4_(combine3, sum1_, sum2_, sum3_); + EXPECT(sum4_.keys() == list_of(1)(2)(3)); + EXPECT_CORRECT_EXPRESSION_JACOBIANS(sum4_, values, fd_step, tolerance); +} + +/* ************************************************************************* */ +// Test multiplication with the inverse of a matrix +TEST(ExpressionFactor, MultiplyWithInverse) { + auto model = noiseModel::Isotropic::Sigma(3, 1); + + // Create expression + Vector3_ f_expr(MultiplyWithInverse<3>(), Expression(0), Vector3_(1)); + + // Check derivatives + Values values; + Matrix3 A = Vector3(1, 2, 3).asDiagonal(); + A(0, 1) = 0.1; + A(0, 2) = 0.1; + const Vector3 b(0.1, 0.2, 0.3); + values.insert(0, A); + values.insert(1, b); + ExpressionFactor factor(model, Vector3::Zero(), f_expr); + EXPECT_CORRECT_FACTOR_JACOBIANS(factor, values, 1e-5, 1e-5); +} + +/* ************************************************************************* */ +// Test multiplication with the inverse of a matrix function +namespace test_operator { +Vector3 f(const Point2& a, const Vector3& b, OptionalJacobian<3, 2> H1, + OptionalJacobian<3, 3> H2) { + Matrix3 A = Vector3(1, 2, 3).asDiagonal(); + A(0, 1) = a.x(); + A(0, 2) = a.y(); + A(1, 0) = a.x(); + if (H1) *H1 << b.y(), b.z(), b.x(), 0, 0, 0; + if (H2) *H2 = A; + return A * b; +}; +} + +TEST(ExpressionFactor, MultiplyWithInverseFunction) { + auto model = noiseModel::Isotropic::Sigma(3, 1); + + using test_operator::f; + Vector3_ f_expr(MultiplyWithInverseFunction(f), + Expression(0), Vector3_(1)); + + // Check derivatives + Point2 a(1, 2); + const Vector3 b(0.1, 0.2, 0.3); + Matrix32 H1; + Matrix3 A; + const Vector Ab = f(a, b, H1, A); + CHECK(assert_equal(A * b, Ab)); + CHECK(assert_equal(numericalDerivative11( + boost::bind(f, _1, b, boost::none, boost::none), a), + H1)); + + Values values; + values.insert(0, a); + values.insert(1, b); + ExpressionFactor factor(model, Vector3::Zero(), f_expr); + EXPECT_CORRECT_FACTOR_JACOBIANS(factor, values, 1e-5, 1e-5); +} + /* ************************************************************************* */ int main() { TestResult tr; diff --git a/tests/testGaussianFactorGraphB.cpp b/tests/testGaussianFactorGraphB.cpp index 3a0081bdb..88dc91ce7 100644 --- a/tests/testGaussianFactorGraphB.cpp +++ b/tests/testGaussianFactorGraphB.cpp @@ -532,7 +532,7 @@ TEST(GaussianFactorGraph, hasConstraints) #include #include #include -#include +#include /* ************************************************************************* */ TEST( GaussianFactorGraph, conditional_sigma_failure) { diff --git a/tests/testGaussianISAM2.cpp b/tests/testGaussianISAM2.cpp index 4e14d49b3..58c718726 100644 --- a/tests/testGaussianISAM2.cpp +++ b/tests/testGaussianISAM2.cpp @@ -9,7 +9,7 @@ #include #include #include -#include +#include #include #include #include @@ -25,7 +25,7 @@ #include #include #include -#include +#include using namespace boost::assign; #include namespace br { using namespace boost::adaptors; using namespace boost::range; } @@ -186,12 +186,12 @@ done: // Permuted permuted(permutation, values); // // // After permutation, the indices above the threshold are 2 and 2 -// FastSet expected; +// KeySet expected; // expected.insert(2); // expected.insert(3); // // // Indices checked by CheckRelinearization -// FastSet actual = Impl::CheckRelinearization(permuted, 0.1); +// KeySet actual = Impl::CheckRelinearization(permuted, 0.1); // // EXPECT(assert_equal(expected, actual)); //} diff --git a/tests/testGaussianJunctionTreeB.cpp b/tests/testGaussianJunctionTreeB.cpp index cdb1509b6..e877e5a9d 100644 --- a/tests/testGaussianJunctionTreeB.cpp +++ b/tests/testGaussianJunctionTreeB.cpp @@ -15,29 +15,42 @@ * @author nikai */ -#include - -#if 0 - #include -#include +#include #include -#include +#include +#include #include #include -#include -#include +#include +#include +#include +#include +#include #include +#include +#include +#include +#include +#include #include -#include -#include -#include -#include +#include +#include +#include +#include +#include -#include -#include // for operator += -#include // for operator += +#include + +#include +#include #include + +#include +#include +#include +#include + using namespace boost::assign; #include @@ -51,190 +64,218 @@ using symbol_shorthand::L; /* ************************************************************************* * Bayes tree for smoother with "nested dissection" ordering: - C1 x5 x6 x4 - C2 x3 x2 : x4 - C3 x1 : x2 - C4 x7 : x6 -*/ -TEST( GaussianJunctionTreeB, constructor2 ) -{ + C1 x5 x6 x4 + C2 x3 x2 : x4 + C3 x1 : x2 + C4 x7 : x6 + */ +TEST( GaussianJunctionTreeB, constructor2 ) { // create a graph - Ordering ordering; ordering += X(1),X(3),X(5),X(7),X(2),X(6),X(4); - GaussianFactorGraph fg = createSmoother(7, ordering).first; + NonlinearFactorGraph nlfg; + Values values; + boost::tie(nlfg, values) = createNonlinearSmoother(7); + SymbolicFactorGraph::shared_ptr symbolic = nlfg.symbolic(); + + // linearize + GaussianFactorGraph::shared_ptr fg = nlfg.linearize(values); + + Ordering ordering; + ordering += X(1), X(3), X(5), X(7), X(2), X(6), X(4); // create an ordering - GaussianJunctionTree actual(fg); + GaussianEliminationTree etree(*fg, ordering); + SymbolicEliminationTree stree(*symbolic, ordering); + GaussianJunctionTree actual(etree); - vector frontal1; frontal1 += ordering[X(5)], ordering[X(6)], ordering[X(4)]; - vector frontal2; frontal2 += ordering[X(3)], ordering[X(2)]; - vector frontal3; frontal3 += ordering[X(1)]; - vector frontal4; frontal4 += ordering[X(7)]; - vector sep1; - vector sep2; sep2 += ordering[X(4)]; - vector sep3; sep3 += ordering[X(2)]; - vector sep4; sep4 += ordering[X(6)]; - EXPECT(assert_equal(frontal1, actual.root()->frontal)); - EXPECT(assert_equal(sep1, actual.root()->separator)); - LONGS_EQUAL(5, actual.root()->size()); - list::const_iterator child0it = actual.root()->children().begin(); - list::const_iterator child1it = child0it; ++child1it; - GaussianJunctionTree::sharedClique child0 = *child0it; - GaussianJunctionTree::sharedClique child1 = *child1it; - EXPECT(assert_equal(frontal2, child0->frontal)); - EXPECT(assert_equal(sep2, child0->separator)); - LONGS_EQUAL(4, child0->size()); - EXPECT(assert_equal(frontal3, child0->children().front()->frontal)); - EXPECT(assert_equal(sep3, child0->children().front()->separator)); - LONGS_EQUAL(2, child0->children().front()->size()); - EXPECT(assert_equal(frontal4, child1->frontal)); - EXPECT(assert_equal(sep4, child1->separator)); - LONGS_EQUAL(2, child1->size()); + Ordering o324; + o324 += X(3), X(2), X(4); + Ordering o56; + o56 += X(5), X(6); + Ordering o7; + o7 += X(7); + Ordering o1; + o1 += X(1); + + // Can no longer test these: +// Ordering sep1; +// Ordering sep2; sep2 += X(4); +// Ordering sep3; sep3 += X(6); +// Ordering sep4; sep4 += X(2); + + GaussianJunctionTree::sharedNode x324 = actual.roots().front(); + LONGS_EQUAL(2, x324->children.size()); + GaussianJunctionTree::sharedNode x1 = x324->children.front(); + GaussianJunctionTree::sharedNode x56 = x324->children.back(); + if (x1->children.size() > 0) + x1.swap(x56); // makes it work with different tie-breakers + + LONGS_EQUAL(0, x1->children.size()); + LONGS_EQUAL(1, x56->children.size()); + GaussianJunctionTree::sharedNode x7 = x56->children[0]; + LONGS_EQUAL(0, x7->children.size()); + + EXPECT(assert_equal(o324, x324->orderedFrontalKeys)); + EXPECT_LONGS_EQUAL(5, x324->factors.size()); + EXPECT_LONGS_EQUAL(9, x324->problemSize_); + + EXPECT(assert_equal(o56, x56->orderedFrontalKeys)); + EXPECT_LONGS_EQUAL(4, x56->factors.size()); + EXPECT_LONGS_EQUAL(9, x56->problemSize_); + + EXPECT(assert_equal(o7, x7->orderedFrontalKeys)); + EXPECT_LONGS_EQUAL(2, x7->factors.size()); + EXPECT_LONGS_EQUAL(4, x7->problemSize_); + + EXPECT(assert_equal(o1, x1->orderedFrontalKeys)); + EXPECT_LONGS_EQUAL(2, x1->factors.size()); + EXPECT_LONGS_EQUAL(4, x1->problemSize_); } +///* ************************************************************************* */ +//TEST( GaussianJunctionTreeB, optimizeMultiFrontal ) +//{ +// // create a graph +// GaussianFactorGraph fg; +// Ordering ordering; +// boost::tie(fg,ordering) = createSmoother(7); +// +// // optimize the graph +// GaussianJunctionTree tree(fg); +// VectorValues actual = tree.optimize(&EliminateQR); +// +// // verify +// VectorValues expected(vector(7,2)); // expected solution +// Vector v = Vector2(0., 0.); +// for (int i=1; i<=7; i++) +// expected[ordering[X(i)]] = v; +// EXPECT(assert_equal(expected,actual)); +//} +// +///* ************************************************************************* */ +//TEST( GaussianJunctionTreeB, optimizeMultiFrontal2) +//{ +// // create a graph +// example::Graph nlfg = createNonlinearFactorGraph(); +// Values noisy = createNoisyValues(); +// Ordering ordering; ordering += X(1),X(2),L(1); +// GaussianFactorGraph fg = *nlfg.linearize(noisy, ordering); +// +// // optimize the graph +// GaussianJunctionTree tree(fg); +// VectorValues actual = tree.optimize(&EliminateQR); +// +// // verify +// VectorValues expected = createCorrectDelta(ordering); // expected solution +// EXPECT(assert_equal(expected,actual)); +//} +// +///* ************************************************************************* */ +//TEST(GaussianJunctionTreeB, slamlike) { +// Values init; +// NonlinearFactorGraph newfactors; +// NonlinearFactorGraph fullgraph; +// SharedDiagonal odoNoise = noiseModel::Diagonal::Sigmas((Vector(3) << 0.1, 0.1, M_PI/100.0)); +// SharedDiagonal brNoise = noiseModel::Diagonal::Sigmas((Vector(2) << M_PI/100.0, 0.1)); +// +// size_t i = 0; +// +// newfactors = NonlinearFactorGraph(); +// newfactors.add(PriorFactor(X(0), Pose2(0.0, 0.0, 0.0), odoNoise)); +// init.insert(X(0), Pose2(0.01, 0.01, 0.01)); +// fullgraph.push_back(newfactors); +// +// for( ; i<5; ++i) { +// newfactors = NonlinearFactorGraph(); +// newfactors.add(BetweenFactor(X(i), X(i+1), Pose2(1.0, 0.0, 0.0), odoNoise)); +// init.insert(X(i+1), Pose2(double(i+1)+0.1, -0.1, 0.01)); +// fullgraph.push_back(newfactors); +// } +// +// newfactors = NonlinearFactorGraph(); +// newfactors.add(BetweenFactor(X(i), X(i+1), Pose2(1.0, 0.0, 0.0), odoNoise)); +// newfactors.add(BearingRangeFactor(X(i), L(0), Rot2::fromAngle(M_PI/4.0), 5.0, brNoise)); +// newfactors.add(BearingRangeFactor(X(i), L(1), Rot2::fromAngle(-M_PI/4.0), 5.0, brNoise)); +// init.insert(X(i+1), Pose2(1.01, 0.01, 0.01)); +// init.insert(L(0), Point2(5.0/sqrt(2.0), 5.0/sqrt(2.0))); +// init.insert(L(1), Point2(5.0/sqrt(2.0), -5.0/sqrt(2.0))); +// fullgraph.push_back(newfactors); +// ++ i; +// +// for( ; i<5; ++i) { +// newfactors = NonlinearFactorGraph(); +// newfactors.add(BetweenFactor(X(i), X(i+1), Pose2(1.0, 0.0, 0.0), odoNoise)); +// init.insert(X(i+1), Pose2(double(i+1)+0.1, -0.1, 0.01)); +// fullgraph.push_back(newfactors); +// } +// +// newfactors = NonlinearFactorGraph(); +// newfactors.add(BetweenFactor(X(i), X(i+1), Pose2(1.0, 0.0, 0.0), odoNoise)); +// newfactors.add(BearingRangeFactor(X(i), L(0), Rot2::fromAngle(M_PI/4.0 + M_PI/16.0), 4.5, brNoise)); +// newfactors.add(BearingRangeFactor(X(i), L(1), Rot2::fromAngle(-M_PI/4.0 + M_PI/16.0), 4.5, brNoise)); +// init.insert(X(i+1), Pose2(6.9, 0.1, 0.01)); +// fullgraph.push_back(newfactors); +// ++ i; +// +// // Compare solutions +// Ordering ordering = *fullgraph.orderingCOLAMD(init); +// GaussianFactorGraph linearized = *fullgraph.linearize(init, ordering); +// +// GaussianJunctionTree gjt(linearized); +// VectorValues deltaactual = gjt.optimize(&EliminateQR); +// Values actual = init.retract(deltaactual, ordering); +// +// GaussianBayesNet gbn = *GaussianSequentialSolver(linearized).eliminate(); +// VectorValues delta = optimize(gbn); +// Values expected = init.retract(delta, ordering); +// +// EXPECT(assert_equal(expected, actual)); +//} +// +///* ************************************************************************* */ +//TEST(GaussianJunctionTreeB, simpleMarginal) { +// +// typedef BayesTree GaussianBayesTree; +// +// // Create a simple graph +// NonlinearFactorGraph fg; +// fg.add(PriorFactor(X(0), Pose2(), noiseModel::Isotropic::Sigma(3, 10.0))); +// fg.add(BetweenFactor(X(0), X(1), Pose2(1.0, 0.0, 0.0), noiseModel::Diagonal::Sigmas(Vector3(10.0, 1.0, 1.0)))); +// +// Values init; +// init.insert(X(0), Pose2()); +// init.insert(X(1), Pose2(1.0, 0.0, 0.0)); +// +// Ordering ordering; +// ordering += X(1), X(0); +// +// GaussianFactorGraph gfg = *fg.linearize(init, ordering); +// +// // Compute marginals with both sequential and multifrontal +// Matrix expected = GaussianSequentialSolver(gfg).marginalCovariance(1); +// +// Matrix actual1 = GaussianMultifrontalSolver(gfg).marginalCovariance(1); +// +// // Compute marginal directly from marginal factor +// GaussianFactor::shared_ptr marginalFactor = GaussianMultifrontalSolver(gfg).marginalFactor(1); +// JacobianFactor::shared_ptr marginalJacobian = boost::dynamic_pointer_cast(marginalFactor); +// Matrix actual2 = inverse(marginalJacobian->getA(marginalJacobian->begin()).transpose() * marginalJacobian->getA(marginalJacobian->begin())); +// +// // Compute marginal directly from BayesTree +// GaussianBayesTree gbt; +// gbt.insert(GaussianJunctionTree(gfg).eliminate(EliminateCholesky)); +// marginalFactor = gbt.marginalFactor(1, EliminateCholesky); +// marginalJacobian = boost::dynamic_pointer_cast(marginalFactor); +// Matrix actual3 = inverse(marginalJacobian->getA(marginalJacobian->begin()).transpose() * marginalJacobian->getA(marginalJacobian->begin())); +// +// EXPECT(assert_equal(expected, actual1)); +// EXPECT(assert_equal(expected, actual2)); +// EXPECT(assert_equal(expected, actual3)); +//} + /* ************************************************************************* */ -TEST( GaussianJunctionTreeB, optimizeMultiFrontal ) -{ - // create a graph - GaussianFactorGraph fg; - Ordering ordering; - boost::tie(fg,ordering) = createSmoother(7); - - // optimize the graph - GaussianJunctionTree tree(fg); - VectorValues actual = tree.optimize(&EliminateQR); - - // verify - VectorValues expected(vector(7,2)); // expected solution - Vector v = Vector2(0., 0.); - for (int i=1; i<=7; i++) - expected[ordering[X(i)]] = v; - EXPECT(assert_equal(expected,actual)); +int main() { + TestResult tr; + return TestRegistry::runAllTests(tr); } - -/* ************************************************************************* */ -TEST( GaussianJunctionTreeB, optimizeMultiFrontal2) -{ - // create a graph - example::Graph nlfg = createNonlinearFactorGraph(); - Values noisy = createNoisyValues(); - Ordering ordering; ordering += X(1),X(2),L(1); - GaussianFactorGraph fg = *nlfg.linearize(noisy, ordering); - - // optimize the graph - GaussianJunctionTree tree(fg); - VectorValues actual = tree.optimize(&EliminateQR); - - // verify - VectorValues expected = createCorrectDelta(ordering); // expected solution - EXPECT(assert_equal(expected,actual)); -} - -/* ************************************************************************* */ -TEST(GaussianJunctionTreeB, slamlike) { - Values init; - NonlinearFactorGraph newfactors; - NonlinearFactorGraph fullgraph; - SharedDiagonal odoNoise = noiseModel::Diagonal::Sigmas((Vector(3) << 0.1, 0.1, M_PI/100.0)); - SharedDiagonal brNoise = noiseModel::Diagonal::Sigmas((Vector(2) << M_PI/100.0, 0.1)); - - size_t i = 0; - - newfactors = NonlinearFactorGraph(); - newfactors.add(PriorFactor(X(0), Pose2(0.0, 0.0, 0.0), odoNoise)); - init.insert(X(0), Pose2(0.01, 0.01, 0.01)); - fullgraph.push_back(newfactors); - - for( ; i<5; ++i) { - newfactors = NonlinearFactorGraph(); - newfactors.add(BetweenFactor(X(i), X(i+1), Pose2(1.0, 0.0, 0.0), odoNoise)); - init.insert(X(i+1), Pose2(double(i+1)+0.1, -0.1, 0.01)); - fullgraph.push_back(newfactors); - } - - newfactors = NonlinearFactorGraph(); - newfactors.add(BetweenFactor(X(i), X(i+1), Pose2(1.0, 0.0, 0.0), odoNoise)); - newfactors.add(BearingRangeFactor(X(i), L(0), Rot2::fromAngle(M_PI/4.0), 5.0, brNoise)); - newfactors.add(BearingRangeFactor(X(i), L(1), Rot2::fromAngle(-M_PI/4.0), 5.0, brNoise)); - init.insert(X(i+1), Pose2(1.01, 0.01, 0.01)); - init.insert(L(0), Point2(5.0/sqrt(2.0), 5.0/sqrt(2.0))); - init.insert(L(1), Point2(5.0/sqrt(2.0), -5.0/sqrt(2.0))); - fullgraph.push_back(newfactors); - ++ i; - - for( ; i<5; ++i) { - newfactors = NonlinearFactorGraph(); - newfactors.add(BetweenFactor(X(i), X(i+1), Pose2(1.0, 0.0, 0.0), odoNoise)); - init.insert(X(i+1), Pose2(double(i+1)+0.1, -0.1, 0.01)); - fullgraph.push_back(newfactors); - } - - newfactors = NonlinearFactorGraph(); - newfactors.add(BetweenFactor(X(i), X(i+1), Pose2(1.0, 0.0, 0.0), odoNoise)); - newfactors.add(BearingRangeFactor(X(i), L(0), Rot2::fromAngle(M_PI/4.0 + M_PI/16.0), 4.5, brNoise)); - newfactors.add(BearingRangeFactor(X(i), L(1), Rot2::fromAngle(-M_PI/4.0 + M_PI/16.0), 4.5, brNoise)); - init.insert(X(i+1), Pose2(6.9, 0.1, 0.01)); - fullgraph.push_back(newfactors); - ++ i; - - // Compare solutions - Ordering ordering = *fullgraph.orderingCOLAMD(init); - GaussianFactorGraph linearized = *fullgraph.linearize(init, ordering); - - GaussianJunctionTree gjt(linearized); - VectorValues deltaactual = gjt.optimize(&EliminateQR); - Values actual = init.retract(deltaactual, ordering); - - GaussianBayesNet gbn = *GaussianSequentialSolver(linearized).eliminate(); - VectorValues delta = optimize(gbn); - Values expected = init.retract(delta, ordering); - - EXPECT(assert_equal(expected, actual)); -} - -/* ************************************************************************* */ -TEST(GaussianJunctionTreeB, simpleMarginal) { - - typedef BayesTree GaussianBayesTree; - - // Create a simple graph - NonlinearFactorGraph fg; - fg.add(PriorFactor(X(0), Pose2(), noiseModel::Isotropic::Sigma(3, 10.0))); - fg.add(BetweenFactor(X(0), X(1), Pose2(1.0, 0.0, 0.0), noiseModel::Diagonal::Sigmas(Vector3(10.0, 1.0, 1.0)))); - - Values init; - init.insert(X(0), Pose2()); - init.insert(X(1), Pose2(1.0, 0.0, 0.0)); - - Ordering ordering; - ordering += X(1), X(0); - - GaussianFactorGraph gfg = *fg.linearize(init, ordering); - - // Compute marginals with both sequential and multifrontal - Matrix expected = GaussianSequentialSolver(gfg).marginalCovariance(1); - - Matrix actual1 = GaussianMultifrontalSolver(gfg).marginalCovariance(1); - - // Compute marginal directly from marginal factor - GaussianFactor::shared_ptr marginalFactor = GaussianMultifrontalSolver(gfg).marginalFactor(1); - JacobianFactor::shared_ptr marginalJacobian = boost::dynamic_pointer_cast(marginalFactor); - Matrix actual2 = inverse(marginalJacobian->getA(marginalJacobian->begin()).transpose() * marginalJacobian->getA(marginalJacobian->begin())); - - // Compute marginal directly from BayesTree - GaussianBayesTree gbt; - gbt.insert(GaussianJunctionTree(gfg).eliminate(EliminateCholesky)); - marginalFactor = gbt.marginalFactor(1, EliminateCholesky); - marginalJacobian = boost::dynamic_pointer_cast(marginalFactor); - Matrix actual3 = inverse(marginalJacobian->getA(marginalJacobian->begin()).transpose() * marginalJacobian->getA(marginalJacobian->begin())); - - EXPECT(assert_equal(expected, actual1)); - EXPECT(assert_equal(expected, actual2)); - EXPECT(assert_equal(expected, actual3)); -} - -#endif - -/* ************************************************************************* */ -int main() { TestResult tr; return TestRegistry::runAllTests(tr);} /* ************************************************************************* */ diff --git a/tests/testGeneralSFMFactorB.cpp b/tests/testGeneralSFMFactorB.cpp index d43e7e31a..aea18c90d 100644 --- a/tests/testGeneralSFMFactorB.cpp +++ b/tests/testGeneralSFMFactorB.cpp @@ -61,7 +61,7 @@ TEST(PinholeCamera, BAL) { Values actual = lm.optimize(); double actualError = graph.error(actual); - EXPECT_DOUBLES_EQUAL(0.0199833, actualError, 1e-7); + EXPECT_DOUBLES_EQUAL(0.0199833, actualError, 1e-5); } /* ************************************************************************* */ diff --git a/tests/testLie.cpp b/tests/testLie.cpp index 7be629053..c153adf5f 100644 --- a/tests/testLie.cpp +++ b/tests/testLie.cpp @@ -54,9 +54,9 @@ TEST(Lie, ProductLieGroup) { Vector5 d; d << 1, 2, 0.1, 0.2, 0.3; Product expected(Point2(1, 2), Pose2::Expmap(Vector3(0.1, 0.2, 0.3))); - Product pair2 = pair1.retract(d); + Product pair2 = pair1.expmap(d); EXPECT(assert_equal(expected, pair2, 1e-9)); - EXPECT(assert_equal(d, pair1.localCoordinates(pair2), 1e-9)); + EXPECT(assert_equal(d, pair1.logmap(pair2), 1e-9)); } /* ************************************************************************* */ diff --git a/tests/testMarginals.cpp b/tests/testMarginals.cpp index dd22ae738..392b84deb 100644 --- a/tests/testMarginals.cpp +++ b/tests/testMarginals.cpp @@ -31,7 +31,7 @@ // add in headers for specific factors #include #include -#include +#include #include @@ -226,7 +226,8 @@ TEST(Marginals, order) { vals.at(3).range(vals.at(101)), noiseModel::Unit::Create(2)); Marginals marginals(fg, vals); - FastVector keys(fg.keys()); + KeySet set = fg.keys(); + FastVector keys(set.begin(), set.end()); JointMarginal joint = marginals.jointMarginalCovariance(keys); LONGS_EQUAL(3, (long)joint(0,0).rows()); diff --git a/tests/testNonlinearFactorGraph.cpp b/tests/testNonlinearFactorGraph.cpp index f398a33fe..ee60f9714 100644 --- a/tests/testNonlinearFactorGraph.cpp +++ b/tests/testNonlinearFactorGraph.cpp @@ -66,9 +66,9 @@ TEST( NonlinearFactorGraph, error ) TEST( NonlinearFactorGraph, keys ) { NonlinearFactorGraph fg = createNonlinearFactorGraph(); - FastSet actual = fg.keys(); + KeySet actual = fg.keys(); LONGS_EQUAL(3, (long)actual.size()); - FastSet::const_iterator it = actual.begin(); + KeySet::const_iterator it = actual.begin(); LONGS_EQUAL((long)L(1), (long)*(it++)); LONGS_EQUAL((long)X(1), (long)*(it++)); LONGS_EQUAL((long)X(2), (long)*(it++)); @@ -79,14 +79,14 @@ TEST( NonlinearFactorGraph, GET_ORDERING) { Ordering expected; expected += L(1), X(2), X(1); // For starting with l1,x1,x2 NonlinearFactorGraph nlfg = createNonlinearFactorGraph(); - Ordering actual = Ordering::colamd(nlfg); + Ordering actual = Ordering::Colamd(nlfg); EXPECT(assert_equal(expected,actual)); // Constrained ordering - put x2 at the end Ordering expectedConstrained; expectedConstrained += L(1), X(1), X(2); FastMap constraints; constraints[X(2)] = 1; - Ordering actualConstrained = Ordering::colamdConstrained(nlfg, constraints); + Ordering actualConstrained = Ordering::ColamdConstrained(nlfg, constraints); EXPECT(assert_equal(expectedConstrained, actualConstrained)); } diff --git a/tests/testNonlinearISAM.cpp b/tests/testNonlinearISAM.cpp index e9e266bb3..3c49d54af 100644 --- a/tests/testNonlinearISAM.cpp +++ b/tests/testNonlinearISAM.cpp @@ -6,7 +6,7 @@ #include #include -#include +#include #include #include #include diff --git a/tests/testNonlinearOptimizer.cpp b/tests/testNonlinearOptimizer.cpp index 6d8a056fc..f927f45ae 100644 --- a/tests/testNonlinearOptimizer.cpp +++ b/tests/testNonlinearOptimizer.cpp @@ -187,7 +187,9 @@ TEST( NonlinearOptimizer, Factorization ) ordering.push_back(X(1)); ordering.push_back(X(2)); - LevenbergMarquardtOptimizer optimizer(graph, config, ordering); + LevenbergMarquardtParams params; + LevenbergMarquardtParams::SetLegacyDefaults(¶ms); + LevenbergMarquardtOptimizer optimizer(graph, config, ordering, params); optimizer.iterate(); Values expected; @@ -260,13 +262,13 @@ TEST_UNSAFE(NonlinearOptimizer, MoreOptimization) { expectedGradient.insert(2,zero(3)); // Try LM and Dogleg - LevenbergMarquardtParams params; -// params.setVerbosityLM("TRYDELTA"); -// params.setVerbosity("TERMINATION"); - params.setlambdaUpperBound(1e9); -// params.setRelativeErrorTol(0); -// params.setAbsoluteErrorTol(0); - //params.setlambdaInitial(10); + LevenbergMarquardtParams params = LevenbergMarquardtParams::LegacyDefaults(); + // params.setVerbosityLM("TRYDELTA"); + // params.setVerbosity("TERMINATION"); + params.lambdaUpperBound = 1e9; +// params.relativeErrorTol = 0; +// params.absoluteErrorTol = 0; + //params.lambdaInitial = 10; { LevenbergMarquardtOptimizer optimizer(fg, init, params); @@ -290,7 +292,7 @@ TEST_UNSAFE(NonlinearOptimizer, MoreOptimization) { initBetter.insert(2, Pose2(11,7,M_PI/2)); { - params.setDiagonalDamping(true); + params.diagonalDamping = true; LevenbergMarquardtOptimizer optimizer(fg, initBetter, params); // test the diagonal @@ -399,7 +401,7 @@ public: /// Constructor IterativeLM(const NonlinearFactorGraph& graph, const Values& initialValues, const ConjugateGradientParameters &p, - const LevenbergMarquardtParams& params = LevenbergMarquardtParams()) : + const LevenbergMarquardtParams& params = LevenbergMarquardtParams::LegacyDefaults()) : LevenbergMarquardtOptimizer(graph, initialValues, params), cgParams_(p) { } @@ -446,8 +448,7 @@ TEST( NonlinearOptimizer, logfile ) // Levenberg-Marquardt LevenbergMarquardtParams lmParams; static const string filename("testNonlinearOptimizer.log"); - lmParams.setLogFile(filename); - CHECK(lmParams.getLogFile()==filename); + lmParams.logFile = filename; LevenbergMarquardtOptimizer(fg, c0, lmParams).optimize(); // stringstream expected,actual; diff --git a/tests/testSerializationSLAM.cpp b/tests/testSerializationSLAM.cpp index 2514c80d9..33453d7d3 100644 --- a/tests/testSerializationSLAM.cpp +++ b/tests/testSerializationSLAM.cpp @@ -22,15 +22,14 @@ #include //#include -#include -#include +#include #include //#include #include //#include #include #include -#include +#include #include #include #include @@ -106,9 +105,6 @@ typedef RangeFactor RangeFactorSimpleCameraP typedef RangeFactor RangeFactorCalibratedCamera; typedef RangeFactor RangeFactorSimpleCamera; -typedef BearingFactor BearingFactor2D; -typedef BearingFactor BearingFactor3D; - typedef BearingRangeFactor BearingRangeFactor2D; typedef BearingRangeFactor BearingRangeFactor3D; @@ -217,8 +213,6 @@ BOOST_CLASS_EXPORT_GUID(RangeFactorSimpleCameraPoint, "gtsam::RangeFactorSimpleC BOOST_CLASS_EXPORT_GUID(RangeFactorCalibratedCamera, "gtsam::RangeFactorCalibratedCamera"); BOOST_CLASS_EXPORT_GUID(RangeFactorSimpleCamera, "gtsam::RangeFactorSimpleCamera"); -BOOST_CLASS_EXPORT_GUID(BearingFactor2D, "gtsam::BearingFactor2D"); - BOOST_CLASS_EXPORT_GUID(BearingRangeFactor2D, "gtsam::BearingRangeFactor2D"); BOOST_CLASS_EXPORT_GUID(GenericProjectionFactorCal3_S2, "gtsam::GenericProjectionFactorCal3_S2"); @@ -393,8 +387,6 @@ TEST (testSerializationSLAM, factors) { RangeFactorCalibratedCamera rangeFactorCalibratedCamera(a12, b12, 2.0, model1); RangeFactorSimpleCamera rangeFactorSimpleCamera(a13, b13, 2.0, model1); - BearingFactor2D bearingFactor2D(a08, a03, rot2, model1); - BearingRangeFactor2D bearingRangeFactor2D(a08, a03, rot2, 2.0, model2); GenericProjectionFactorCal3_S2 genericProjectionFactorCal3_S2(point2, model2, a09, a05, boost::make_shared(cal3_s2)); @@ -456,8 +448,6 @@ TEST (testSerializationSLAM, factors) { graph += rangeFactorCalibratedCamera; graph += rangeFactorSimpleCamera; - graph += bearingFactor2D; - graph += bearingRangeFactor2D; graph += genericProjectionFactorCal3_S2; @@ -524,8 +514,6 @@ TEST (testSerializationSLAM, factors) { EXPECT(equalsObj(rangeFactorCalibratedCamera)); EXPECT(equalsObj(rangeFactorSimpleCamera)); - EXPECT(equalsObj(bearingFactor2D)); - EXPECT(equalsObj(bearingRangeFactor2D)); EXPECT(equalsObj(genericProjectionFactorCal3_S2)); @@ -592,8 +580,6 @@ TEST (testSerializationSLAM, factors) { EXPECT(equalsXML(rangeFactorCalibratedCamera)); EXPECT(equalsXML(rangeFactorSimpleCamera)); - EXPECT(equalsXML(bearingFactor2D)); - EXPECT(equalsXML(bearingRangeFactor2D)); EXPECT(equalsXML(genericProjectionFactorCal3_S2)); @@ -660,8 +646,6 @@ TEST (testSerializationSLAM, factors) { EXPECT(equalsBinary(rangeFactorCalibratedCamera)); EXPECT(equalsBinary(rangeFactorSimpleCamera)); - EXPECT(equalsBinary(bearingFactor2D)); - EXPECT(equalsBinary(bearingRangeFactor2D)); EXPECT(equalsBinary(genericProjectionFactorCal3_S2)); diff --git a/timing/DummyFactor.h b/timing/DummyFactor.h new file mode 100644 index 000000000..08e9d8f4b --- /dev/null +++ b/timing/DummyFactor.h @@ -0,0 +1,56 @@ +/** + * @file DummyFactor.h + * @brief Just to help in timing overhead + * @author Frank Dellaert + */ + +#pragma once + +#include + +namespace gtsam { + +/** + * DummyFactor + */ +template // +class DummyFactor: public RegularImplicitSchurFactor { + +public: + + typedef Eigen::Matrix Matrix2D; + typedef std::pair KeyMatrix2D; + + DummyFactor() { + } + + DummyFactor(const std::vector& Fblocks, const Matrix& E, + const Matrix3& P, const Vector& b) : + RegularImplicitSchurFactor(Fblocks, E, P, b) { + } + + virtual ~DummyFactor() { + } + +public: + + /** + * @brief Dummy version to measure overhead of key access + */ + void multiplyHessian(double alpha, const VectorValues& x, + VectorValues& y) const { + + BOOST_FOREACH(const KeyMatrix2D& Fi, this->Fblocks_) { + static const Vector empty; + Key key = Fi.first; + std::pair it = y.tryInsert(key, empty); + Vector& yi = it.first->second; + yi = x.at(key); + } + } + +}; +// DummyFactor + +} + diff --git a/timing/timeAdaptAutoDiff.cpp b/timing/timeAdaptAutoDiff.cpp index edfd420ef..3a9b5297a 100644 --- a/timing/timeAdaptAutoDiff.cpp +++ b/timing/timeAdaptAutoDiff.cpp @@ -57,16 +57,19 @@ int main() { f1 = boost::make_shared >(z, model, 1, 2); time("GeneralSFMFactor : ", f1, values); - // AdaptAutoDiff - typedef AdaptAutoDiff AdaptedSnavely; - Point2_ expression(AdaptedSnavely(), camera, point); - f2 = boost::make_shared >(model, z, expression); - time("Point2_(AdaptedSnavely(), camera, point): ", f2, values); - // ExpressionFactor Point2_ expression2(camera, &Camera::project2, point); f3 = boost::make_shared >(model, z, expression2); time("Point2_(camera, &Camera::project, point): ", f3, values); + // AdaptAutoDiff + values.clear(); + values.insert(1,Vector9(Vector9::Zero())); + values.insert(2,Vector3(0,0,1)); + typedef AdaptAutoDiff AdaptedSnavely; + Expression expression(AdaptedSnavely(), Expression(1), Expression(2)); + f2 = boost::make_shared >(model, z.vector(), expression); + time("Point2_(AdaptedSnavely(), camera, point): ", f2, values); + return 0; } diff --git a/timing/timeIncremental.cpp b/timing/timeIncremental.cpp index d82ef9442..b5dd37516 100644 --- a/timing/timeIncremental.cpp +++ b/timing/timeIncremental.cpp @@ -17,7 +17,7 @@ #include #include #include -#include +#include #include #include #include diff --git a/timing/timeRot2.cpp b/timing/timeRot2.cpp index 26eed0207..52dfdcc08 100644 --- a/timing/timeRot2.cpp +++ b/timing/timeRot2.cpp @@ -92,11 +92,8 @@ int main() int n = 50000000; cout << "NOTE: Times are reported for " << n << " calls" << endl; - // create a random direction: - double norm=sqrt(16.0+4.0); - double x=4.0/norm, y=2.0/norm; - Vector v = (Vector(2) << x, y).finished(); - Rot2 R = Rot2(0.4), R2 = R.retract(v), R3(0.6); + Vector1 v; v << 0.1; + Rot2 R = Rot2(0.4), R2(0.5), R3(0.6); TEST(Rot2_Expmap, Rot2::Expmap(v)); TEST(Rot2_Retract, R.retract(v)); diff --git a/timing/timeRot3.cpp b/timing/timeRot3.cpp index 4977fba86..5806149f3 100644 --- a/timing/timeRot3.cpp +++ b/timing/timeRot3.cpp @@ -40,10 +40,10 @@ int main() double norm=sqrt(1.0+16.0+4.0); double x=1.0/norm, y=4.0/norm, z=2.0/norm; Vector v = (Vector(3) << x, y, z).finished(); - Rot3 R = Rot3::rodriguez(0.1, 0.4, 0.2), R2 = R.retract(v); + Rot3 R = Rot3::Rodrigues(0.1, 0.4, 0.2), R2 = R.retract(v); - TEST("Rodriguez formula given axis angle", Rot3::rodriguez(v,0.001)) - TEST("Rodriguez formula given canonical coordinates", Rot3::rodriguez(v)) + TEST("Rodriguez formula given axis angle", Rot3::AxisAngle(v,0.001)) + TEST("Rodriguez formula given canonical coordinates", Rot3::Rodrigues(v)) TEST("Expmap", R*Rot3::Expmap(v)) TEST("Retract", R.retract(v)) TEST("Logmap", Rot3::Logmap(R.between(R2))) diff --git a/timing/timeSFMBAL.cpp b/timing/timeSFMBAL.cpp new file mode 100644 index 000000000..6308a1d61 --- /dev/null +++ b/timing/timeSFMBAL.cpp @@ -0,0 +1,56 @@ +/* ---------------------------------------------------------------------------- + + * 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 timeSFMBAL.cpp + * @brief time SFM with BAL file, conventional GeneralSFMFactor + * @author Frank Dellaert + * @date June 6, 2015 + */ + +#include "timeSFMBAL.h" + +#include +#include +#include +#include + +#include + +using namespace std; +using namespace gtsam; + +typedef PinholeCamera Camera; +typedef GeneralSFMFactor SfmFactor; + +int main(int argc, char* argv[]) { + // parse options and read BAL file + SfM_data db = preamble(argc, argv); + + // Build graph using conventional GeneralSFMFactor + NonlinearFactorGraph graph; + for (size_t j = 0; j < db.number_tracks(); j++) { + BOOST_FOREACH (const SfM_Measurement& m, db.tracks[j].measurements) { + size_t i = m.first; + Point2 z = m.second; + graph.push_back(SfmFactor(z, gNoiseModel, C(i), P(j))); + } + } + + Values initial; + size_t i = 0, j = 0; + BOOST_FOREACH (const SfM_Camera& camera, db.cameras) + initial.insert(C(i++), camera); + BOOST_FOREACH (const SfM_Track& track, db.tracks) + initial.insert(P(j++), track.p); + + return optimize(db, graph, initial); +} diff --git a/timing/timeSFMBAL.h b/timing/timeSFMBAL.h new file mode 100644 index 000000000..e9449af7b --- /dev/null +++ b/timing/timeSFMBAL.h @@ -0,0 +1,87 @@ +/* ---------------------------------------------------------------------------- + + * 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 timeSFMBAL.h + * @brief Common code for timeSFMBAL scripts + * @author Frank Dellaert + * @date July 5, 2015 + */ + +#include +#include +#include +#include +#include +#include +#include +#include + +#include +#include + +using namespace std; +using namespace gtsam; +using symbol_shorthand::C; +using symbol_shorthand::K; +using symbol_shorthand::P; + +static bool gUseSchur = true; +static SharedNoiseModel gNoiseModel = noiseModel::Unit::Create(2); + +// parse options and read BAL file +SfM_data preamble(int argc, char* argv[]) { + // primitive argument parsing: + if (argc > 2) { + if (strcmp(argv[1], "--colamd")) + gUseSchur = false; + else + throw runtime_error("Usage: timeSFMBALxxx [--colamd] [BALfile]"); + } + + // Load BAL file + SfM_data db; + string defaultFilename = findExampleDataFile("dubrovnik-16-22106-pre"); + bool success = readBAL(argc > 1 ? argv[argc - 1] : defaultFilename, db); + if (!success) throw runtime_error("Could not access file!"); + return db; +} + +// Create ordering and optimize +int optimize(const SfM_data& db, const NonlinearFactorGraph& graph, + const Values& initial, bool separateCalibration = false) { + using symbol_shorthand::P; + + // Set parameters to be similar to ceres + LevenbergMarquardtParams params; + LevenbergMarquardtParams::SetCeresDefaults(¶ms); + params.setVerbosityLM("SUMMARY"); + + if (gUseSchur) { + // Create Schur-complement ordering + Ordering ordering; + for (size_t j = 0; j < db.number_tracks(); j++) ordering.push_back(P(j)); + for (size_t i = 0; i < db.number_cameras(); i++) { + ordering.push_back(C(i)); + if (separateCalibration) ordering.push_back(K(i)); + } + params.setOrdering(ordering); + } + + // Optimize + LevenbergMarquardtOptimizer lm(graph, initial, params); + Values result = lm.optimize(); + + tictoc_finishedIteration_(); + tictoc_print_(); + + return 0; +} diff --git a/timing/timeSFMBALautodiff.cpp b/timing/timeSFMBALautodiff.cpp new file mode 100644 index 000000000..4545abc21 --- /dev/null +++ b/timing/timeSFMBALautodiff.cpp @@ -0,0 +1,75 @@ +/* ---------------------------------------------------------------------------- + + * 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 timeSFMBALautodiff.cpp + * @brief time SFM with BAL file, Ceres autodiff version + * @author Frank Dellaert + * @date July 5, 2015 + */ + +#include "timeSFMBAL.h" +#include +#include +#include +#include + +#include +#include +#include +#include + +using namespace std; +using namespace gtsam; + +// See http://www.cs.cornell.edu/~snavely/bundler/bundler-v0.3-manual.html +// as to why so much gymnastics is needed to massage the initial estimates and +// measurements: basically, Snavely does not use computer vision conventions +// but OpenGL conventions :-( + +typedef PinholeCamera Camera; + +int main(int argc, char* argv[]) { + // parse options and read BAL file + SfM_data db = preamble(argc, argv); + + AdaptAutoDiff snavely; + + // Build graph + NonlinearFactorGraph graph; + for (size_t j = 0; j < db.number_tracks(); j++) { + BOOST_FOREACH (const SfM_Measurement& m, db.tracks[j].measurements) { + size_t i = m.first; + Point2 z = m.second; + Expression camera_(C(i)); + Expression point_(P(j)); + // Expects measurements in OpenGL format, with y increasing upwards + graph.addExpressionFactor(gNoiseModel, Vector2(z.x(), -z.y()), + Expression(snavely, camera_, point_)); + } + } + + Values initial; + size_t i = 0, j = 0; + BOOST_FOREACH (const SfM_Camera& camera, db.cameras) { + // readBAL converts to GTSAM format, so we need to convert back ! + Pose3 openGLpose = gtsam2openGL(camera.pose()); + Vector9 v9; + v9 << Pose3::Logmap(openGLpose), camera.calibration().vector(); + initial.insert(C(i++), v9); + } + BOOST_FOREACH (const SfM_Track& track, db.tracks) { + Vector3 v3 = track.p.vector(); + initial.insert(P(j++), v3); + } + + return optimize(db, graph, initial); +} diff --git a/timing/timeSFMBALcamTnav.cpp b/timing/timeSFMBALcamTnav.cpp new file mode 100644 index 000000000..32fae4ac2 --- /dev/null +++ b/timing/timeSFMBALcamTnav.cpp @@ -0,0 +1,63 @@ +/* ---------------------------------------------------------------------------- + + * 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 timeSFMBALcamTnav.cpp + * @brief time SFM with BAL file, expressions with camTnav pose + * @author Frank Dellaert + * @date July 5, 2015 + */ + +#include "timeSFMBAL.h" + +#include +#include +#include +#include + +#include + +using namespace std; +using namespace gtsam; + +int main(int argc, char* argv[]) { + // parse options and read BAL file + SfM_data db = preamble(argc, argv); + + // Build graph using conventional GeneralSFMFactor + NonlinearFactorGraph graph; + for (size_t j = 0; j < db.number_tracks(); j++) { + BOOST_FOREACH (const SfM_Measurement& m, db.tracks[j].measurements) { + size_t i = m.first; + Point2 z = m.second; + Pose3_ camTnav_(C(i)); + Cal3Bundler_ calibration_(K(i)); + Point3_ nav_point_(P(j)); + graph.addExpressionFactor( + gNoiseModel, z, + uncalibrate(calibration_, // now using transform_from !!!: + project(transform_from(camTnav_, nav_point_)))); + } + } + + Values initial; + size_t i = 0, j = 0; + BOOST_FOREACH (const SfM_Camera& camera, db.cameras) { + initial.insert(C(i), camera.pose().inverse()); // inverse !!! + initial.insert(K(i), camera.calibration()); + i += 1; + } + BOOST_FOREACH (const SfM_Track& track, db.tracks) + initial.insert(P(j++), track.p); + + bool separateCalibration = true; + return optimize(db, graph, initial, separateCalibration); +} diff --git a/timing/timeSFMBALnavTcam.cpp b/timing/timeSFMBALnavTcam.cpp new file mode 100644 index 000000000..e370a5a67 --- /dev/null +++ b/timing/timeSFMBALnavTcam.cpp @@ -0,0 +1,63 @@ +/* ---------------------------------------------------------------------------- + + * 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 timeSFMBALnavTcam.cpp + * @brief time SFM with BAL file, expressions with navTcam pose + * @author Frank Dellaert + * @date July 5, 2015 + */ + +#include "timeSFMBAL.h" + +#include +#include +#include +#include + +#include + +using namespace std; +using namespace gtsam; + +int main(int argc, char* argv[]) { + // parse options and read BAL file + SfM_data db = preamble(argc, argv); + + // Build graph using conventional GeneralSFMFactor + NonlinearFactorGraph graph; + for (size_t j = 0; j < db.number_tracks(); j++) { + BOOST_FOREACH (const SfM_Measurement& m, db.tracks[j].measurements) { + size_t i = m.first; + Point2 z = m.second; + Pose3_ navTcam_(C(i)); + Cal3Bundler_ calibration_(K(i)); + Point3_ nav_point_(P(j)); + graph.addExpressionFactor( + gNoiseModel, z, + uncalibrate(calibration_, + project(transform_to(navTcam_, nav_point_)))); + } + } + + Values initial; + size_t i = 0, j = 0; + BOOST_FOREACH (const SfM_Camera& camera, db.cameras) { + initial.insert(C(i), camera.pose()); + initial.insert(K(i), camera.calibration()); + i += 1; + } + BOOST_FOREACH (const SfM_Track& track, db.tracks) + initial.insert(P(j++), track.p); + + bool separateCalibration = true; + return optimize(db, graph, initial, separateCalibration); +} diff --git a/timing/timeSchurFactors.cpp b/timing/timeSchurFactors.cpp new file mode 100644 index 000000000..e08924400 --- /dev/null +++ b/timing/timeSchurFactors.cpp @@ -0,0 +1,157 @@ +/** + * @file timeSchurFactors.cpp + * @brief Time various Schur-complement Jacobian factors + * @author Frank Dellaert + * @date Oct 27, 2013 + */ + +#include "DummyFactor.h" +#include + +#include +#include "gtsam/slam/JacobianFactorQR.h" +#include +#include +#include + +#include +#include +#include + +using namespace std; +using namespace boost::assign; +using namespace gtsam; + +#define SLOW +#define RAW +#define HESSIAN +#define NUM_ITERATIONS 1000 + +// Create CSV file for results +ofstream os("timeSchurFactors.csv"); + +/*************************************************************************************/ +template +void timeAll(size_t m, size_t N) { + + cout << m << endl; + + // create F + static const int D = CAMERA::dimension; + typedef Eigen::Matrix Matrix2D; + FastVector keys; + vector Fblocks; + for (size_t i = 0; i < m; i++) { + keys.push_back(i); + Fblocks.push_back((i + 1) * Matrix::Ones(2, D)); + } + + // create E + Matrix E(2 * m, 3); + for (size_t i = 0; i < m; i++) + E.block < 2, 3 > (2 * i, 0) = Matrix::Ones(2, 3); + + // Calculate point covariance + Matrix P = (E.transpose() * E).inverse(); + + // RHS and sigmas + const Vector b = gtsam::repeat(2 * m, 1); + const SharedDiagonal model; + + // parameters for multiplyHessianAdd + double alpha = 0.5; + VectorValues xvalues, yvalues; + for (size_t i = 0; i < m; i++) + xvalues.insert(i, gtsam::repeat(D, 2)); + + // Implicit + RegularImplicitSchurFactor implicitFactor(keys, Fblocks, E, P, b); + // JacobianFactor with same error + JacobianFactorQ jf(keys, Fblocks, E, P, b, model); + // JacobianFactorQR with same error + JacobianFactorQR jqr(keys, Fblocks, E, P, b, model); + // Hessian + HessianFactor hessianFactor(jqr); + +#define TIME(label,factor,xx,yy) {\ + for (size_t t = 0; t < N; t++) \ + factor.multiplyHessianAdd(alpha, xx, yy);\ + gttic_(label);\ + for (size_t t = 0; t < N; t++) {\ + factor.multiplyHessianAdd(alpha, xx, yy);\ + }\ + gttoc_(label);\ + tictoc_getNode(timer, label)\ + os << timer->secs()/NUM_ITERATIONS << ", ";\ + } + +#ifdef SLOW + TIME(Implicit, implicitFactor, xvalues, yvalues) + TIME(Jacobian, jf, xvalues, yvalues) + TIME(JacobianQR, jqr, xvalues, yvalues) +#endif + +#ifdef HESSIAN + TIME(Hessian, hessianFactor, xvalues, yvalues) +#endif + +#ifdef OVERHEAD + DummyFactor dummy(Fblocks, E, P, b); + TIME(Overhead,dummy,xvalues,yvalues) +#endif + +#ifdef RAW + { // Raw memory Version + FastVector < Key > keys; + for (size_t i = 0; i < m; i++) + keys += i; + Vector x = xvalues.vector(keys); + double* xdata = x.data(); + + // create a y + Vector y = zero(m * D); + TIME(RawImplicit, implicitFactor, xdata, y.data()) + TIME(RawJacobianQ, jf, xdata, y.data()) + TIME(RawJacobianQR, jqr, xdata, y.data()) + } +#endif + + os << m << endl; + +} // timeAll + +/*************************************************************************************/ +int main(void) { +#ifdef SLOW + os << "Implicit,"; + os << "JacobianQ,"; + os << "JacobianQR,"; +#endif +#ifdef HESSIAN + os << "Hessian,"; +#endif +#ifdef OVERHEAD + os << "Overhead,"; +#endif +#ifdef RAW + os << "RawImplicit,"; + os << "RawJacobianQ,"; + os << "RawJacobianQR,"; +#endif + os << "m" << endl; + // define images + vector < size_t > ms; + // ms += 2; + // ms += 3, 4, 5, 6, 7, 8, 9, 10; + // ms += 11,12,13,14,15,16,17,18,19; + // ms += 20, 30, 40, 50; + // ms += 20,30,40,50,60,70,80,90,100; + for (size_t m = 2; m <= 50; m += 2) + ms += m; + //for (size_t m=10;m<=100;m+=10) ms += m; + // loop over number of images + BOOST_FOREACH(size_t m,ms) + timeAll >(m, NUM_ITERATIONS); +} + +//*************************************************************************************