diff --git a/.cproject b/.cproject index 5d8469baa..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,146 +868,154 @@ true true - + make - -j2 - all + -j5 + testGaussianFactorGraphUnordered.run true true true - + make - -j2 - check + -j5 + testGaussianBayesNetUnordered.run true true true - + make - -j2 + -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 - -j2 - testPlanarSLAM.run - true - true - true - - - make - -j2 - testPose2Config.run - true - true - true - - - make - -j2 - testPose2Factor.run - true - true - true - - - make - -j2 - testPose2Prior.run - true - true - true - - - make - -j2 - testPose2SLAM.run - true - true - true - - - make - -j2 - testPose3Config.run - true - true - true - - - make - -j2 - testPose3SLAM.run - true - true - true - - - make - - testSimulated2DOriented.run - true - false - true - - - make - -j2 - testVSLAMConfig.run - true - true - true - - - make - -j2 - testVSLAMFactor.run - true - true - true - - - make - -j2 - testVSLAMGraph.run - true - true - true - - - make - -j2 - testPose3Factor.run - true - true - true - - - make - - testSimulated2D.run - true - false - true - - - make - - testSimulated3D.run - true - false - true - - - make - -j2 - tests/testGaussianISAM2 + -j5 + all true true true @@ -1461,111 +1110,477 @@ make + testErrors.run true false true - + make - -j5 - testAntiFactor.run + -j2 + check true true true - + make - -j5 - testPriorFactor.run + -j2 + tests/testGaussianJunctionTree.run true true true - + make - -j5 - testDataset.run + -j2 + tests/testGaussianFactor.run true true true - + make - -j5 - testEssentialMatrixFactor.run + -j2 + tests/testGaussianConditional.run true true true - + make - -j5 - testGeneralSFMFactor_Cal3Bundler.run + -j2 + tests/timeSLAMlike.run true true true - + make - -j5 - testGeneralSFMFactor.run + -j2 + check true true true - + make - -j5 - testProjectionFactor.run + -j2 + clean true true true - + make - -j5 - testRotateFactor.run + -j2 + testBTree.run true true true - + make - -j5 - testPoseRotationPrior.run + -j2 + testDSF.run true true true - + make - -j5 - testImplicitSchurFactor.run + -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 + all + true + true + true + + + make + -j2 + check + true + true + true + + + make + -j2 + clean + true + true + true + + + make + -j2 + testPlanarSLAM.run + true + true + true + + + make + -j2 + testPose2Config.run + true + true + true + + + make + -j2 + testPose2Factor.run + true + true + true + + + make + -j2 + testPose2Prior.run + true + true + true + + + make + -j2 + testPose2SLAM.run + true + true + true + + + make + -j2 + testPose3Config.run + true + true + true + + + make + -j2 + testPose3SLAM.run + true + true + true + + + make + testSimulated2DOriented.run + true + false + true + + + make + -j2 + testVSLAMConfig.run + true + true + true + + + make + -j2 + testVSLAMFactor.run + true + true + true + + + make + -j2 + testVSLAMGraph.run + true + true + true + + + make + -j2 + testPose3Factor.run + true + true + true + + + make + testSimulated2D.run + true + false + true + + + make + testSimulated3D.run + true + false + true + + + make + -j2 + tests/testGaussianISAM2 + 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 + -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 - testRangeFactor.run + testLabeledSymbol.run true true true - + make - -j4 - testOrientedPlane3Factor.run + -j2 + check true true true - + make - -j4 - testSmartProjectionPoseFactor.run + -j2 + tests/testLieConfig.run true true true @@ -1771,6 +1786,7 @@ cpack + -G DEB true false @@ -1778,6 +1794,7 @@ cpack + -G RPM true false @@ -1785,6 +1802,7 @@ cpack + -G TGZ true false @@ -1792,6 +1810,7 @@ cpack + --config CPackSourceConfig.cmake true false @@ -1973,7 +1992,15 @@ false true - + + make + -j4 + check.sam + true + true + true + + make -j2 check @@ -1981,55 +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 @@ -2037,10 +2047,458 @@ true true - + make -j5 - testParticleFactor.run + 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 + 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 + true + true + true + + + make + -j2 + clean + true + true + true + + + make + -j5 + all + true + false + true + + + make + -j5 + check + true + false + true + + + make + -j2 + 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 + + + make + -j1 + testDiscreteBayesTree.run + true + false + true + + + make + -j5 + testDiscreteConditional.run + true + true + true + + + make + -j5 + testDiscreteFactor.run + true + true + true + + + make + -j5 + testDiscreteFactorGraph.run + true + true + true + + + make + -j5 + testDiscreteMarginals.run + true + true + true + + + make + -j5 + testIMUSystem.run + true + true + true + + + make + -j5 + testPoseRTV.run + true + true + true + + + make + -j5 + testVelocityConstraint.run + true + true + true + + + make + -j5 + testVelocityConstraint3.run + true + true + 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 + -j5 + testWrap.run + true + true + true + + + make + -j5 + testSpirit.run + true + true + true + + + make + -j5 + check.wrap + true + true + true + + + make + -j5 + testMethod.run + true + true + true + + + make + -j5 + testClass.run + true + true + true + + + make + -j4 + testType.run + true + true + true + + + make + -j4 + testArgument.run + true + true + true + + + make + -j4 + testReturnValue.run + true + true + true + + + make + -j4 + testTemplate.run + true + true + true + + + make + -j4 + testGlobalFunction.run true true true @@ -2093,7 +2551,343 @@ true true - + + make + -j2 + vSFMexample.run + true + true + true + + + make + -j2 + testVSLAMGraph + true + true + true + + + make + -j5 + testMatrix.run + true + true + true + + + make + -j5 + testVector.run + true + true + true + + + make + -j5 + testNumericalDerivative.run + true + true + true + + + make + -j5 + testVerticalBlockMatrix.run + true + true + true + + + make + -j4 + testOptionalJacobian.run + true + true + true + + + make + -j4 + testGroup.run + true + true + true + + + make + -j5 + check.tests + true + true + true + + + make + -j2 + timeGaussianFactorGraph.run + true + true + true + + + make + -j5 + testMarginals.run + true + true + true + + + make + -j5 + testGaussianISAM2.run + true + true + true + + + make + -j5 + testSymbolicFactorGraphB.run + true + true + true + + + make + -j2 + timeSequentialOnDataset.run + true + true + true + + + make + -j5 + testGradientDescentOptimizer.run + true + true + true + + + make + -j2 + testGaussianFactor.run + true + true + true + + + make + -j2 + testNonlinearOptimizer.run + true + true + true + + + make + -j2 + testGaussianBayesNet.run + true + true + true + + + make + -j2 + testNonlinearISAM.run + true + true + true + + + make + -j2 + testNonlinearEquality.run + true + true + true + + + make + -j2 + testExtendedKalmanFilter.run + true + true + true + + + make + -j5 + timing.tests + true + true + true + + + make + -j5 + testNonlinearFactor.run + true + true + true + + + make + -j5 + clean + true + true + true + + + make + -j5 + testGaussianJunctionTreeB.run + true + true + true + + + make + + testGraph.run + true + false + true + + + make + + testJunctionTree.run + true + false + true + + + make + + testSymbolicBayesNetB.run + true + false + true + + + make + -j5 + testGaussianISAM.run + true + true + true + + + make + -j5 + testDoglegOptimizer.run + true + true + true + + + make + -j5 + testNonlinearFactorGraph.run + true + true + true + + + make + -j5 + testIterative.run + true + true + true + + + make + -j5 + testSubgraphSolver.run + true + true + true + + + make + -j5 + testGaussianFactorGraphB.run + true + true + true + + + make + -j5 + testSummarization.run + true + true + true + + + make + -j5 + testManifold.run + true + true + true + + + make + -j4 + testLie.run + true + true + true + + + make + -j4 + testSerializationSLAM.run + true + true + true + + + make + -j5 + testParticleFactor.run + true + true + true + + + make + -j2 + testGaussianFactor.run + true + true + true + + + make + -j2 + install + true + true + true + + + make + -j2 + clean + true + true + true + + make -j2 all @@ -2101,7 +2895,7 @@ true true - + make -j2 clean @@ -2109,129 +2903,15 @@ 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 + all 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 @@ -2239,18 +2919,106 @@ true true - + make - -j2 - tests/testPose2.run + -j5 + testAntiFactor.run true true true - + make - -j2 - tests/testPose3.run + -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 @@ -2455,6 +3223,213 @@ 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 + true + 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 @@ -2551,927 +3526,34 @@ true true - - make - -j1 - testDiscreteBayesTree.run - true - false - true - - - make - -j5 - testDiscreteConditional.run - true - true - true - - - make - -j5 - testDiscreteFactor.run - true - true - true - - - make - -j5 - testDiscreteFactorGraph.run - true - true - true - - - make - -j5 - testDiscreteMarginals.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 + testBearingFactor.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 + testRangeFactor.run true true true - + make -j4 - testAdaptAutoDiff.run + testBearingRangeFactor.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 - testIMUSystem.run - true - true - true - - - make - -j5 - testPoseRTV.run - true - true - true - - - make - -j5 - testVelocityConstraint.run - true - true - true - - - make - -j5 - testVelocityConstraint3.run - true - true - 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 - -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 - true - true - true - - - make - -j2 - clean - true - 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 - testWrap.run - true - true - true - - - make - -j5 - testSpirit.run - true - true - true - - - make - -j5 - check.wrap - true - true - true - - - make - -j5 - testMethod.run - true - true - true - - - make - -j5 - testClass.run - true - true - true - - - make - -j4 - testType.run - true - true - true - - - make - -j4 - testArgument.run - true - true - true - - - make - -j4 - testReturnValue.run - true - true - true - - - make - -j4 - testTemplate.run - true - true - true - - - make - -j4 - testGlobalFunction.run - true - true - true - - - make - -j2 - all - true - true - true - - - make - -j2 - clean - true - true - true - - - make - -j5 - testMatrix.run - true - true - true - - - make - -j5 - testVector.run - true - true - true - - - make - -j5 - testNumericalDerivative.run - true - true - true - - - make - -j5 - testVerticalBlockMatrix.run - true - true - true - - - make - -j4 - testOptionalJacobian.run - true - true - true - - - make - -j4 - testGroup.run - true - true - true - - - make - -j5 - check.tests - true - true - true - - - make - -j2 - timeGaussianFactorGraph.run - true - true - true - - - make - -j5 - testMarginals.run - true - true - true - - - make - -j5 - testGaussianISAM2.run - true - true - true - - - make - -j5 - testSymbolicFactorGraphB.run - true - true - true - - - make - -j2 - timeSequentialOnDataset.run - true - true - true - - - make - -j5 - testGradientDescentOptimizer.run - true - true - true - - - make - -j2 - testGaussianFactor.run - true - true - true - - - make - -j2 - testNonlinearOptimizer.run - true - true - true - - - make - -j2 - testGaussianBayesNet.run - true - true - true - - - make - -j2 - testNonlinearISAM.run - true - true - true - - - make - -j2 - testNonlinearEquality.run - true - true - true - - - make - -j2 - testExtendedKalmanFilter.run - true - true - true - - - make - -j5 - timing.tests - true - true - true - - - make - -j5 - testNonlinearFactor.run - true - true - true - - - make - -j5 - clean - true - true - true - - - make - -j5 - testGaussianJunctionTreeB.run - true - true - true - - - make - testGraph.run - true - false - true - - - make - testJunctionTree.run - true - false - true - - - make - testSymbolicBayesNetB.run - true - false - true - - - make - -j5 - testGaussianISAM.run - true - true - true - - - make - -j5 - testDoglegOptimizer.run - true - true - true - - - make - -j5 - testNonlinearFactorGraph.run - true - true - true - - - make - -j5 - testIterative.run - true - true - true - - - make - -j5 - testSubgraphSolver.run - true - true - true - - - make - -j5 - testGaussianFactorGraphB.run - true - true - true - - - make - -j5 - testSummarization.run - true - true - true - - - make - -j5 - testManifold.run - true - true - true - - - make - -j4 - testLie.run - true - true - true - - - make - -j2 - vSFMexample.run - true - true - true - - - make - -j5 - clean - true - true - true - - - make - -j5 - all - true - true - true - - - make - -j2 - check - true - true - true - - - make - -j2 - testVSLAMGraph + wrap true true true 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/SolverComparer.cpp b/examples/SolverComparer.cpp index 068846884..2000b348b 100644 --- a/examples/SolverComparer.cpp +++ b/examples/SolverComparer.cpp @@ -32,7 +32,7 @@ */ #include -#include +#include #include #include #include diff --git a/gtsam.h b/gtsam.h index ebd554549..1ddae3f48 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(); @@ -2262,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); @@ -2272,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; @@ -2293,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 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/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/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..6746236be 100644 --- a/gtsam/base/Manifold.h +++ b/gtsam/base/Manifold.h @@ -187,8 +187,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/OptionalJacobian.h b/gtsam/base/OptionalJacobian.h index d0e2297ef..c0ac8cd7f 100644 --- a/gtsam/base/OptionalJacobian.h +++ b/gtsam/base/OptionalJacobian.h @@ -171,6 +171,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/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/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/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/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/CalibratedCamera.h b/gtsam/geometry/CalibratedCamera.h index 4d605ef4e..b1e5917b2 100644 --- a/gtsam/geometry/CalibratedCamera.h +++ b/gtsam/geometry/CalibratedCamera.h @@ -18,6 +18,7 @@ #pragma once +#include #include #include #include @@ -318,7 +319,7 @@ public: } /// @} - /// @name Transformations and mesaurement functions + /// @name Transformations and measurement functions /// @{ /** @@ -384,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/PinholeCamera.h b/gtsam/geometry/PinholeCamera.h index 12e9f023b..6177dec95 100644 --- a/gtsam/geometry/PinholeCamera.h +++ b/gtsam/geometry/PinholeCamera.h @@ -19,6 +19,7 @@ #pragma once #include +#include namespace gtsam { @@ -263,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<1, 6>(0, 0) = 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) */ @@ -304,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/Point3.h b/gtsam/geometry/Point3.h index 883e5fb62..e8cf0be7b 100644 --- a/gtsam/geometry/Point3.h +++ b/gtsam/geometry/Point3.h @@ -22,6 +22,7 @@ #pragma once #include +#include #include #include @@ -199,4 +200,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.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 e549cb009..ac08f0797 100644 --- a/gtsam/geometry/Pose3.cpp +++ b/gtsam/geometry/Pose3.cpp @@ -314,35 +314,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(); 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/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/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/testPose3.cpp b/gtsam/geometry/tests/testPose3.cpp index cf6ca9bfb..f6f8b7b40 100644 --- a/gtsam/geometry/tests/testPose3.cpp +++ b/gtsam/geometry/tests/testPose3.cpp @@ -633,6 +633,22 @@ 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 ) { 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/nonlinear/Expression.h b/gtsam/nonlinear/Expression.h index 4fdbe8610..0b348ece9 100644 --- a/gtsam/nonlinear/Expression.h +++ b/gtsam/nonlinear/Expression.h @@ -172,6 +172,9 @@ public: private: + /// Default constructor, for serialization + Expression() {} + /// Keys and dimensions in same order typedef std::pair > KeysAndDims; KeysAndDims keysAndDims() const; diff --git a/gtsam/nonlinear/ExpressionFactor.h b/gtsam/nonlinear/ExpressionFactor.h index cac55563f..5d6d28061 100644 --- a/gtsam/nonlinear/ExpressionFactor.h +++ b/gtsam/nonlinear/ExpressionFactor.h @@ -23,43 +23,54 @@ #include #include #include - namespace gtsam { /** + * Factor that supports arbitrary expressions via AD */ -template +template class ExpressionFactor: public NoiseModelFactor { + BOOST_CONCEPT_ASSERT((IsTestable)); 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; + 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_; } /** @@ -71,10 +82,10 @@ public: boost::optional&> H = boost::none) const { if (H) { const T value = expression_.valueAndDerivatives(x, keys_, dims_, *H); - return traits::Local(measurement_, value); + return traits::Local(measured_, value); } else { const T value = expression_.value(x); - return traits::Local(measurement_, value); + return traits::Local(measured_, value); } } @@ -105,7 +116,7 @@ public: 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(measured_, value); // Whiten the corresponding system, Ab already contains RHS Vector b = Ab(size()).col(0); // need b to be valid for Robust noise models @@ -119,8 +130,116 @@ public: return boost::static_pointer_cast( 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/expressionTesting.h b/gtsam/nonlinear/expressionTesting.h index f2f1c9578..b15592c00 100644 --- a/gtsam/nonlinear/expressionTesting.h +++ b/gtsam/nonlinear/expressionTesting.h @@ -20,44 +20,11 @@ #pragma once #include -#include #include -#include #include -#include - -#include -#include -#include namespace gtsam { -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)); - - // Check cast result and then equality - return actual && 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) \ - { EXPECT(gtsam::internal::testFactorJacobians(result_, name_, factor, values, numerical_derivative_step, tolerance)); } - namespace internal { // CPPUnitLite-style test for linearization of an ExpressionFactor template diff --git a/gtsam/nonlinear/factorTesting.h b/gtsam/nonlinear/factorTesting.h index 442b29382..52f103630 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,30 @@ 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)); + + // Check cast result and then equality + return actual && 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) \ + { EXPECT(gtsam::internal::testFactorJacobians(result_, name_, factor, values, numerical_derivative_step, tolerance)); } + } // namespace gtsam 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..1ad27865d --- /dev/null +++ b/gtsam/sam/RangeFactor.h @@ -0,0 +1,142 @@ +/* ---------------------------------------------------------------------------- + + * 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 ::result_type> +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..b7fcfc9aa --- /dev/null +++ b/gtsam/sam/tests/testBearingFactor.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 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)); +} + +/* ************************************************************************* */ +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..e11e62628 --- /dev/null +++ b/gtsam/sam/tests/testBearingRangeFactor.cpp @@ -0,0 +1,106 @@ +/* ---------------------------------------------------------------------------- + + * 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)); +} + +/* ************************************************************************* */ +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/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/dataset.cpp b/gtsam/slam/dataset.cpp index 70b6eb622..04234bacc 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 diff --git a/gtsam/slam/tests/testGeneralSFMFactor.cpp b/gtsam/slam/tests/testGeneralSFMFactor.cpp index a8f85301e..a634928dc 100644 --- a/gtsam/slam/tests/testGeneralSFMFactor.cpp +++ b/gtsam/slam/tests/testGeneralSFMFactor.cpp @@ -17,7 +17,7 @@ */ #include -#include +#include #include #include #include diff --git a/gtsam/slam/tests/testGeneralSFMFactor_Cal3Bundler.cpp b/gtsam/slam/tests/testGeneralSFMFactor_Cal3Bundler.cpp index f812cd308..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 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_unstable/dynamics/PoseRTV.h b/gtsam_unstable/dynamics/PoseRTV.h index 78bd1fe6f..a6bc6006a 100644 --- a/gtsam_unstable/dynamics/PoseRTV.h +++ b/gtsam_unstable/dynamics/PoseRTV.h @@ -170,4 +170,17 @@ private: template<> struct traits : public internal::LieGroup {}; +// Define Range functor specializations that are used in RangeFactor +template struct Range; + +template <> +struct Range { + typedef double result_type; + double operator()(const PoseRTV& pose1, const PoseRTV& pose2, + OptionalJacobian<1, 9> H1 = boost::none, + OptionalJacobian<1, 9> H2 = boost::none) { + return pose1.range(pose2, H1, H2); + } +}; + } // \namespace gtsam diff --git a/gtsam_unstable/dynamics/tests/testIMUSystem.cpp b/gtsam_unstable/dynamics/tests/testIMUSystem.cpp index d97f185e7..51d027b3c 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 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/gtsam_unstable.h b/gtsam_unstable/gtsam_unstable.h index 6b57bfcd0..bbfcaa418 100644 --- a/gtsam_unstable/gtsam_unstable.h +++ b/gtsam_unstable/gtsam_unstable.h @@ -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/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/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/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/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 7922c14d1..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; } diff --git a/tests/testGaussianJunctionTreeB.cpp b/tests/testGaussianJunctionTreeB.cpp index 98adfc1dc..e877e5a9d 100644 --- a/tests/testGaussianJunctionTreeB.cpp +++ b/tests/testGaussianJunctionTreeB.cpp @@ -16,7 +16,7 @@ */ #include -#include +#include #include #include #include diff --git a/tests/testMarginals.cpp b/tests/testMarginals.cpp index bd202e991..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 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/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/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));