Renamed testGaussianFactor to testJacobianFactor
							parent
							
								
									d16f29dec7
								
							
						
					
					
						commit
						f275126815
					
				|  | @ -28,7 +28,7 @@ | ||||||
| #include <gtsam/base/blockMatrices.h> | #include <gtsam/base/blockMatrices.h> | ||||||
| 
 | 
 | ||||||
| // Forward declaration to friend unit tests
 | // Forward declaration to friend unit tests
 | ||||||
| class eliminate2GaussianFactorTest; | class eliminate2JacobianFactorTest; | ||||||
| class constructorGaussianConditionalTest; | class constructorGaussianConditionalTest; | ||||||
| class eliminationGaussianFactorGraphTest; | class eliminationGaussianFactorGraphTest; | ||||||
| 
 | 
 | ||||||
|  | @ -220,14 +220,15 @@ protected: | ||||||
|   rsd_type::Block get_R_() { return rsd_(0); } |   rsd_type::Block get_R_() { return rsd_(0); } | ||||||
|   rsd_type::Block get_S_(iterator variable) { return rsd_(variable - this->begin()); } |   rsd_type::Block get_S_(iterator variable) { return rsd_(variable - this->begin()); } | ||||||
| 
 | 
 | ||||||
|  | private: | ||||||
|  | 
 | ||||||
|   // Friends
 |   // Friends
 | ||||||
|   friend class JacobianFactor; |   friend class JacobianFactor; | ||||||
|   friend class ::eliminate2GaussianFactorTest; |   friend class ::eliminate2JacobianFactorTest; | ||||||
|   friend class ::constructorGaussianConditionalTest; |   friend class ::constructorGaussianConditionalTest; | ||||||
|   friend class ::eliminationGaussianFactorGraphTest; |   friend class ::eliminationGaussianFactorGraphTest; | ||||||
| 
 | 
 | ||||||
| private: |   /** Serialization function */ | ||||||
| 	/** Serialization function */ |  | ||||||
| 	friend class boost::serialization::access; | 	friend class boost::serialization::access; | ||||||
| 	template<class Archive> | 	template<class Archive> | ||||||
| 	void serialize(Archive & ar, const unsigned int version) { | 	void serialize(Archive & ar, const unsigned int version) { | ||||||
|  |  | ||||||
|  | @ -27,9 +27,9 @@ | ||||||
| #include <boost/tuple/tuple.hpp> | #include <boost/tuple/tuple.hpp> | ||||||
| 
 | 
 | ||||||
| // Forward declarations of friend unit tests
 | // Forward declarations of friend unit tests
 | ||||||
| class Combine2GaussianFactorTest; | class Combine2JacobianFactorTest; | ||||||
| class eliminateFrontalsGaussianFactorTest; | class eliminateFrontalsJacobianFactorTest; | ||||||
| class constructor2GaussianFactorTest; | class constructor2JacobianFactorTest; | ||||||
| 
 | 
 | ||||||
| namespace gtsam { | namespace gtsam { | ||||||
| 
 | 
 | ||||||
|  | @ -198,14 +198,6 @@ namespace gtsam { | ||||||
|     /** return a multi-frontal conditional. It's actually a chordal Bayesnet */ |     /** return a multi-frontal conditional. It's actually a chordal Bayesnet */ | ||||||
|     boost::shared_ptr<GaussianConditional> eliminate(size_t nrFrontals = 1); |     boost::shared_ptr<GaussianConditional> 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 */ |     /* Used by ::CombineJacobians for sorting */ | ||||||
|     struct _RowSource { |     struct _RowSource { | ||||||
|       size_t firstNonzeroVar; |       size_t firstNonzeroVar; | ||||||
|  | @ -242,6 +234,15 @@ namespace gtsam { | ||||||
|     void assertInvariants() const; |     void assertInvariants() const; | ||||||
| 
 | 
 | ||||||
|   private: |   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 */ |     /** Serialization function */ | ||||||
|     friend class boost::serialization::access; |     friend class boost::serialization::access; | ||||||
|     template<class ARCHIVE> |     template<class ARCHIVE> | ||||||
|  |  | ||||||
|  | @ -28,7 +28,7 @@ sources += GaussianFactor.cpp GaussianFactorGraph.cpp | ||||||
| sources += GaussianJunctionTree.cpp  | sources += GaussianJunctionTree.cpp  | ||||||
| sources += GaussianConditional.cpp GaussianBayesNet.cpp | sources += GaussianConditional.cpp GaussianBayesNet.cpp | ||||||
| sources += GaussianISAM.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 | check_PROGRAMS += tests/testGaussianFactorGraph tests/testGaussianJunctionTree | ||||||
| 
 | 
 | ||||||
| # Kalman Filter
 | # Kalman Filter
 | ||||||
|  |  | ||||||
|  | @ -10,7 +10,7 @@ | ||||||
|  * -------------------------------------------------------------------------- */ |  * -------------------------------------------------------------------------- */ | ||||||
| 
 | 
 | ||||||
| /**
 | /**
 | ||||||
|  *  @file   testGaussianFactor.cpp |  *  @file   testJacobianFactor.cpp | ||||||
|  *  @brief  Unit tests for Linear Factor |  *  @brief  Unit tests for Linear Factor | ||||||
|  *  @author Christian Potthast |  *  @author Christian Potthast | ||||||
|  *  @author Frank Dellaert |  *  @author Frank Dellaert | ||||||
|  | @ -32,7 +32,7 @@ static SharedDiagonal | ||||||
| 	constraintModel = noiseModel::Constrained::All(2); | 	constraintModel = noiseModel::Constrained::All(2); | ||||||
| 
 | 
 | ||||||
| /* ************************************************************************* */ | /* ************************************************************************* */ | ||||||
| TEST(GaussianFactor, constructor) | TEST(JacobianFactor, constructor) | ||||||
| { | { | ||||||
| 	Vector b = Vector_(3, 1., 2., 3.); | 	Vector b = Vector_(3, 1., 2., 3.); | ||||||
| 	SharedDiagonal noise = noiseModel::Diagonal::Sigmas(Vector_(3,1.,1.,1.)); | 	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.); |   Vector b = Vector_(3, 1., 2., 3.); | ||||||
|   SharedDiagonal noise = noiseModel::Diagonal::Sigmas(Vector_(3,1.,1.,1.)); |   SharedDiagonal noise = noiseModel::Diagonal::Sigmas(Vector_(3,1.,1.,1.)); | ||||||
|  | @ -72,7 +72,7 @@ TEST(GaussianFactor, constructor2) | ||||||
| 
 | 
 | ||||||
| /* ************************************************************************* */ | /* ************************************************************************* */ | ||||||
| #ifdef BROKEN | #ifdef BROKEN | ||||||
| TEST(GaussianFactor, operators ) | TEST(JacobianFactor, operators ) | ||||||
| { | { | ||||||
| 	Matrix I = eye(2); | 	Matrix I = eye(2); | ||||||
| 	Vector b = Vector_(2,0.2,-0.1); | 	Vector b = Vector_(2,0.2,-0.1); | ||||||
|  | @ -102,7 +102,7 @@ TEST(GaussianFactor, operators ) | ||||||
| } | } | ||||||
| #endif | #endif | ||||||
| /* ************************************************************************* */ | /* ************************************************************************* */ | ||||||
| TEST(GaussianFactor, eliminate2 ) | TEST(JacobianFactor, eliminate2 ) | ||||||
| { | { | ||||||
| 	// sigmas
 | 	// sigmas
 | ||||||
| 	double sigma1 = 0.2; | 	double sigma1 = 0.2; | ||||||
|  | @ -175,7 +175,7 @@ TEST(GaussianFactor, eliminate2 ) | ||||||
| } | } | ||||||
| 
 | 
 | ||||||
| /* ************************************************************************* */ | /* ************************************************************************* */ | ||||||
| TEST(GaussianFactor, default_error ) | TEST(JacobianFactor, default_error ) | ||||||
| { | { | ||||||
| 	JacobianFactor f; | 	JacobianFactor f; | ||||||
| 	vector<size_t> dims; | 	vector<size_t> dims; | ||||||
|  | @ -186,7 +186,7 @@ TEST(GaussianFactor, default_error ) | ||||||
| 
 | 
 | ||||||
| //* ************************************************************************* */
 | //* ************************************************************************* */
 | ||||||
| #ifdef BROKEN | #ifdef BROKEN | ||||||
| TEST(GaussianFactor, eliminate_empty ) | TEST(JacobianFactor, eliminate_empty ) | ||||||
| { | { | ||||||
| 	// create an empty factor
 | 	// create an empty factor
 | ||||||
| 	JacobianFactor f; | 	JacobianFactor f; | ||||||
|  | @ -208,7 +208,7 @@ TEST(GaussianFactor, eliminate_empty ) | ||||||
| } | } | ||||||
| #endif | #endif | ||||||
| //* ************************************************************************* */
 | //* ************************************************************************* */
 | ||||||
| TEST(GaussianFactor, empty ) | TEST(JacobianFactor, empty ) | ||||||
| { | { | ||||||
| 	// create an empty factor
 | 	// create an empty factor
 | ||||||
| 	JacobianFactor f; | 	JacobianFactor f; | ||||||
|  | @ -224,7 +224,7 @@ void print(const list<T>& i) { | ||||||
| } | } | ||||||
| 
 | 
 | ||||||
| /* ************************************************************************* */ | /* ************************************************************************* */ | ||||||
| TEST(GaussianFactor, CONSTRUCTOR_GaussianConditional ) | TEST(JacobianFactor, CONSTRUCTOR_GaussianConditional ) | ||||||
| { | { | ||||||
| 	Matrix R11 = eye(2); | 	Matrix R11 = eye(2); | ||||||
| 	Matrix S12 = Matrix_(2,2, | 	Matrix S12 = Matrix_(2,2, | ||||||
		Loading…
	
		Reference in New Issue