From d0c193e403b493336e5f09d38a8b0500a855c903 Mon Sep 17 00:00:00 2001 From: Richard Roberts Date: Thu, 21 Jun 2012 01:20:04 +0000 Subject: [PATCH] Made global variables and functions in unit tests static to avoid duplicate symbols when linking all tests together --- gtsam/base/TestableAssertions.h | 4 +-- gtsam/geometry/tests/testCal3Bundler.cpp | 4 +-- gtsam/geometry/tests/testCal3DS2.cpp | 4 +-- gtsam/geometry/tests/testCalibratedCamera.cpp | 14 +++++----- gtsam/geometry/tests/testFundamental.cpp | 8 +++--- gtsam/geometry/tests/testHomography2.cpp | 6 ++--- gtsam/geometry/tests/testPoint3.cpp | 2 +- gtsam/geometry/tests/testPose2.cpp | 6 ++--- gtsam/geometry/tests/testRot3M.cpp | 6 ++--- gtsam/geometry/tests/testRot3Q.cpp | 6 ++--- gtsam/geometry/tests/testSimpleCamera.cpp | 16 ++++++------ gtsam/inference/tests/testBayesTree.cpp | 6 ++--- .../inference/tests/testSymbolicBayesNet.cpp | 2 +- gtsam/slam/tests/testGeneralSFMFactor.cpp | 12 ++++----- .../testGeneralSFMFactor_Cal3Bundler.cpp | 26 +++++++++---------- 15 files changed, 61 insertions(+), 61 deletions(-) diff --git a/gtsam/base/TestableAssertions.h b/gtsam/base/TestableAssertions.h index 10daafbb4..e79d6b764 100644 --- a/gtsam/base/TestableAssertions.h +++ b/gtsam/base/TestableAssertions.h @@ -30,7 +30,7 @@ namespace gtsam { /** * Equals testing for basic types */ -bool assert_equal(const Index& expected, const Index& actual, double tol = 0.0) { +static bool assert_equal(const Index& expected, const Index& actual, double tol = 0.0) { if(expected != actual) { std::cout << "Not equal:\nexpected: " << expected << "\nactual: " << actual << std::endl; return false; @@ -327,7 +327,7 @@ bool assert_container_equality(const V& expected, const V& actual) { /** * Compare strings for unit tests */ -bool assert_equal(const std::string& expected, const std::string& actual) { +static bool assert_equal(const std::string& expected, const std::string& actual) { if (expected == actual) return true; printf("Not equal:\n"); diff --git a/gtsam/geometry/tests/testCal3Bundler.cpp b/gtsam/geometry/tests/testCal3Bundler.cpp index bb1bd861d..e354796fa 100644 --- a/gtsam/geometry/tests/testCal3Bundler.cpp +++ b/gtsam/geometry/tests/testCal3Bundler.cpp @@ -25,8 +25,8 @@ using namespace gtsam; GTSAM_CONCEPT_TESTABLE_INST(Cal3Bundler) GTSAM_CONCEPT_MANIFOLD_INST(Cal3Bundler) -Cal3Bundler K(500, 1e-3, 1e-3); -Point2 p(2,3); +static Cal3Bundler K(500, 1e-3, 1e-3); +static Point2 p(2,3); /* ************************************************************************* */ TEST( Cal3Bundler, calibrate) diff --git a/gtsam/geometry/tests/testCal3DS2.cpp b/gtsam/geometry/tests/testCal3DS2.cpp index 4c79a447b..9f8777e49 100644 --- a/gtsam/geometry/tests/testCal3DS2.cpp +++ b/gtsam/geometry/tests/testCal3DS2.cpp @@ -25,8 +25,8 @@ using namespace gtsam; GTSAM_CONCEPT_TESTABLE_INST(Cal3DS2) GTSAM_CONCEPT_MANIFOLD_INST(Cal3DS2) -Cal3DS2 K(500, 100, 0.1, 320, 240, 1e-3, 2.0*1e-3, 3.0*1e-3, 4.0*1e-3); -Point2 p(2,3); +static Cal3DS2 K(500, 100, 0.1, 320, 240, 1e-3, 2.0*1e-3, 3.0*1e-3, 4.0*1e-3); +static Point2 p(2,3); /* ************************************************************************* */ TEST( Cal3DS2, calibrate) diff --git a/gtsam/geometry/tests/testCalibratedCamera.cpp b/gtsam/geometry/tests/testCalibratedCamera.cpp index 7fe88bce0..f8750ec24 100644 --- a/gtsam/geometry/tests/testCalibratedCamera.cpp +++ b/gtsam/geometry/tests/testCalibratedCamera.cpp @@ -27,19 +27,19 @@ using namespace gtsam; GTSAM_CONCEPT_MANIFOLD_INST(CalibratedCamera) -const Pose3 pose1(Matrix_(3,3, +static const Pose3 pose1(Matrix_(3,3, 1., 0., 0., 0.,-1., 0., 0., 0.,-1. ), Point3(0,0,0.5)); -const CalibratedCamera camera(pose1); +static const CalibratedCamera camera(pose1); -const Point3 point1(-0.08,-0.08, 0.0); -const Point3 point2(-0.08, 0.08, 0.0); -const Point3 point3( 0.08, 0.08, 0.0); -const Point3 point4( 0.08,-0.08, 0.0); +static const Point3 point1(-0.08,-0.08, 0.0); +static const Point3 point2(-0.08, 0.08, 0.0); +static const Point3 point3( 0.08, 0.08, 0.0); +static const Point3 point4( 0.08,-0.08, 0.0); /* ************************************************************************* */ TEST( CalibratedCamera, constructor) @@ -95,7 +95,7 @@ TEST( CalibratedCamera, Dproject_to_camera1) { } /* ************************************************************************* */ -Point2 project2(const Pose3& pose, const Point3& point) { +static Point2 project2(const Pose3& pose, const Point3& point) { return CalibratedCamera(pose).project(point); } diff --git a/gtsam/geometry/tests/testFundamental.cpp b/gtsam/geometry/tests/testFundamental.cpp index 46a051609..c233cbfd0 100644 --- a/gtsam/geometry/tests/testFundamental.cpp +++ b/gtsam/geometry/tests/testFundamental.cpp @@ -34,11 +34,11 @@ using namespace tensors; /* ************************************************************************* */ // Indices -tensors::Index<3, 'a'> a; -tensors::Index<3, 'b'> b; +static tensors::Index<3, 'a'> a; +static tensors::Index<3, 'b'> b; -tensors::Index<4, 'A'> A; -tensors::Index<4, 'B'> B; +static tensors::Index<4, 'A'> A; +static tensors::Index<4, 'B'> B; /* ************************************************************************* */ TEST( Tensors, FundamentalMatrix) diff --git a/gtsam/geometry/tests/testHomography2.cpp b/gtsam/geometry/tests/testHomography2.cpp index 062de9d1d..85681baa4 100644 --- a/gtsam/geometry/tests/testHomography2.cpp +++ b/gtsam/geometry/tests/testHomography2.cpp @@ -36,9 +36,9 @@ using namespace tensors; /* ************************************************************************* */ // Indices -tensors::Index<3, 'a'> a, _a; -tensors::Index<3, 'b'> b, _b; -tensors::Index<3, 'c'> c, _c; +static tensors::Index<3, 'a'> a, _a; +static tensors::Index<3, 'b'> b, _b; +static tensors::Index<3, 'c'> c, _c; /* ************************************************************************* */ TEST( Homography2, RealImages) diff --git a/gtsam/geometry/tests/testPoint3.cpp b/gtsam/geometry/tests/testPoint3.cpp index c7e25f7a9..492d65e42 100644 --- a/gtsam/geometry/tests/testPoint3.cpp +++ b/gtsam/geometry/tests/testPoint3.cpp @@ -23,7 +23,7 @@ using namespace gtsam; GTSAM_CONCEPT_TESTABLE_INST(Point3) GTSAM_CONCEPT_LIE_INST(Point3) -Point3 P(0.2,0.7,-2); +static Point3 P(0.2,0.7,-2); /* ************************************************************************* */ TEST(Point3, Lie) { diff --git a/gtsam/geometry/tests/testPose2.cpp b/gtsam/geometry/tests/testPose2.cpp index 2a0f9ebec..a79371e63 100644 --- a/gtsam/geometry/tests/testPose2.cpp +++ b/gtsam/geometry/tests/testPose2.cpp @@ -156,7 +156,7 @@ TEST(Pose3, expmap_c) #endif /* ************************************************************************* */ -TEST(Pose3, expmap_c_full) +TEST(Pose2, expmap_c_full) { double w=0.3; Vector xi = Vector_(3, 0.0, w, w); @@ -191,7 +191,7 @@ TEST(Pose2, logmap_full) { } /* ************************************************************************* */ -Point2 transform_to_proxy(const Pose2& pose, const Point2& point) { +static Point2 transform_to_proxy(const Pose2& pose, const Point2& point) { return pose.transform_to(point); } @@ -220,7 +220,7 @@ TEST( Pose2, transform_to ) } /* ************************************************************************* */ -Point2 transform_from_proxy(const Pose2& pose, const Point2& point) { +static Point2 transform_from_proxy(const Pose2& pose, const Point2& point) { return pose.transform_from(point); } diff --git a/gtsam/geometry/tests/testRot3M.cpp b/gtsam/geometry/tests/testRot3M.cpp index 7c8bd04bd..449ed9cd7 100644 --- a/gtsam/geometry/tests/testRot3M.cpp +++ b/gtsam/geometry/tests/testRot3M.cpp @@ -31,9 +31,9 @@ using namespace std; using namespace gtsam; -Rot3 R = Rot3::rodriguez(0.1, 0.4, 0.2); -Point3 P(0.2, 0.7, -2.0); -double error = 1e-9, epsilon = 0.001; +static Rot3 R = Rot3::rodriguez(0.1, 0.4, 0.2); +static Point3 P(0.2, 0.7, -2.0); +static double error = 1e-9, epsilon = 0.001; static const Matrix I3 = eye(3); /* ************************************************************************* */ diff --git a/gtsam/geometry/tests/testRot3Q.cpp b/gtsam/geometry/tests/testRot3Q.cpp index 02056eb2d..7268eed55 100644 --- a/gtsam/geometry/tests/testRot3Q.cpp +++ b/gtsam/geometry/tests/testRot3Q.cpp @@ -27,9 +27,9 @@ using namespace gtsam; -Rot3 R = Rot3::rodriguez(0.1, 0.4, 0.2); -Point3 P(0.2, 0.7, -2.0); -double error = 1e-9, epsilon = 0.001; +static Rot3 R = Rot3::rodriguez(0.1, 0.4, 0.2); +static Point3 P(0.2, 0.7, -2.0); +static double error = 1e-9, epsilon = 0.001; /* ************************************************************************* */ TEST( Rot3, constructor) diff --git a/gtsam/geometry/tests/testSimpleCamera.cpp b/gtsam/geometry/tests/testSimpleCamera.cpp index e46a247a0..6cc00de8a 100644 --- a/gtsam/geometry/tests/testSimpleCamera.cpp +++ b/gtsam/geometry/tests/testSimpleCamera.cpp @@ -26,21 +26,21 @@ using namespace std; using namespace gtsam; -const Cal3_S2 K(625, 625, 0, 0, 0); +static const Cal3_S2 K(625, 625, 0, 0, 0); -const Pose3 pose1(Matrix_(3,3, +static const Pose3 pose1(Matrix_(3,3, 1., 0., 0., 0.,-1., 0., 0., 0.,-1. ), Point3(0,0,0.5)); -const SimpleCamera camera(pose1, K); +static const SimpleCamera camera(pose1, K); -const Point3 point1(-0.08,-0.08, 0.0); -const Point3 point2(-0.08, 0.08, 0.0); -const Point3 point3( 0.08, 0.08, 0.0); -const Point3 point4( 0.08,-0.08, 0.0); +static const Point3 point1(-0.08,-0.08, 0.0); +static const Point3 point2(-0.08, 0.08, 0.0); +static const Point3 point3( 0.08, 0.08, 0.0); +static const Point3 point4( 0.08,-0.08, 0.0); /* ************************************************************************* */ TEST( SimpleCamera, constructor) @@ -118,7 +118,7 @@ TEST( SimpleCamera, backproject2) } /* ************************************************************************* */ -Point2 project2(const Pose3& pose, const Point3& point) { +static Point2 project2(const Pose3& pose, const Point3& point) { return SimpleCamera(pose,K).project(point); } diff --git a/gtsam/inference/tests/testBayesTree.cpp b/gtsam/inference/tests/testBayesTree.cpp index 2f85e1454..a5601b8eb 100644 --- a/gtsam/inference/tests/testBayesTree.cpp +++ b/gtsam/inference/tests/testBayesTree.cpp @@ -62,7 +62,7 @@ static const Index _x3_=0, _x2_=1; /* ************************************************************************* */ // Conditionals for ASIA example from the tutorial with A and D evidence static const Index _X_=0, _T_=1, _S_=2, _E_=3, _L_=4, _B_=5; -IndexConditional::shared_ptr +static IndexConditional::shared_ptr B(new IndexConditional(_B_)), L(new IndexConditional(_L_, _B_)), E(new IndexConditional(_E_, _L_, _B_)), @@ -71,11 +71,11 @@ IndexConditional::shared_ptr X(new IndexConditional(_X_, _E_)); // Cliques -IndexConditional::shared_ptr +static IndexConditional::shared_ptr ELB(IndexConditional::FromKeys(cref_list_of<3>(_E_)(_L_)(_B_), 3)); // Bayes Tree for Asia example -SymbolicBayesTree createAsiaSymbolicBayesTree() { +static SymbolicBayesTree createAsiaSymbolicBayesTree() { SymbolicBayesTree bayesTree; // Ordering asiaOrdering; asiaOrdering += _X_, _T_, _S_, _E_, _L_, _B_; SymbolicBayesTree::insert(bayesTree, B); diff --git a/gtsam/inference/tests/testSymbolicBayesNet.cpp b/gtsam/inference/tests/testSymbolicBayesNet.cpp index 20abb6a71..06b1bded9 100644 --- a/gtsam/inference/tests/testSymbolicBayesNet.cpp +++ b/gtsam/inference/tests/testSymbolicBayesNet.cpp @@ -35,7 +35,7 @@ static const Index _C_ = 3; static const Index _D_ = 4; static const Index _E_ = 5; -IndexConditional::shared_ptr +static IndexConditional::shared_ptr B(new IndexConditional(_B_)), L(new IndexConditional(_L_, _B_)); diff --git a/gtsam/slam/tests/testGeneralSFMFactor.cpp b/gtsam/slam/tests/testGeneralSFMFactor.cpp index 1306f5148..d6fcb5c5a 100644 --- a/gtsam/slam/tests/testGeneralSFMFactor.cpp +++ b/gtsam/slam/tests/testGeneralSFMFactor.cpp @@ -65,7 +65,7 @@ public: }; -double getGaussian() +static double getGaussian() { double S,V1,V2; // Use Box-Muller method to create gauss noise from uniform noise @@ -80,7 +80,7 @@ double getGaussian() return sqrt(-2.0f * (double)log(S) / S) * V1; } -const SharedNoiseModel sigma1(noiseModel::Unit::Create(1)); +static const SharedNoiseModel sigma1(noiseModel::Unit::Create(1)); /* ************************************************************************* */ TEST( GeneralSFMFactor, equals ) @@ -116,7 +116,7 @@ TEST( GeneralSFMFactor, error ) { static const double baseline = 5.0 ; /* ************************************************************************* */ -vector genPoint3() { +static vector genPoint3() { const double z = 5; vector landmarks ; landmarks.push_back(Point3 (-1.0,-1.0, z)); @@ -134,14 +134,14 @@ vector genPoint3() { return landmarks ; } -vector genCameraDefaultCalibration() { +static vector genCameraDefaultCalibration() { vector X ; X.push_back(GeneralCamera(Pose3(eye(3),Point3(-baseline/2.0, 0.0, 0.0)))); X.push_back(GeneralCamera(Pose3(eye(3),Point3( baseline/2.0, 0.0, 0.0)))); return X ; } -vector genCameraVariableCalibration() { +static vector genCameraVariableCalibration() { const Cal3_S2 K(640,480,0.01,320,240); vector X ; X.push_back(GeneralCamera(Pose3(eye(3),Point3(-baseline/2.0, 0.0, 0.0)), K)); @@ -149,7 +149,7 @@ vector genCameraVariableCalibration() { return X ; } -boost::shared_ptr getOrdering(const vector& cameras, const vector& landmarks) { +static boost::shared_ptr getOrdering(const vector& cameras, const vector& landmarks) { boost::shared_ptr ordering(new Ordering); for ( size_t i = 0 ; i < landmarks.size() ; ++i ) ordering->push_back(L(i)) ; for ( size_t i = 0 ; i < cameras.size() ; ++i ) ordering->push_back(X(i)) ; diff --git a/gtsam/slam/tests/testGeneralSFMFactor_Cal3Bundler.cpp b/gtsam/slam/tests/testGeneralSFMFactor_Cal3Bundler.cpp index 142c27e7e..9afd8eff1 100644 --- a/gtsam/slam/tests/testGeneralSFMFactor_Cal3Bundler.cpp +++ b/gtsam/slam/tests/testGeneralSFMFactor_Cal3Bundler.cpp @@ -66,7 +66,7 @@ public: }; -double getGaussian() +static double getGaussian() { double S,V1,V2; // Use Box-Muller method to create gauss noise from uniform noise @@ -81,10 +81,10 @@ double getGaussian() return sqrt(-2.0f * (double)log(S) / S) * V1; } -const SharedNoiseModel sigma1(noiseModel::Unit::Create(1)); +static const SharedNoiseModel sigma1(noiseModel::Unit::Create(1)); /* ************************************************************************* */ -TEST( GeneralSFMFactor, equals ) +TEST( GeneralSFMFactor_Cal3Bundler, equals ) { // Create two identical factors and make sure they're equal Vector z = Vector_(2,323.,240.); @@ -100,7 +100,7 @@ TEST( GeneralSFMFactor, equals ) } /* ************************************************************************* */ -TEST( GeneralSFMFactor, error ) { +TEST( GeneralSFMFactor_Cal3Bundler, error ) { Point2 z(3.,0.); const SharedNoiseModel sigma(noiseModel::Unit::Create(1)); boost::shared_ptr @@ -119,7 +119,7 @@ TEST( GeneralSFMFactor, error ) { static const double baseline = 5.0 ; /* ************************************************************************* */ -vector genPoint3() { +static vector genPoint3() { const double z = 5; vector landmarks ; landmarks.push_back(Point3 (-1.0,-1.0, z)); @@ -137,14 +137,14 @@ vector genPoint3() { return landmarks ; } -vector genCameraDefaultCalibration() { +static vector genCameraDefaultCalibration() { vector cameras ; cameras.push_back(GeneralCamera(Pose3(eye(3),Point3(-baseline/2.0, 0.0, 0.0)))); cameras.push_back(GeneralCamera(Pose3(eye(3),Point3( baseline/2.0, 0.0, 0.0)))); return cameras ; } -vector genCameraVariableCalibration() { +static vector genCameraVariableCalibration() { const Cal3Bundler K(500,1e-3,1e-3); vector cameras ; cameras.push_back(GeneralCamera(Pose3(eye(3),Point3(-baseline/2.0, 0.0, 0.0)), K)); @@ -152,7 +152,7 @@ vector genCameraVariableCalibration() { return cameras ; } -boost::shared_ptr getOrdering(const std::vector& cameras, const std::vector& landmarks) { +static boost::shared_ptr getOrdering(const std::vector& cameras, const std::vector& landmarks) { boost::shared_ptr ordering(new Ordering); for ( size_t i = 0 ; i < landmarks.size() ; ++i ) ordering->push_back(L(i)) ; for ( size_t i = 0 ; i < cameras.size() ; ++i ) ordering->push_back(X(i)) ; @@ -160,7 +160,7 @@ boost::shared_ptr getOrdering(const std::vector& camera } /* ************************************************************************* */ -TEST( GeneralSFMFactor, optimize_defaultK ) { +TEST( GeneralSFMFactor_Cal3Bundler, optimize_defaultK ) { vector landmarks = genPoint3(); vector cameras = genCameraDefaultCalibration(); @@ -199,7 +199,7 @@ TEST( GeneralSFMFactor, optimize_defaultK ) { } /* ************************************************************************* */ -TEST( GeneralSFMFactor, optimize_varK_SingleMeasurementError ) { +TEST( GeneralSFMFactor_Cal3Bundler, optimize_varK_SingleMeasurementError ) { vector landmarks = genPoint3(); vector cameras = genCameraVariableCalibration(); // add measurement with noise @@ -242,7 +242,7 @@ TEST( GeneralSFMFactor, optimize_varK_SingleMeasurementError ) { } /* ************************************************************************* */ -TEST( GeneralSFMFactor, optimize_varK_FixCameras ) { +TEST( GeneralSFMFactor_Cal3Bundler, optimize_varK_FixCameras ) { vector landmarks = genPoint3(); vector cameras = genCameraVariableCalibration(); @@ -283,7 +283,7 @@ TEST( GeneralSFMFactor, optimize_varK_FixCameras ) { } /* ************************************************************************* */ -TEST( GeneralSFMFactor, optimize_varK_FixLandmarks ) { +TEST( GeneralSFMFactor_Cal3Bundler, optimize_varK_FixLandmarks ) { vector landmarks = genPoint3(); vector cameras = genCameraVariableCalibration(); @@ -336,7 +336,7 @@ TEST( GeneralSFMFactor, optimize_varK_FixLandmarks ) { } /* ************************************************************************* */ -TEST( GeneralSFMFactor, optimize_varK_BA ) { +TEST( GeneralSFMFactor_Cal3Bundler, optimize_varK_BA ) { vector landmarks = genPoint3(); vector cameras = genCameraVariableCalibration();