From f275126815d0dc2c324de7ad74e0b9e2552f766c Mon Sep 17 00:00:00 2001 From: Richard Roberts Date: Thu, 8 Sep 2011 20:33:11 +0000 Subject: [PATCH] Renamed testGaussianFactor to testJacobianFactor --- gtsam/linear/GaussianConditional.h | 9 ++++---- gtsam/linear/JacobianFactor.h | 23 ++++++++++--------- gtsam/linear/Makefile.am | 2 +- ...ssianFactor.cpp => testJacobianFactor.cpp} | 18 +++++++-------- 4 files changed, 27 insertions(+), 25 deletions(-) rename gtsam/linear/tests/{testGaussianFactor.cpp => testJacobianFactor.cpp} (96%) diff --git a/gtsam/linear/GaussianConditional.h b/gtsam/linear/GaussianConditional.h index 9d8379959..3f4551863 100644 --- a/gtsam/linear/GaussianConditional.h +++ b/gtsam/linear/GaussianConditional.h @@ -28,7 +28,7 @@ #include // Forward declaration to friend unit tests -class eliminate2GaussianFactorTest; +class eliminate2JacobianFactorTest; class constructorGaussianConditionalTest; class eliminationGaussianFactorGraphTest; @@ -220,14 +220,15 @@ protected: rsd_type::Block get_R_() { return rsd_(0); } rsd_type::Block get_S_(iterator variable) { return rsd_(variable - this->begin()); } +private: + // Friends friend class JacobianFactor; - friend class ::eliminate2GaussianFactorTest; + friend class ::eliminate2JacobianFactorTest; friend class ::constructorGaussianConditionalTest; friend class ::eliminationGaussianFactorGraphTest; -private: - /** Serialization function */ + /** Serialization function */ friend class boost::serialization::access; template void serialize(Archive & ar, const unsigned int version) { diff --git a/gtsam/linear/JacobianFactor.h b/gtsam/linear/JacobianFactor.h index 18d42dac6..7873799c0 100644 --- a/gtsam/linear/JacobianFactor.h +++ b/gtsam/linear/JacobianFactor.h @@ -27,9 +27,9 @@ #include // Forward declarations of friend unit tests -class Combine2GaussianFactorTest; -class eliminateFrontalsGaussianFactorTest; -class constructor2GaussianFactorTest; +class Combine2JacobianFactorTest; +class eliminateFrontalsJacobianFactorTest; +class constructor2JacobianFactorTest; namespace gtsam { @@ -198,14 +198,6 @@ namespace gtsam { /** return a multi-frontal conditional. It's actually a chordal Bayesnet */ boost::shared_ptr eliminate(size_t nrFrontals = 1); - // Friend HessianFactor to facilitate convertion constructors - friend class HessianFactor; - - // Friend unit tests (see also forward declarations above) - friend class ::Combine2GaussianFactorTest; - friend class ::eliminateFrontalsGaussianFactorTest; - friend class ::constructor2GaussianFactorTest; - /* Used by ::CombineJacobians for sorting */ struct _RowSource { size_t firstNonzeroVar; @@ -242,6 +234,15 @@ namespace gtsam { void assertInvariants() const; private: + + // Friend HessianFactor to facilitate convertion constructors + friend class HessianFactor; + + // Friend unit tests (see also forward declarations above) + friend class ::Combine2JacobianFactorTest; + friend class ::eliminateFrontalsJacobianFactorTest; + friend class ::constructor2JacobianFactorTest; + /** Serialization function */ friend class boost::serialization::access; template diff --git a/gtsam/linear/Makefile.am b/gtsam/linear/Makefile.am index 37d38c6c3..446332d03 100644 --- a/gtsam/linear/Makefile.am +++ b/gtsam/linear/Makefile.am @@ -28,7 +28,7 @@ sources += GaussianFactor.cpp GaussianFactorGraph.cpp sources += GaussianJunctionTree.cpp sources += GaussianConditional.cpp GaussianBayesNet.cpp sources += GaussianISAM.cpp -check_PROGRAMS += tests/testHessianFactor tests/testGaussianFactor tests/testGaussianConditional +check_PROGRAMS += tests/testHessianFactor tests/testJacobianFactor tests/testGaussianConditional check_PROGRAMS += tests/testGaussianFactorGraph tests/testGaussianJunctionTree # Kalman Filter diff --git a/gtsam/linear/tests/testGaussianFactor.cpp b/gtsam/linear/tests/testJacobianFactor.cpp similarity index 96% rename from gtsam/linear/tests/testGaussianFactor.cpp rename to gtsam/linear/tests/testJacobianFactor.cpp index 984d3d2c6..374261d30 100644 --- a/gtsam/linear/tests/testGaussianFactor.cpp +++ b/gtsam/linear/tests/testJacobianFactor.cpp @@ -10,7 +10,7 @@ * -------------------------------------------------------------------------- */ /** - * @file testGaussianFactor.cpp + * @file testJacobianFactor.cpp * @brief Unit tests for Linear Factor * @author Christian Potthast * @author Frank Dellaert @@ -32,7 +32,7 @@ static SharedDiagonal constraintModel = noiseModel::Constrained::All(2); /* ************************************************************************* */ -TEST(GaussianFactor, constructor) +TEST(JacobianFactor, constructor) { Vector b = Vector_(3, 1., 2., 3.); SharedDiagonal noise = noiseModel::Diagonal::Sigmas(Vector_(3,1.,1.,1.)); @@ -45,7 +45,7 @@ TEST(GaussianFactor, constructor) } /* ************************************************************************* */ -TEST(GaussianFactor, constructor2) +TEST(JacobianFactor, constructor2) { Vector b = Vector_(3, 1., 2., 3.); SharedDiagonal noise = noiseModel::Diagonal::Sigmas(Vector_(3,1.,1.,1.)); @@ -72,7 +72,7 @@ TEST(GaussianFactor, constructor2) /* ************************************************************************* */ #ifdef BROKEN -TEST(GaussianFactor, operators ) +TEST(JacobianFactor, operators ) { Matrix I = eye(2); Vector b = Vector_(2,0.2,-0.1); @@ -102,7 +102,7 @@ TEST(GaussianFactor, operators ) } #endif /* ************************************************************************* */ -TEST(GaussianFactor, eliminate2 ) +TEST(JacobianFactor, eliminate2 ) { // sigmas double sigma1 = 0.2; @@ -175,7 +175,7 @@ TEST(GaussianFactor, eliminate2 ) } /* ************************************************************************* */ -TEST(GaussianFactor, default_error ) +TEST(JacobianFactor, default_error ) { JacobianFactor f; vector dims; @@ -186,7 +186,7 @@ TEST(GaussianFactor, default_error ) //* ************************************************************************* */ #ifdef BROKEN -TEST(GaussianFactor, eliminate_empty ) +TEST(JacobianFactor, eliminate_empty ) { // create an empty factor JacobianFactor f; @@ -208,7 +208,7 @@ TEST(GaussianFactor, eliminate_empty ) } #endif //* ************************************************************************* */ -TEST(GaussianFactor, empty ) +TEST(JacobianFactor, empty ) { // create an empty factor JacobianFactor f; @@ -224,7 +224,7 @@ void print(const list& i) { } /* ************************************************************************* */ -TEST(GaussianFactor, CONSTRUCTOR_GaussianConditional ) +TEST(JacobianFactor, CONSTRUCTOR_GaussianConditional ) { Matrix R11 = eye(2); Matrix S12 = Matrix_(2,2,