Made global variables and functions in unit tests static to avoid duplicate symbols when linking all tests together

release/4.3a0
Richard Roberts 2012-06-21 01:20:04 +00:00
parent 30525529c9
commit d0c193e403
15 changed files with 61 additions and 61 deletions

View File

@ -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");

View File

@ -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)

View File

@ -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)

View File

@ -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);
}

View File

@ -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)

View File

@ -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)

View File

@ -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) {

View File

@ -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);
}

View File

@ -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);
/* ************************************************************************* */

View File

@ -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)

View File

@ -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);
}

View File

@ -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);

View File

@ -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_));

View File

@ -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<Point3> genPoint3() {
static vector<Point3> genPoint3() {
const double z = 5;
vector<Point3> landmarks ;
landmarks.push_back(Point3 (-1.0,-1.0, z));
@ -134,14 +134,14 @@ vector<Point3> genPoint3() {
return landmarks ;
}
vector<GeneralCamera> genCameraDefaultCalibration() {
static vector<GeneralCamera> genCameraDefaultCalibration() {
vector<GeneralCamera> 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<GeneralCamera> genCameraVariableCalibration() {
static vector<GeneralCamera> genCameraVariableCalibration() {
const Cal3_S2 K(640,480,0.01,320,240);
vector<GeneralCamera> X ;
X.push_back(GeneralCamera(Pose3(eye(3),Point3(-baseline/2.0, 0.0, 0.0)), K));
@ -149,7 +149,7 @@ vector<GeneralCamera> genCameraVariableCalibration() {
return X ;
}
boost::shared_ptr<Ordering> getOrdering(const vector<GeneralCamera>& cameras, const vector<Point3>& landmarks) {
static boost::shared_ptr<Ordering> getOrdering(const vector<GeneralCamera>& cameras, const vector<Point3>& landmarks) {
boost::shared_ptr<Ordering> 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)) ;

View File

@ -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<Projection>
@ -119,7 +119,7 @@ TEST( GeneralSFMFactor, error ) {
static const double baseline = 5.0 ;
/* ************************************************************************* */
vector<Point3> genPoint3() {
static vector<Point3> genPoint3() {
const double z = 5;
vector<Point3> landmarks ;
landmarks.push_back(Point3 (-1.0,-1.0, z));
@ -137,14 +137,14 @@ vector<Point3> genPoint3() {
return landmarks ;
}
vector<GeneralCamera> genCameraDefaultCalibration() {
static vector<GeneralCamera> genCameraDefaultCalibration() {
vector<GeneralCamera> 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<GeneralCamera> genCameraVariableCalibration() {
static vector<GeneralCamera> genCameraVariableCalibration() {
const Cal3Bundler K(500,1e-3,1e-3);
vector<GeneralCamera> cameras ;
cameras.push_back(GeneralCamera(Pose3(eye(3),Point3(-baseline/2.0, 0.0, 0.0)), K));
@ -152,7 +152,7 @@ vector<GeneralCamera> genCameraVariableCalibration() {
return cameras ;
}
boost::shared_ptr<Ordering> getOrdering(const std::vector<GeneralCamera>& cameras, const std::vector<Point3>& landmarks) {
static boost::shared_ptr<Ordering> getOrdering(const std::vector<GeneralCamera>& cameras, const std::vector<Point3>& landmarks) {
boost::shared_ptr<Ordering> 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<Ordering> getOrdering(const std::vector<GeneralCamera>& camera
}
/* ************************************************************************* */
TEST( GeneralSFMFactor, optimize_defaultK ) {
TEST( GeneralSFMFactor_Cal3Bundler, optimize_defaultK ) {
vector<Point3> landmarks = genPoint3();
vector<GeneralCamera> cameras = genCameraDefaultCalibration();
@ -199,7 +199,7 @@ TEST( GeneralSFMFactor, optimize_defaultK ) {
}
/* ************************************************************************* */
TEST( GeneralSFMFactor, optimize_varK_SingleMeasurementError ) {
TEST( GeneralSFMFactor_Cal3Bundler, optimize_varK_SingleMeasurementError ) {
vector<Point3> landmarks = genPoint3();
vector<GeneralCamera> 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<Point3> landmarks = genPoint3();
vector<GeneralCamera> cameras = genCameraVariableCalibration();
@ -283,7 +283,7 @@ TEST( GeneralSFMFactor, optimize_varK_FixCameras ) {
}
/* ************************************************************************* */
TEST( GeneralSFMFactor, optimize_varK_FixLandmarks ) {
TEST( GeneralSFMFactor_Cal3Bundler, optimize_varK_FixLandmarks ) {
vector<Point3> landmarks = genPoint3();
vector<GeneralCamera> cameras = genCameraVariableCalibration();
@ -336,7 +336,7 @@ TEST( GeneralSFMFactor, optimize_varK_FixLandmarks ) {
}
/* ************************************************************************* */
TEST( GeneralSFMFactor, optimize_varK_BA ) {
TEST( GeneralSFMFactor_Cal3Bundler, optimize_varK_BA ) {
vector<Point3> landmarks = genPoint3();
vector<GeneralCamera> cameras = genCameraVariableCalibration();