diff --git a/.cproject b/.cproject index 9b476b986..790f70daa 100644 --- a/.cproject +++ b/.cproject @@ -1,5 +1,7 @@ - + + + @@ -291,152 +293,6 @@ - - make - -j2 - check - true - true - true - - - make - -j2 - tests/testSPQRUtil.run - true - true - true - - - make - -j2 - clean - true - true - true - - - make - -j2 - testGaussianFactor.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 -j5 @@ -453,234 +309,10 @@ true true - - make - -j5 - testBTree.run - true - true - true - - - make - -j5 - testDSF.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 - 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 - tests/testPose2.run - true - true - true - - - make - -j2 - tests/testPose3.run - true - true - true - - - make - -j2 - all - true - true - true - - - make - -j2 - clean - true - true - true - - - make - -j2 - clean all - true - true - true - - - make - -j5 - testValues.run - true - true - true - - - make - -j5 - testOrdering.run - true - true - true - - - make - -j5 - testKey.run - true - true - true - - - make - -j5 - testLinearContainerFactor.run - true - true - true - - - make - -j6 -j8 - testWhiteNoiseFactor.run - true - true - true - - - make - -j5 - testGeneralSFMFactor.run - true - true - true - - - make - -j5 - testProjectionFactor.run - true - true - true - - - make - -j5 - testGeneralSFMFactor_Cal3Bundler.run - true - true - true - - - make - -j6 -j8 - testAntiFactor.run - true - true - true - - - make - -j6 -j8 - testBetweenFactor.run - true - true - true - - - make - -j2 - all - true - true - true - - - make - -j2 - check - true - true - true - - - make - -j2 - clean + testGaussianFactor.run true true true @@ -733,172 +365,116 @@ 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 - testInvDepthFactor3.run + testStereoCamera.run true true true - + make -j5 - testPoseTranslationPrior.run + testRot3M.run true true true - + make -j5 - testPoseRotationPrior.run + testPoint3.run true true true - + make -j5 - testReferenceFrameFactor.run + testCalibratedCamera.run true true true - + make -j5 - testAHRS.run + timeStereoCamera.run true true true - + make - -j8 - testImuFactor.run - true - true - true - - - make - -j5 - testMultiProjectionFactor.run - true - true - true - - - make - -j5 - testSmartProjectionFactor.run - true - true - true - - - make - -j5 - testDiscreteFactor.run - true - true - true - - - make - -j1 - testDiscreteBayesTree.run + -j1 VERBOSE=1 + testHomography2.run true false true - + make -j5 - testDiscreteFactorGraph.run + testPoint2.run true true true - + make -j5 - testDiscreteConditional.run + testPose2.run true true true - + make -j5 - testDiscreteMarginals.run + testPose3.run true true true - + make -j5 - testInference.run + testCal3_S2.run true true true - + make - -j1 - testSymbolicSequentialSolver.run - true - false - true - - - make - -j5 - testEliminationTree.run + -j2 + all true true true - + make - -j1 - testSymbolicBayesTree.run + -j2 + testNonlinearConstraint.run true - false + true + true + + + make + -j2 + testLieConfig.run + true + true + true + + + make + -j2 + testConstraintOptimizer.run + true + true true @@ -909,18 +485,303 @@ true true - + make - -j5 - testInvDepthCamera3.run + -j2 + all true true true - + + make + -j2 + check + true + true + true + + + make + -j2 + clean + true + true + true + + make -j5 - testTriangulation.run + all + true + false + true + + + make + -j5 + check + true + false + 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 + 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 @@ -933,6 +794,60 @@ 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 + tests/testGaussianISAM2 + true + false + true + make -j5 @@ -1071,6 +986,7 @@ make + testGraph.run true false @@ -1078,6 +994,7 @@ make + testJunctionTree.run true false @@ -1085,6 +1002,7 @@ make + testSymbolicBayesNetB.run true false @@ -1146,39 +1064,7 @@ 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 @@ -1186,75 +1072,204 @@ true true - + make -j2 - testGaussianConditional.run + timeCalibratedCamera.run true true true - + make -j2 - testGaussianFactor.run + timeRot3.run true true true - + make -j2 - timeGaussianFactor.run + clean true true true - + make - -j2 - timeVectorConfig.run + -j5 + testVectorValues.run true true true - + make - -j2 - testVectorBTree.run - true - true - true - - - make - -j2 - testVectorMap.run - true - true - true - - - make - -j2 + -j5 testNoiseModel.run true true true - + make - -j2 - testBayesNetPreconditioner.run + -j5 + testHessianFactor.run true true true - + make - testErrors.run + -j5 + testGaussianConditional.run true - false + true + true + + + make + -j5 + testGaussianFactorGraph.run + true + true + true + + + make + -j5 + testGaussianJunctionTree.run + true + true + true + + + make + -j5 + testKalmanFilter.run + true + true + true + + + make + -j5 + testGaussianDensity.run + true + true + true + + + make + -j5 + testSerializationLinear.run + true + true + true + + + make + -j5 + testJacobianFactor.run + true + true + true + + + make + -j5 + testBTree.run + true + true + true + + + make + -j5 + testDSF.run + true + true + true + + + make + -j5 + testDSFVector.run + true + true + true + + + make + -j5 + testFixedVector.run + true + true + true + + + make + -j2 + check + true + true + true + + + make + -j5 + testInvDepthCamera3.run + true + true + true + + + make + -j5 + testTriangulation.run + true + true + true + + + make + -j5 + testValues.run + true + true + true + + + make + -j5 + testOrdering.run + true + true + true + + + make + -j5 + testKey.run + true + true + true + + + make + -j5 + testLinearContainerFactor.run + true + true + true + + + make + -j6 -j8 + testWhiteNoiseFactor.run + true + true true @@ -1297,10 +1312,114 @@ true true - + + make + -j5 + testVector.run + true + true + true + + + make + -j5 + testMatrix.run + true + true + true + + + make + -j5 + clean + true + true + true + + + make + -j5 + all + true + true + true + + make -j2 - testGaussianFactor.run + all + true + true + true + + + make + -j2 + clean + true + true + true + + + make + -j2 + clean all + true + true + true + + + make + -j2 + install + true + true + true + + + make + -j2 + clean + true + true + true + + + make + -j5 + testGeneralSFMFactor.run + true + true + true + + + make + -j5 + testProjectionFactor.run + true + true + true + + + make + -j5 + testGeneralSFMFactor_Cal3Bundler.run + true + true + true + + + make + -j6 -j8 + testAntiFactor.run + true + true + true + + + make + -j6 -j8 + testBetweenFactor.run true true true @@ -1385,6 +1504,110 @@ true true + + make + -j2 + testGaussianFactor.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 + -j2 + check + true + true + true + + + make + -j2 + clean + true + true + true + + + make + -j2 + testPoint2.run + true + true + true + make -j2 @@ -1449,70 +1672,6 @@ 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 - install - true - true - true - - - make - -j2 - clean - true - true - true - - - make - -j2 - all - true - true - true - - - make - -j2 - clean - true - true - true - make -j2 @@ -1529,87 +1688,71 @@ true true - - make - -j2 - check - true - true - true - - + make -j5 - testStereoCamera.run + testInvDepthFactor3.run true true true - + make -j5 - testRot3M.run + testPoseTranslationPrior.run true true true - + make -j5 - testPoint3.run + testPoseRotationPrior.run true true true - + make -j5 - testCalibratedCamera.run + testReferenceFrameFactor.run true true true - + make -j5 - timeStereoCamera.run + testAHRS.run true true true - + make - -j1 VERBOSE=1 - testHomography2.run + -j8 + testImuFactor.run true - false + true true - + make -j5 - testPoint2.run + testMultiProjectionFactor.run true true true - + make -j5 - testPose2.run + testSmartProjectionFactor.run true true true - - make - -j5 - testPose3.run - true - true - true - - + make -j2 all @@ -1617,15 +1760,7 @@ true true - - make - -j2 - check - true - true - true - - + make -j2 clean @@ -1633,222 +1768,6 @@ 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 - testVector.run - true - true - true - - - make - -j5 - testMatrix.run - true - true - true - - - make - -j5 - testVectorValues.run - true - true - true - - - make - -j5 - testNoiseModel.run - true - true - true - - - make - -j5 - testHessianFactor.run - true - true - true - - - make - -j5 - testGaussianConditional.run - true - true - true - - - make - -j5 - testGaussianFactorGraph.run - true - true - true - - - make - -j5 - testGaussianJunctionTree.run - true - true - true - - - make - -j5 - testKalmanFilter.run - true - true - true - - - make - -j5 - testGaussianDensity.run - true - true - true - - - make - -j5 - testSerializationLinear.run - true - true - true - - - make - -j5 - testJacobianFactor.run - true - true - true - make -j2 @@ -1945,30 +1864,6 @@ true true - - make - -j4 - testImuFactor.run - true - true - true - - - make - -j2 - check - true - true - true - - - make - - tests/testGaussianISAM2 - true - false - true - make -j2 @@ -1985,87 +1880,79 @@ true true - + make - -j2 - testRot3.run + -j5 + testInference.run true true true - + make - -j2 - testRot2.run + -j1 + testSymbolicSequentialSolver.run + true + false + true + + + make + -j5 + testEliminationTree.run true true true - + make - -j2 - testPose3.run + -j1 + testSymbolicBayesTree.run + true + false + true + + + make + -j5 + testSpirit.run true true true - + make - -j2 - timeRot3.run + -j5 + testWrap.run true true true - + make - -j2 - testPose2.run + -j5 + check.wrap true true true - + make - -j2 - testCal3_S2.run + -j5 + wrap true true true - + make -j2 - testSimpleCamera.run + all 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 @@ -2073,10 +1960,26 @@ true true - + make -j2 - testPoint2.run + all + true + true + true + + + make + -j2 + check + true + true + true + + + make + -j2 + clean true true true @@ -2282,6 +2185,7 @@ cpack + -G DEB true false @@ -2289,6 +2193,7 @@ cpack + -G RPM true false @@ -2296,6 +2201,7 @@ cpack + -G TGZ true false @@ -2303,6 +2209,7 @@ cpack + --config CPackSourceConfig.cmake true false @@ -2468,39 +2375,15 @@ true true - + make - -j5 - testSpirit.run + -j4 + testImuFactor.run true true true - - make - -j5 - testWrap.run - true - true - true - - - make - -j5 - check.wrap - true - true - true - - - make - -j5 - wrap - true - true - true - - + make -j2 check @@ -2508,7 +2391,15 @@ true true - + + make + -j2 + tests/testSPQRUtil.run + true + true + true + + make -j2 clean @@ -2516,15 +2407,63 @@ true true - + make - -j2 - install + -j5 + testDiscreteFactor.run true true true - + + make + -j1 + testDiscreteBayesTree.run + true + false + true + + + make + -j5 + testDiscreteFactorGraph.run + true + true + true + + + make + -j5 + testDiscreteConditional.run + true + true + true + + + make + -j5 + testDiscreteMarginals.run + true + true + true + + + make + -j2 + tests/testPose2.run + true + true + true + + + make + -j2 + tests/testPose3.run + true + true + true + + make -j2 all @@ -2532,9 +2471,90 @@ true true - - cmake - .. + + 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 diff --git a/gtsam/geometry/Cal3DS2.h b/gtsam/geometry/Cal3DS2.h index 5453e1481..27e5d4f1e 100644 --- a/gtsam/geometry/Cal3DS2.h +++ b/gtsam/geometry/Cal3DS2.h @@ -103,7 +103,7 @@ public: boost::optional Dcal = boost::none, boost::optional Dp = boost::none) const ; - /// Conver a pixel coordinate to ideal coordinate + /// Convert pixel coordinates to ideal coordinates Point2 calibrate(const Point2& p, const double tol=1e-5) const; /// Derivative of uncalibrate wrpt intrinsic coordinates diff --git a/gtsam/geometry/Cal3_S2.cpp b/gtsam/geometry/Cal3_S2.cpp index 1fb7f4069..c8c0255ea 100644 --- a/gtsam/geometry/Cal3_S2.cpp +++ b/gtsam/geometry/Cal3_S2.cpp @@ -89,6 +89,11 @@ Point2 Cal3_S2::calibrate(const Point2& p) const { (1 / fy_) * (v - v0_)); } +/* ************************************************************************* */ +Vector3 Cal3_S2::calibrate(const Vector3& p) const { + return matrix_inverse() * p; +} + /* ************************************************************************* */ } // namespace gtsam diff --git a/gtsam/geometry/Cal3_S2.h b/gtsam/geometry/Cal3_S2.h index bb3327afc..a62266046 100644 --- a/gtsam/geometry/Cal3_S2.h +++ b/gtsam/geometry/Cal3_S2.h @@ -158,6 +158,13 @@ public: */ Point2 calibrate(const Point2& p) const; + /** + * convert homogeneous image coordinates to intrinsic coordinates + * @param p point in image coordinates + * @return point in intrinsic coordinates + */ + Vector3 calibrate(const Vector3& p) const; + /// @} /// @name Manifold /// @{ diff --git a/gtsam/geometry/tests/testCal3_S2.cpp b/gtsam/geometry/tests/testCal3_S2.cpp index fe15afa0c..e1dba2272 100644 --- a/gtsam/geometry/tests/testCal3_S2.cpp +++ b/gtsam/geometry/tests/testCal3_S2.cpp @@ -42,12 +42,18 @@ TEST( Cal3_S2, easy_constructor) /* ************************************************************************* */ TEST( Cal3_S2, calibrate) { - Cal3_S2 K1(500, 500, 0.1, 640 / 2, 480 / 2); Point2 intrinsic(2,3); Point2 expectedimage(1320.3, 1740); - Point2 imagecoordinates = K1.uncalibrate(intrinsic); + Point2 imagecoordinates = K.uncalibrate(intrinsic); CHECK(assert_equal(expectedimage,imagecoordinates)); - CHECK(assert_equal(intrinsic,K1.calibrate(imagecoordinates))); + CHECK(assert_equal(intrinsic,K.calibrate(imagecoordinates))); +} + +/* ************************************************************************* */ +TEST( Cal3_S2, calibrate_homogeneous) { + Vector3 intrinsic(2, 3, 1); + Vector3 image(1320.3, 1740, 1); + CHECK(assert_equal((Vector)intrinsic,(Vector)K.calibrate(image))); } /* ************************************************************************* */