Skip to content

Commit 8c68e21

Browse files
Added ISAM2 serialize test
1 parent df579ec commit 8c68e21

File tree

1 file changed

+79
-0
lines changed

1 file changed

+79
-0
lines changed

gtsam/nonlinear/tests/testSerializationNonlinear.cpp

Lines changed: 79 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -17,6 +17,7 @@
1717
*/
1818

1919
#include <gtsam/nonlinear/Values.h>
20+
#include <gtsam/nonlinear/ISAM2.h>
2021
#include <gtsam/inference/Symbol.h>
2122
#include <gtsam/geometry/PinholeCamera.h>
2223
#include <gtsam/geometry/Pose2.h>
@@ -31,6 +32,30 @@ using namespace std;
3132
using namespace gtsam;
3233
using namespace gtsam::serializationTestHelpers;
3334

35+
36+
/* ************************************************************************* */
37+
// Create GUIDs for Noisemodels
38+
BOOST_CLASS_EXPORT_GUID(gtsam::noiseModel::Diagonal, "gtsam_noiseModel_Diagonal");
39+
BOOST_CLASS_EXPORT_GUID(gtsam::noiseModel::mEstimator::Base , "gtsam_noiseModel_mEstimator_Base");
40+
BOOST_CLASS_EXPORT_GUID(gtsam::noiseModel::mEstimator::Null , "gtsam_noiseModel_mEstimator_Null");
41+
BOOST_CLASS_EXPORT_GUID(gtsam::noiseModel::mEstimator::Fair , "gtsam_noiseModel_mEstimator_Fair");
42+
BOOST_CLASS_EXPORT_GUID(gtsam::noiseModel::mEstimator::Huber, "gtsam_noiseModel_mEstimator_Huber");
43+
BOOST_CLASS_EXPORT_GUID(gtsam::noiseModel::mEstimator::Tukey, "gtsam_noiseModel_mEstimator_Tukey");
44+
BOOST_CLASS_EXPORT_GUID(gtsam::noiseModel::Constrained, "gtsam_noiseModel_Constrained");
45+
BOOST_CLASS_EXPORT_GUID(gtsam::noiseModel::Unit, "gtsam_noiseModel_Unit");
46+
BOOST_CLASS_EXPORT_GUID(gtsam::noiseModel::Isotropic,"gtsam_noiseModel_Isotropic");
47+
BOOST_CLASS_EXPORT_GUID(gtsam::noiseModel::Robust, "gtsam_noiseModel_Robust");
48+
BOOST_CLASS_EXPORT_GUID(gtsam::SharedNoiseModel, "gtsam_SharedNoiseModel");
49+
BOOST_CLASS_EXPORT_GUID(gtsam::SharedDiagonal, "gtsam_SharedDiagonal");
50+
51+
/* ************************************************************************* */
52+
// Create GUIDs for factors
53+
BOOST_CLASS_EXPORT_GUID(gtsam::PriorFactor<gtsam::Pose3>, "gtsam::PriorFactor<gtsam::Pose3>");
54+
BOOST_CLASS_EXPORT_GUID(gtsam::JacobianFactor, "gtsam::JacobianFactor");
55+
BOOST_CLASS_EXPORT_GUID(gtsam::HessianFactor , "gtsam::HessianFactor");
56+
BOOST_CLASS_EXPORT_GUID(gtsam::GaussianConditional , "gtsam::GaussianConditional");
57+
58+
3459
/* ************************************************************************* */
3560
// Export all classes derived from Value
3661
GTSAM_VALUE_EXPORT(gtsam::Cal3_S2);
@@ -82,6 +107,60 @@ TEST (Serialization, TemplatedValues) {
82107
EXPECT(equalsBinary(values));
83108
}
84109

110+
TEST(Serialization, ISAM2) {
111+
112+
gtsam::ISAM2Params parameters;
113+
gtsam::ISAM2 solver(parameters);
114+
gtsam::NonlinearFactorGraph graph;
115+
gtsam::Values initialValues;
116+
initialValues.clear();
117+
118+
gtsam::Vector6 temp6;
119+
for (int i = 0; i < 6; ++i) {
120+
temp6[i] = 0.0001;
121+
}
122+
gtsam::noiseModel::Diagonal::shared_ptr noiseModel = gtsam::noiseModel::Diagonal::Sigmas(temp6);
123+
124+
gtsam::Pose3 pose0(gtsam::Rot3(), gtsam::Point3(0, 0, 0));
125+
gtsam::Symbol symbol0('x', 0);
126+
graph.add(gtsam::PriorFactor<gtsam::Pose3>(symbol0, pose0, noiseModel));
127+
initialValues.insert(symbol0, pose0);
128+
129+
solver.update(graph, initialValues, gtsam::FastVector<size_t>());
130+
131+
std::string binaryPath = "saved_solver.dat";
132+
try {
133+
std::ofstream outputStream(binaryPath);
134+
boost::archive::binary_oarchive outputArchive(outputStream);
135+
outputArchive << solver;
136+
} catch(...) {
137+
EXPECT(false);
138+
}
139+
140+
gtsam::ISAM2 solverFromDisk;
141+
try {
142+
std::ifstream ifs(binaryPath);
143+
boost::archive::binary_iarchive inputArchive(ifs);
144+
inputArchive >> solverFromDisk;
145+
} catch(...) {
146+
EXPECT(false);
147+
}
148+
149+
gtsam::Pose3 p1, p2;
150+
try {
151+
p1 = solver.calculateEstimate<gtsam::Pose3>(symbol0);
152+
} catch(std::exception &e) {
153+
EXPECT(false);
154+
}
155+
156+
try {
157+
p2 = solverFromDisk.calculateEstimate<gtsam::Pose3>(symbol0);
158+
} catch(std::exception &e) {
159+
EXPECT(false);
160+
}
161+
EXPECT(assert_equal(p1, p2));
162+
}
163+
85164
/* ************************************************************************* */
86165
int main() { TestResult tr; return TestRegistry::runAllTests(tr); }
87166
/* ************************************************************************* */

0 commit comments

Comments
 (0)