diff --git a/.cproject b/.cproject index ab1d0cdfc..77ccd8a14 100644 --- a/.cproject +++ b/.cproject @@ -5,13 +5,13 @@ - - + + @@ -60,13 +60,13 @@ - - + + @@ -116,13 +116,13 @@ - - + + @@ -130,7 +130,7 @@ - + @@ -176,8 +176,16 @@ - - + + + + + + + + + + @@ -484,333 +492,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 - -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 @@ -835,6 +516,38 @@ true true + + make + -j5 + SFMExampleExpressions.run + true + true + true + + + make + -j5 + Pose2SLAMExampleExpressions.run + true + true + true + + + make + -j5 + testInvDepthCamera3.run + true + true + true + + + make + -j5 + testTriangulation.run + true + true + true + make -j2 @@ -859,167 +572,7 @@ 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 - true - true - true - - - make - -j4 - testQuaternion.run - true - true - true - - - make - -j4 - testOrientedPlane3.run - true - true - true - - + make -j2 all @@ -1027,7 +580,7 @@ true true - + make -j2 clean @@ -1035,23 +588,137 @@ 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 @@ -1195,10 +862,505 @@ true true - + make - -j4 - testTOAFactor.run + -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 + timeCameraExpression.run + true + true + true + + + make + -j5 + timeOneCameraExpression.run + true + true + true + + + make + -j5 + timeSFMExpressions.run + true + true + true + + + make + -j5 + timeAdaptAutoDiff.run + true + true + true + + + make + -j5 + testCombinedImuFactor.run + true + true + true + + + make + -j5 + testImuFactor.run + true + true + true + + + make + -j5 + testAHRSFactor.run + true + true + true + + + make + -j8 + testAttitudeFactor.run + true + true + true + + + make + -j5 + clean + true + true + true + + + make + -j5 + all + true + true + true + + + make + -j2 + all + true + true + true + + + make + -j2 + clean + true + true + true + + + make + -j2 + check + true + true + true + + + make + -j2 + testGaussianConditional.run + true + true + true + + + make + -j2 + testGaussianFactor.run + true + true + true + + + make + -j2 + timeGaussianFactor.run + true + true + true + + + make + -j2 + timeVectorConfig.run + true + true + true + + + make + -j2 + testVectorBTree.run + true + true + true + + + make + -j2 + testVectorMap.run + true + true + true + + + make + -j2 + testNoiseModel.run + true + true + true + + + make + -j2 + testBayesNetPreconditioner.run + true + true + true + + + make + testErrors.run + true + false + true + + + make + -j2 + check + true + true + true + + + make + -j2 + tests/testGaussianJunctionTree.run + true + true + true + + + make + -j2 + tests/testGaussianFactor.run + true + true + true + + + make + -j2 + tests/testGaussianConditional.run + true + true + true + + + make + -j2 + tests/timeSLAMlike.run + true + true + true + + + make + -j2 + check + true + true + true + + + make + -j2 + clean + true + true + true + + + make + -j2 + testBTree.run + true + true + true + + + make + -j2 + testDSF.run + true + true + true + + + make + -j2 + testDSFVector.run + true + true + true + + + make + -j2 + testMatrix.run + true + true + true + + + make + -j2 + testSPQRUtil.run + true + true + true + + + make + -j2 + testVector.run + true + true + true + + + make + -j2 + timeMatrix.run + true + true + true + + + make + -j2 + all + true + true + true + + + make + -j2 + check + true + true + true + + + make + -j2 + testClusterTree.run + true + true + true + + + make + -j2 + testJunctionTree.run + true + true + true + + + make + -j2 + tests/testEliminationTree.run + true + true + true + + + make + -j2 + tests/testSymbolicFactor.run + true + true + true + + + make + -j2 + tests/testVariableSlots.run + true + true + true + + + make + -j2 + tests/testConditional.run + true + true + true + + + make + -j2 + tests/testSymbolicFactorGraph.run + true + true + true + + + make + -j2 + all + true + true + true + + + make + -j2 + testNonlinearConstraint.run + true + true + true + + + make + -j2 + testLieConfig.run + true + true + true + + + make + -j2 + testConstraintOptimizer.run + true + true + true + + + make + -j2 + check true true true @@ -1347,23 +1509,87 @@ true true - + make - -j2 - all + -j5 + testBTree.run true true true - + make - -j2 - clean + -j5 + testDSF.run true true true - + + make + -j5 + testDSFMap.run + true + true + true + + + make + -j5 + testDSFVector.run + true + true + true + + + make + -j5 + testFixedVector.run + true + true + true + + + make + -j5 + testEliminationTree.run + true + true + true + + + make + -j5 + testInference.run + true + true + true + + + make + -j5 + testKey.run + true + true + true + + + make + -j1 + testSymbolicBayesTree.run + true + false + true + + + make + -j1 + testSymbolicSequentialSolver.run + true + false + true + + make -j2 check @@ -1371,179 +1597,20 @@ true true - + make -j2 - testGaussianConditional.run - true - true - true - - - make - -j2 - testGaussianFactor.run - true - true - true - - - make - -j2 - timeGaussianFactor.run - true - true - true - - - make - -j2 - timeVectorConfig.run - true - true - true - - - make - -j2 - testVectorBTree.run - true - true - true - - - make - -j2 - testVectorMap.run - true - true - true - - - make - -j2 - testNoiseModel.run - true - true - true - - - make - -j2 - testBayesNetPreconditioner.run - true - true - true - - - make - testErrors.run - true - false - true - - - make - -j5 - testAntiFactor.run - true - true - true - - - make - -j5 - testPriorFactor.run - true - true - true - - - make - -j5 - testDataset.run - true - true - true - - - make - -j5 - testEssentialMatrixFactor.run - true - true - true - - - make - -j5 - testGeneralSFMFactor_Cal3Bundler.run - true - true - true - - - make - -j5 - testGeneralSFMFactor.run - true - true - true - - - make - -j5 - testProjectionFactor.run - true - true - true - - - make - -j5 - testRotateFactor.run - true - true - true - - - make - -j5 - testPoseRotationPrior.run - true - true - true - - - make - -j5 - testImplicitSchurFactor.run - true - true - true - - - make - -j4 - testRangeFactor.run - true - true - true - - - make - -j4 - testOrientedPlane3Factor.run + tests/testLieConfig.run true true true make - -j3 + -j8 install true - false + true true @@ -1933,15 +2000,23 @@ true true - - make - -j2 VERBOSE=1 - check.navigation + + cmake-gui + .. + true false true - + + make + -j8 + testLCNLPSolver.run + true + true + true + + make -j2 check @@ -1949,55 +2024,54 @@ 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 - + + cmake-gui + .. + + true + false + true + + make - -j2 - check + -j8 + testLCNLPSolver.run 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 @@ -2005,513 +2079,151 @@ true true - + make -j5 - testParticleFactor.run + testCal3Bundler.run true true true - + make -j5 - testExpressionMeta.run + testCal3DS2.run true true true - - make - -j4 - testCustomChartExpression.run - true - true - true - - + make -j5 - schedulingExample.run - true - true - true - - - make - -j5 - schedulingQuals12.run - true - true - true - - - make - -j5 - schedulingQuals13.run - true - true - true - - - make - -j5 - testCSP.run - true - true - true - - - make - -j5 - testScheduler.run - true - true - true - - - make - -j5 - testSudoku.run - true - true - true - - - make - -j2 - all - true - true - true - - - make - -j2 - clean - true - true - true - - - make - -k - check - true - false - true - - - make - tests/testBayesTree.run - true - false - true - - - make - testBinaryBayesNet.run - true - false - true - - - make - -j2 - testFactorGraph.run - true - true - true - - - make - -j2 - testISAM.run - true - true - true - - - make - -j2 - testJunctionTree.run - true - true - true - - - make - -j2 - testKey.run - true - true - true - - - make - -j2 - testOrdering.run - true - true - true - - - make - testSymbolicBayesNet.run - true - false - true - - - make - tests/testSymbolicFactor.run - true - false - true - - - make - testSymbolicFactorGraph.run - true - false - true - - - make - -j2 - timeSymbolMaps.run - true - true - true - - - make - tests/testBayesTree - true - false - true - - - make - -j2 - check - true - true - true - - - make - -j2 - timeCalibratedCamera.run - true - true - true - - - make - -j2 - timeRot3.run - true - true - true - - - make - -j2 - clean - true - true - true - - - make - -j2 - tests/testPose2.run - true - true - true - - - make - -j2 - tests/testPose3.run - true - true - true - - - make - -j2 - SimpleRotation.run - true - true - true - - - make - -j5 - CameraResectioning.run - true - true - true - - - make - -j5 - PlanarSLAMExample.run - true - true - true - - - make - -j2 - all - true - true - true - - - make - -j2 - easyPoint2KalmanFilter.run - true - true - true - - - make - -j2 - elaboratePoint2KalmanFilter.run - true - true - true - - - make - -j5 - Pose2SLAMExample.run - true - true - true - - - make - -j2 - Pose2SLAMwSPCG_easy.run - true - true - true - - - make - -j5 - UGM_small.run - true - true - true - - - make - -j5 - LocalizationExample.run - true - true - true - - - make - -j5 - OdometryExample.run - true - true - true - - - make - -j5 - RangeISAMExample_plaza2.run - true - true - true - - - make - -j5 - SelfCalibrationExample.run - true - true - true - - - make - -j5 - SFMExample.run - true - true - true - - - make - -j5 - VisualISAMExample.run - true - true - true - - - make - -j5 - VisualISAM2Example.run - true - true - true - - - make - -j5 - Pose2SLAMExample_graphviz.run - true - true - true - - - make - -j5 - Pose2SLAMExample_graph.run - true - true - true - - - make - -j5 - SFMExample_bal.run - true - true - true - - - make - -j5 - Pose2SLAMExample_lago.run - true - true - true - - - make - -j5 - Pose2SLAMExample_g2o.run - true - true - true - - - make - -j5 - SFMExample_SmartFactor.run - true - true - true - - - make - -j4 - Pose2SLAMExampleExpressions.run - true - true - true - - - make - -j4 - SFMExampleExpressions.run - true - true - true - - - make - -j4 - SFMExampleExpressions_bal.run - true - true - true - - - make - -j2 - testRot3.run - true - true - true - - - make - -j2 - testRot2.run - true - true - true - - - make - -j2 - testPose3.run - true - true - true - - - make - -j2 - timeRot3.run - true - true - true - - - make - -j2 - testPose2.run - true - true - true - - - make - -j2 - testCal3_S2.run - true - true - true - - - make - -j2 - testSimpleCamera.run - true - true - true - - - make - -j2 - testHomography2.run - true - true - true - - - make - -j2 testCalibratedCamera.run true true true - + + make + -j5 + testEssentialMatrix.run + true + true + true + + + make + -j1 VERBOSE=1 + testHomography2.run + true + false + true + + + make + -j5 + testPinholeCamera.run + true + true + true + + + make + -j5 + testPoint2.run + true + true + true + + + make + -j5 + testPoint3.run + true + true + true + + + make + -j5 + testPose2.run + true + true + true + + + make + -j5 + testPose3.run + true + true + true + + + make + -j5 + testRot3M.run + true + true + true + + + make + -j5 + testSphere2.run + true + true + true + + + make + -j5 + testStereoCamera.run + true + true + true + + + make + -j5 + testCal3Unified.run + true + true + true + + + make + -j5 + testRot2.run + true + true + true + + + make + -j5 + testRot3Q.run + true + true + true + + + make + -j5 + testRot3.run + true + true + true + + + make + -j2 + all + true + true + true + + make -j2 check @@ -2519,7 +2231,7 @@ true true - + make -j2 clean @@ -2527,10 +2239,90 @@ true true - + + make + -j5 + all + true + false + true + + + make + -j5 + check + true + false + true + + make -j2 - testPoint2.run + all + true + true + true + + + make + -j2 + clean + true + true + true + + + make + -j2 + all + true + true + true + + + make + -j2 + clean + true + true + true + + + make + -j2 + clean all + true + true + true + + + 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 @@ -2575,55 +2367,7 @@ true true - - make - -j5 - testEliminationTree.run - true - true - true - - - make - -j5 - testInference.run - true - true - true - - - make - -j5 - testKey.run - true - true - true - - - make - -j1 - testSymbolicBayesTree.run - true - false - true - - - make - -j1 - testSymbolicSequentialSolver.run - true - false - true - - - make - -j4 - testLabeledSymbol.run - true - true - true - - + make -j2 check @@ -2631,295 +2375,23 @@ true true - + make -j2 - testClusterTree.run - true - true - true - - - make - -j2 - testJunctionTree.run - true - true - true - - - make - -j2 - tests/testEliminationTree.run - true - true - true - - - make - -j2 - tests/testSymbolicFactor.run - true - true - true - - - make - -j2 - tests/testVariableSlots.run - true - true - true - - - make - -j2 - tests/testConditional.run - true - true - true - - - make - -j2 - tests/testSymbolicFactorGraph.run - true - true - true - - - make - -j5 - testLago.run - true - true - true - - - make - -j5 - testLinearContainerFactor.run - true - true - true - - - make - -j5 - testOrdering.run - true - true - true - - - make - -j5 - testValues.run - true - true - true - - - make - -j5 - testWhiteNoiseFactor.run - true - true - true - - - make - -j4 - testExpression.run - true - true - true - - - make - -j4 - testAdaptAutoDiff.run - true - true - true - - - make - -j4 - testCallRecord.run - true - true - true - - - make - -j4 - testExpressionFactor.run - true - true - true - - - make - -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 - -j5 - testBTree.run - true - true - true - - - make - -j5 - testDSF.run - true - true - true - - - make - -j5 - testDSFMap.run - true - true - true - - - make - -j5 - testDSFVector.run - true - true - true - - - make - -j5 - testFixedVector.run - true - true - true - - + make -j2 - all + timeRot3.run true true true - + make -j2 clean @@ -2927,110 +2399,6 @@ true true - - make - -j5 - testGaussianFactorGraphUnordered.run - true - true - true - - - make - -j5 - testGaussianBayesNetUnordered.run - true - true - true - - - make - -j5 - testGaussianConditional.run - true - true - true - - - make - -j5 - testGaussianDensity.run - true - true - true - - - make - -j5 - testGaussianJunctionTree.run - true - true - true - - - make - -j5 - testHessianFactor.run - true - true - true - - - make - -j5 - testJacobianFactor.run - true - true - true - - - make - -j5 - testKalmanFilter.run - true - true - true - - - make - -j5 - testNoiseModel.run - true - true - true - - - make - -j5 - testSampler.run - true - true - true - - - make - -j5 - testSerializationLinear.run - true - true - true - - - make - -j5 - testVectorValues.run - true - true - true - - - make - -j5 - testGaussianBayesTree.run - true - true - true - make -j5 @@ -3111,18 +2479,66 @@ true true - + make - -j2 - all + -j5 + schedulingExample.run true true true - + + make + -j5 + schedulingQuals12.run + true + true + true + + + make + -j5 + schedulingQuals13.run + true + true + true + + + make + -j5 + testCSP.run + true + true + true + + + make + -j5 + testScheduler.run + true + true + true + + + make + -j5 + testSudoku.run + true + true + true + + make -j2 - clean + vSFMexample.run + true + true + true + + + make + -j2 + testVSLAMGraph true true true @@ -3159,14 +2575,6 @@ true true - - make - -j4 - testOptionalJacobian.run - true - true - true - make -j5 @@ -3388,31 +2796,479 @@ true true - + make - -j2 - vSFMexample.run + -j5 + testParticleFactor.run true true true - + make -j5 + testExpressionFactor.run + true + true + true + + + make + -j5 + testExpressionMeta.run + true + true + true + + + make + -j5 + testAdaptAutoDiff.run + true + true + true + + + make + -j5 + testCallRecord.run + true + true + true + + + make + -j4 + testBasisDecompositions.run + true + true + true + + + make + -j4 + testCustomChartExpression.run + true + true + true + + + make + -j2 + testGaussianFactor.run + true + true + true + + + make + -j2 + install + true + true + true + + + make + -j2 clean true true true - + make - -j5 + -j2 all true true true - + + make + -j2 + clean + true + true + true + + + make + -j2 + all + true + true + true + + + make + -j2 + clean + true + true + true + + + make + -j5 + testAntiFactor.run + true + true + true + + + make + -j5 + testPriorFactor.run + true + true + true + + + make + -j5 + testDataset.run + true + true + true + + + make + -j5 + testEssentialMatrixFactor.run + true + true + true + + + make + -j5 + testGeneralSFMFactor_Cal3Bundler.run + true + true + true + + + make + -j5 + testGeneralSFMFactor.run + true + true + true + + + make + -j5 + testProjectionFactor.run + true + true + true + + + make + -j5 + testRotateFactor.run + true + true + true + + + make + -j5 + testPoseRotationPrior.run + true + true + true + + + make + -j5 + testImplicitSchurFactor.run + true + true + true + + + make + -j4 + testRangeFactor.run + true + true + true + + + make + -j2 + SimpleRotation.run + true + true + true + + + make + -j5 + CameraResectioning.run + true + true + true + + + make + -j5 + PlanarSLAMExample.run + true + true + true + + + make + -j2 + all + true + true + true + + + make + -j2 + easyPoint2KalmanFilter.run + true + true + true + + + make + -j2 + elaboratePoint2KalmanFilter.run + true + true + true + + + make + -j5 + Pose2SLAMExample.run + true + true + true + + + make + -j2 + Pose2SLAMwSPCG_easy.run + true + true + true + + + make + -j5 + UGM_small.run + true + true + true + + + make + -j5 + LocalizationExample.run + true + true + true + + + make + -j5 + OdometryExample.run + true + true + true + + + make + -j5 + RangeISAMExample_plaza2.run + true + true + true + + + make + -j5 + SelfCalibrationExample.run + true + true + true + + + make + -j5 + SFMExample.run + true + true + true + + + make + -j5 + VisualISAMExample.run + true + true + true + + + make + -j5 + VisualISAM2Example.run + true + true + true + + + make + -j5 + Pose2SLAMExample_graphviz.run + true + true + true + + + make + -j5 + Pose2SLAMExample_graph.run + true + true + true + + + make + -j5 + SFMExample_bal.run + true + true + true + + + make + -j5 + Pose2SLAMExample_lago.run + true + true + true + + + make + -j5 + Pose2SLAMExample_g2o.run + true + true + true + + + make + -j5 + SFMExample_SmartFactor.run + true + true + true + + + make + -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 + testImuFactor.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 -j2 check @@ -3420,10 +3276,114 @@ true true - + + make + + tests/testGaussianISAM2 + true + false + true + + make -j2 - testVSLAMGraph + testRot3.run + true + true + true + + + make + -j2 + testRot2.run + true + true + true + + + make + -j2 + testPose3.run + true + true + true + + + make + -j2 + timeRot3.run + true + true + true + + + make + -j2 + testPose2.run + true + true + true + + + make + -j2 + testCal3_S2.run + true + true + true + + + make + -j2 + testSimpleCamera.run + true + true + true + + + make + -j2 + testHomography2.run + true + true + true + + + make + -j2 + testCalibratedCamera.run + true + true + true + + + make + -j2 + check + true + true + true + + + make + -j2 + clean + true + true + true + + + make + -j2 + testPoint2.run + true + true + true + + + make + -j5 + wrap true true true diff --git a/gtsam_unstable/linear/QPSolver.cpp b/gtsam_unstable/linear/QPSolver.cpp index 10d248d29..84ef6cb3a 100644 --- a/gtsam_unstable/linear/QPSolver.cpp +++ b/gtsam_unstable/linear/QPSolver.cpp @@ -217,15 +217,15 @@ QPState QPSolver::iterate(const QPState& state) const { //****************************************************************************** LinearInequalityFactorGraph QPSolver::identifyActiveConstraints( const LinearInequalityFactorGraph& inequalities, - const VectorValues& initialValues, const VectorValues& duals) const { + const VectorValues& initialValues, const VectorValues& duals, bool useWarmStart) const { LinearInequalityFactorGraph workingSet; BOOST_FOREACH(const LinearInequality::shared_ptr& factor, inequalities) { LinearInequality::shared_ptr workingFactor(new LinearInequality(*factor)); - if (duals.exists(workingFactor->dualKey())) { + if (useWarmStart == true && duals.exists(workingFactor->dualKey())) { workingFactor->activate(); } else { - if (duals.size() > 0) { + if (useWarmStart == true && duals.size() > 0) { workingFactor->inactivate(); } else { double error = workingFactor->error(initialValues); @@ -244,11 +244,11 @@ LinearInequalityFactorGraph QPSolver::identifyActiveConstraints( //****************************************************************************** pair QPSolver::optimize( - const VectorValues& initialValues, const VectorValues& duals) const { + const VectorValues& initialValues, const VectorValues& duals, bool useWarmStart) const { // Initialize workingSet from the feasible initialValues LinearInequalityFactorGraph workingSet = - identifyActiveConstraints(qp_.inequalities, initialValues, duals); + identifyActiveConstraints(qp_.inequalities, initialValues, duals, useWarmStart); QPState state(initialValues, duals, workingSet, false, 0); /// main loop of the solver diff --git a/gtsam_unstable/linear/QPSolver.h b/gtsam_unstable/linear/QPSolver.h index 52a6f2f37..90fea4f70 100644 --- a/gtsam_unstable/linear/QPSolver.h +++ b/gtsam_unstable/linear/QPSolver.h @@ -185,7 +185,7 @@ public: LinearInequalityFactorGraph identifyActiveConstraints( const LinearInequalityFactorGraph& inequalities, const VectorValues& initialValues, - const VectorValues& duals = VectorValues()) const; + const VectorValues& duals = VectorValues(), bool useWarmStart = true) const; /** Optimize with a provided initial values * For this version, it is the responsibility of the caller to provide @@ -193,7 +193,7 @@ public: * @return a pair of solutions */ std::pair optimize( - const VectorValues& initialValues, const VectorValues& duals = VectorValues()) const; + const VectorValues& initialValues, const VectorValues& duals = VectorValues(), bool useWarmStart = true) const; }; diff --git a/gtsam_unstable/nonlinear/LCNLPSolver.cpp b/gtsam_unstable/nonlinear/LCNLPSolver.cpp index 99022ff5d..fe96878fb 100644 --- a/gtsam_unstable/nonlinear/LCNLPSolver.cpp +++ b/gtsam_unstable/nonlinear/LCNLPSolver.cpp @@ -70,13 +70,13 @@ VectorValues LCNLPSolver::initializeDuals() const { } /* ************************************************************************* */ -std::pair LCNLPSolver::optimize(const Values& initialValues, bool debug) const { +std::pair LCNLPSolver::optimize(const Values& initialValues, bool useWarmStart, bool debug) const { LCNLPState state(initialValues); state.duals = initializeDuals(); while (!state.converged && state.iterations < 100) { if (debug) std::cout << "state: iteration " << state.iterations << std::endl; - state = iterate(state, debug); + state = iterate(state, useWarmStart, debug); } if (debug) std::cout << "Number of iterations: " << state.iterations << std::endl; @@ -84,7 +84,7 @@ std::pair LCNLPSolver::optimize(const Values& initialValue } /* ************************************************************************* */ -LCNLPState LCNLPSolver::iterate(const LCNLPState& state, bool debug) const { +LCNLPState LCNLPSolver::iterate(const LCNLPState& state, bool useWarmStart, bool debug) const { // construct the qp subproblem QP qp; @@ -98,14 +98,14 @@ LCNLPState LCNLPSolver::iterate(const LCNLPState& state, bool debug) const { // solve the QP subproblem VectorValues delta, duals; QPSolver qpSolver(qp); - if (state.iterations == 0) + if (useWarmStart == false || state.iterations == 0) boost::tie(delta, duals) = qpSolver.optimize(); else { VectorValues zeroInitialValues; BOOST_FOREACH(const Values::ConstKeyValuePair& key_value, state.values) { zeroInitialValues.insert(key_value.key, zero(key_value.value.dim())); } - boost::tie(delta, duals) = qpSolver.optimize(zeroInitialValues, state.duals); + boost::tie(delta, duals) = qpSolver.optimize(zeroInitialValues, state.duals, useWarmStart); } if (debug) diff --git a/gtsam_unstable/nonlinear/LCNLPSolver.h b/gtsam_unstable/nonlinear/LCNLPSolver.h index 047fca38b..47f6f86ae 100644 --- a/gtsam_unstable/nonlinear/LCNLPSolver.h +++ b/gtsam_unstable/nonlinear/LCNLPSolver.h @@ -104,13 +104,13 @@ public: /** * Single iteration of SQP */ - LCNLPState iterate(const LCNLPState& state, bool debug = false) const; + LCNLPState iterate(const LCNLPState& state, bool useWarmStart = true, bool debug = false) const; VectorValues initializeDuals() const; /** * Main optimization function. new */ - std::pair optimize(const Values& initialValues, bool debug = false) const; + std::pair optimize(const Values& initialValues, bool useWarmStart = true, bool debug = false) const; }; } diff --git a/gtsam_unstable/nonlinear/tests/testLCNLPSolver.cpp b/gtsam_unstable/nonlinear/tests/testLCNLPSolver.cpp index edfc3bee6..0b37e2a0d 100644 --- a/gtsam_unstable/nonlinear/tests/testLCNLPSolver.cpp +++ b/gtsam_unstable/nonlinear/tests/testLCNLPSolver.cpp @@ -348,7 +348,8 @@ TEST(testlcnlpSolver, posesInA2DBox) { // Instantiate LCNLPSolver LCNLPSolver lcnlpSolver(lcnlp); - Values actualSolution = lcnlpSolver.optimize(initialValues).first; + bool useWarmStart = true; + Values actualSolution = lcnlpSolver.optimize(initialValues, useWarmStart).first; // cout << "Rotation angles: " << endl; // for (size_t i = 1; i<=3; i++) { @@ -367,6 +368,7 @@ TEST(testlcnlpSolver, posesInA2DBox) { //****************************************************************************** int main() { + cout<<"here: "<