diff --git a/gtsam/linear/NoiseModel.cpp b/gtsam/linear/NoiseModel.cpp index 359ce9968..641b47640 100644 --- a/gtsam/linear/NoiseModel.cpp +++ b/gtsam/linear/NoiseModel.cpp @@ -166,9 +166,11 @@ void Gaussian::WhitenSystem(Matrix& A1, Matrix& A2, Matrix& A3, Vector& b) const // Diagonal /* ************************************************************************* */ Diagonal::Diagonal() : - Gaussian(1), sigmas_(ones(1)), invsigmas_(ones(1)), precisions_(ones(1)) { + Gaussian(1)//, sigmas_(ones(1)), invsigmas_(ones(1)), precisions_(ones(1)) +{ } +/* ************************************************************************* */ Diagonal::Diagonal(const Vector& sigmas) : Gaussian(sigmas.size()), sigmas_(sigmas), invsigmas_(reciprocal(sigmas)), precisions_( emul(invsigmas_, invsigmas_)) { @@ -229,6 +231,31 @@ void Diagonal::WhitenInPlace(Eigen::Block H) const { /* ************************************************************************* */ // Constrained +/* ************************************************************************* */ + +/* ************************************************************************* */ +Constrained::Constrained(const Vector& sigmas) + : Diagonal(sigmas), mu_(repeat(sigmas.size(), 1000.0)) { + for (int i=0; imu())); EXPECT(assert_equal(gtsam::repeat(d, 0), actual->sigmas())); - double Inf = numeric_limits::infinity(); - EXPECT(assert_equal(gtsam::repeat(d, Inf), actual->invsigmas())); - EXPECT(assert_equal(gtsam::repeat(d, Inf), actual->precisions())); + EXPECT(assert_equal(gtsam::repeat(d, 0), actual->invsigmas())); // Actually zero as dummy value + EXPECT(assert_equal(gtsam::repeat(d, 0), actual->precisions())); // Actually zero as dummy value actual = Constrained::All(d, m); EXPECT(assert_equal(gtsam::repeat(d, m), actual->mu())); diff --git a/gtsam/linear/tests/testSerializationLinear.cpp b/gtsam/linear/tests/testSerializationLinear.cpp index 970cdfe24..5e08a7827 100644 --- a/gtsam/linear/tests/testSerializationLinear.cpp +++ b/gtsam/linear/tests/testSerializationLinear.cpp @@ -70,13 +70,13 @@ TEST (Serialization, noiseModels) { EXPECT(equalsDereferencedXML(iso3)); EXPECT(equalsDereferencedBinary(iso3)); - EXPECT(equalsDereferenced(constrained3)); - EXPECT(equalsDereferencedXML(constrained3)); - EXPECT(equalsDereferencedBinary(constrained3)); - EXPECT(equalsDereferenced(unit3)); EXPECT(equalsDereferencedXML(unit3)); EXPECT(equalsDereferencedBinary(unit3)); + + EXPECT(equalsDereferencedBinary(constrained3)); + EXPECT(equalsDereferenced(constrained3)); + EXPECT(equalsDereferencedXML(constrained3)); } /* ************************************************************************* */ @@ -102,9 +102,9 @@ TEST (Serialization, SharedNoiseModel_noiseModels) { EXPECT(equalsDereferencedXML(unit3)); EXPECT(equalsDereferencedBinary(unit3)); + EXPECT(equalsDereferencedBinary(constrained3)); EXPECT(equalsDereferenced(constrained3)); EXPECT(equalsDereferencedXML(constrained3)); - EXPECT(equalsDereferencedBinary(constrained3)); } /* ************************************************************************* */ @@ -121,9 +121,9 @@ TEST (Serialization, SharedDiagonal_noiseModels) { EXPECT(equalsDereferencedXML(unit3)); EXPECT(equalsDereferencedBinary(unit3)); + EXPECT(equalsDereferencedBinary(constrained3)); EXPECT(equalsDereferenced(constrained3)); EXPECT(equalsDereferencedXML(constrained3)); - EXPECT(equalsDereferencedBinary(constrained3)); } /* Create GUIDs for factors */