29 using namespace gtsam;
30 using namespace gtsam::serializationTestHelpers;
52 static noiseModel::Isotropic::shared_ptr
iso3 = noiseModel::Isotropic::Sigma(3, 0.2);
53 static noiseModel::Constrained::shared_ptr
constrained3 = noiseModel::Constrained::MixedSigmas(
Vector3(0.0, 0.0, 0.1));
54 static noiseModel::Unit::shared_ptr
unit3 = noiseModel::Unit::Create(3);
57 TEST (Serialization, noiseModels) {
59 EXPECT(equalsDereferenced<noiseModel::Diagonal::shared_ptr>(
diag3));
60 EXPECT(equalsDereferencedXML<noiseModel::Diagonal::shared_ptr>(
diag3));
61 EXPECT(equalsDereferencedBinary<noiseModel::Diagonal::shared_ptr>(
diag3));
63 EXPECT(equalsDereferenced<noiseModel::Gaussian::shared_ptr>(
gaussian3));
64 EXPECT(equalsDereferencedXML<noiseModel::Gaussian::shared_ptr>(
gaussian3));
65 EXPECT(equalsDereferencedBinary<noiseModel::Gaussian::shared_ptr>(
gaussian3));
67 EXPECT(equalsDereferenced<noiseModel::Isotropic::shared_ptr>(
iso3));
68 EXPECT(equalsDereferencedXML<noiseModel::Isotropic::shared_ptr>(
iso3));
69 EXPECT(equalsDereferencedBinary<noiseModel::Isotropic::shared_ptr>(
iso3));
71 EXPECT(equalsDereferenced<noiseModel::Unit::shared_ptr>(
unit3));
72 EXPECT(equalsDereferencedXML<noiseModel::Unit::shared_ptr>(
unit3));
73 EXPECT(equalsDereferencedBinary<noiseModel::Unit::shared_ptr>(
unit3));
81 TEST (Serialization, SharedNoiseModel_noiseModels) {
83 EXPECT(equalsDereferenced<SharedNoiseModel>(diag3_sg));
84 EXPECT(equalsDereferencedXML<SharedNoiseModel>(diag3_sg));
85 EXPECT(equalsDereferencedBinary<SharedNoiseModel>(diag3_sg));
87 EXPECT(equalsDereferenced<SharedNoiseModel>(
diag3));
88 EXPECT(equalsDereferencedXML<SharedNoiseModel>(
diag3));
89 EXPECT(equalsDereferencedBinary<SharedNoiseModel>(
diag3));
91 EXPECT(equalsDereferenced<SharedNoiseModel>(
iso3));
92 EXPECT(equalsDereferencedXML<SharedNoiseModel>(
iso3));
93 EXPECT(equalsDereferencedBinary<SharedNoiseModel>(
iso3));
99 EXPECT(equalsDereferenced<SharedNoiseModel>(
unit3));
100 EXPECT(equalsDereferencedXML<SharedNoiseModel>(
unit3));
101 EXPECT(equalsDereferencedBinary<SharedNoiseModel>(
unit3));
109 TEST (Serialization, SharedDiagonal_noiseModels) {
111 EXPECT(equalsDereferencedXML<SharedDiagonal>(
diag3));
112 EXPECT(equalsDereferencedBinary<SharedDiagonal>(
diag3));
114 EXPECT(equalsDereferenced<SharedDiagonal>(
iso3));
115 EXPECT(equalsDereferencedXML<SharedDiagonal>(
iso3));
116 EXPECT(equalsDereferencedBinary<SharedDiagonal>(
iso3));
119 EXPECT(equalsDereferencedXML<SharedDiagonal>(
unit3));
120 EXPECT(equalsDereferencedBinary<SharedDiagonal>(
unit3));
134 TEST (Serialization, linear_factors) {
148 EXPECT(equalsObj(jacobianfactor));
149 EXPECT(equalsXML(jacobianfactor));
150 EXPECT(equalsBinary(jacobianfactor));
153 EXPECT(equalsObj(hessianfactor));
154 EXPECT(equalsXML(hessianfactor));
155 EXPECT(equalsBinary(hessianfactor));
159 TEST (Serialization, gaussian_conditional) {
172 TEST (Serialization, gaussian_factor_graph) {
199 TEST(Serialization, gaussian_bayes_net) {
203 0,
Vector2(1.0, 2.0), (Matrix2() << 3.0, 4.0, 0.0, 6.0).finished(), 3,
204 (Matrix2() << 7.0, 8.0, 9.0, 10.0).finished(), 4,
205 (Matrix2() << 11.0, 12.0, 13.0, 14.0).finished()));
207 1,
Vector2(15.0, 16.0), (Matrix2() << 17.0, 18.0, 0.0, 20.0).finished(),
208 2, (Matrix2() << 21.0, 22.0, 23.0, 24.0).finished(), 4,
209 (Matrix2() << 25.0, 26.0, 27.0, 28.0).finished()));
211 2,
Vector2(29.0, 30.0), (Matrix2() << 31.0, 32.0, 0.0, 34.0).finished(),
212 3, (Matrix2() << 35.0, 36.0, 37.0, 38.0).finished()));
214 3,
Vector2(39.0, 40.0), (Matrix2() << 41.0, 42.0, 0.0, 44.0).finished(),
215 4, (Matrix2() << 45.0, 46.0, 47.0, 48.0).finished()));
217 4,
Vector2(49.0, 50.0), (Matrix2() << 51.0, 52.0, 0.0, 54.0).finished()));
219 std::string serialized = serialize(
gbn);
221 deserialize(serialized, actual);
226 TEST (Serialization, gaussian_bayes_tree) {
229 const SharedDiagonal chainNoise = noiseModel::Isotropic::Sigma(1, 0.5);
231 std::make_shared<JacobianFactor>(
x2, (
Matrix(1, 1) << 1.).finished(),
x1, (
Matrix(1, 1) << 1.).finished(), (
Vector(1) << 1.).finished(), chainNoise),
232 std::make_shared<JacobianFactor>(
x2, (
Matrix(1, 1) << 1.).finished(),
x3, (
Matrix(1, 1) << 1.).finished(), (
Vector(1) << 1.).finished(), chainNoise),
233 std::make_shared<JacobianFactor>(
x3, (
Matrix(1, 1) << 1.).finished(),
x4, (
Matrix(1, 1) << 1.).finished(), (
Vector(1) << 1.).finished(), chainNoise),
234 std::make_shared<JacobianFactor>(
x4, (
Matrix(1, 1) << 1.).finished(), (
Vector(1) << 1.).finished(), chainNoise)};
240 std::string serialized = serialize(
init);
241 deserialize(serialized, actual);