remove debug statements

release/4.3a0
Gerry Chen 2022-07-19 21:41:45 -04:00
parent ea6e32de82
commit 83276853b5
No known key found for this signature in database
GPG Key ID: E9845092D3A57286
2 changed files with 6 additions and 37 deletions

View File

@ -264,13 +264,9 @@ public:
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*/) {
std::cout << "noise model base open " << std::endl;
ar & boost::serialization::make_nvp("NonlinearFactor", ar & boost::serialization::make_nvp("NonlinearFactor",
boost::serialization::base_object<Base>(*this)); boost::serialization::base_object<Base>(*this));
std::cout << "noise model itself begin" << std::endl;
ar & BOOST_SERIALIZATION_NVP(noiseModel_); ar & BOOST_SERIALIZATION_NVP(noiseModel_);
std::cout << "noise model itself end" << std::endl;
std::cout << "noise model base close " << std::endl;
} }
}; // \class NoiseModelFactor }; // \class NoiseModelFactor
@ -466,10 +462,8 @@ class NoiseModelFactorN : public NoiseModelFactor {
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*/) {
std::cout << "checkpoint N open" << std::endl;
ar& boost::serialization::make_nvp( ar& boost::serialization::make_nvp(
"NoiseModelFactor", boost::serialization::base_object<Base>(*this)); "NoiseModelFactor", boost::serialization::base_object<Base>(*this));
std::cout << "checkpoint N close" << std::endl;
} }
}; // \class NoiseModelFactorN }; // \class NoiseModelFactorN
@ -502,10 +496,8 @@ class NoiseModelFactor1 : public NoiseModelFactorN<VALUE> {
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*/) {
std::cout << "checkpoint a open " << std::endl;
ar& boost::serialization::make_nvp( ar& boost::serialization::make_nvp(
"NoiseModelFactor", boost::serialization::base_object<Base>(*this)); "NoiseModelFactor", boost::serialization::base_object<Base>(*this));
std::cout << "checkpoint a close" << std::endl;
} }
}; // \class NoiseModelFactor1 }; // \class NoiseModelFactor1

View File

@ -88,7 +88,6 @@ static Cal3DS2 cal2(1.0, 2.0, 3.0, 4.0, 5.0, 6.0, 7.0, 8.0, 9.0);
static Cal3Bundler cal3(1.0, 2.0, 3.0); static Cal3Bundler cal3(1.0, 2.0, 3.0);
TEST (Serialization, TemplatedValues) { TEST (Serialization, TemplatedValues) {
std::cout << "templatedValues open" << std::endl;
EXPECT(equalsObj(pt3)); EXPECT(equalsObj(pt3));
GenericValue<Point3> chv1(pt3); GenericValue<Point3> chv1(pt3);
EXPECT(equalsObj(chv1)); EXPECT(equalsObj(chv1));
@ -106,7 +105,6 @@ TEST (Serialization, TemplatedValues) {
EXPECT(equalsObj(values)); EXPECT(equalsObj(values));
EXPECT(equalsXML(values)); EXPECT(equalsXML(values));
EXPECT(equalsBinary(values)); EXPECT(equalsBinary(values));
std::cout << "templatedValues close" << std::endl;
} }
/** /**
@ -117,18 +115,16 @@ TEST (Serialization, TemplatedValues) {
* (2) serialized string depends on boost version * (2) serialized string depends on boost version
*/ */
TEST(Serialization, NoiseModelFactor1_backwards_compatibility) { TEST(Serialization, NoiseModelFactor1_backwards_compatibility) {
std::cout << "checkpoint: __FILE__, __LINE__" << std::endl;
PriorFactor<Pose3> factor( PriorFactor<Pose3> factor(
12345, Pose3(Rot3::RzRyRx(Vector3(1., 2., 3.)), Point3(4., 5., 6.)), 12345, Pose3(Rot3::RzRyRx(Vector3(1., 2., 3.)), Point3(4., 5., 6.)),
noiseModel::Unit::Create(6)); noiseModel::Unit::Create(6));
std::cout << "Serialized: \n" // roundtrip (sanity check)
<< serializeToString(factor) << "\nend serialization" << std::endl; PriorFactor<Pose3> factor_deserialized_str_2 = PriorFactor<Pose3>();
roundtrip(factor, factor_deserialized_str_2);
EXPECT(assert_equal(factor, factor_deserialized_str_2));
std::cout << "checkpoint: __FILE__, __LINE__" << std::endl; // Deserialize string
// String
std::cout << "checkpoint: __FILE__, __LINE__" << std::endl;
std::string serialized_str = std::string serialized_str =
"22 serialization::archive 15 1 0\n" "22 serialization::archive 15 1 0\n"
"0 0 0 0 0 0 0 1 0 12345 0 1 6 21 gtsam_noiseModel_Unit 1 0\n" "0 0 0 0 0 0 0 1 0 12345 0 1 6 21 gtsam_noiseModel_Unit 1 0\n"
@ -147,37 +143,19 @@ TEST(Serialization, NoiseModelFactor1_backwards_compatibility) {
"4.00000000000000000e+00 5.00000000000000000e+00 " "4.00000000000000000e+00 5.00000000000000000e+00 "
"6.00000000000000000e+00\n"; "6.00000000000000000e+00\n";
// // serialized_str = serializeToString(factor);
// {
std::cout << "roundtrip start" << std::endl;
PriorFactor<Pose3> factor_deserialized_str_2 = PriorFactor<Pose3>();
roundtrip(factor, factor_deserialized_str_2);
EXPECT(assert_equal(factor, factor_deserialized_str_2));
std::cout << "roundtrip end" << std::endl;
// }
PriorFactor<Pose3> factor_deserialized_str = PriorFactor<Pose3>(); PriorFactor<Pose3> factor_deserialized_str = PriorFactor<Pose3>();
std::cout << "checkpoint: " << __FILE__ << ", " << __LINE__ << std::endl;
deserializeFromString(serialized_str, factor_deserialized_str); deserializeFromString(serialized_str, factor_deserialized_str);
std::cout << "checkpoint: " << __FILE__ << ", " << __LINE__ << std::endl;
EXPECT(assert_equal(factor, factor_deserialized_str)); EXPECT(assert_equal(factor, factor_deserialized_str));
std::cout << "checkpoint: " << __FILE__ << ", " << __LINE__ << std::endl;
// XML // Deserialize XML
std::cout << "checkpoint: " << __FILE__ << ", " << __LINE__ << std::endl;
PriorFactor<Pose3> factor_deserialized_xml = PriorFactor<Pose3>(); PriorFactor<Pose3> factor_deserialized_xml = PriorFactor<Pose3>();
std::cout << "checkpoint: " << __FILE__ << ", " << __LINE__ << std::endl;
deserializeFromXMLFile(GTSAM_SOURCE_TREE_DATASET_DIR deserializeFromXMLFile(GTSAM_SOURCE_TREE_DATASET_DIR
"/../../gtsam/nonlinear/tests/priorFactor.xml", "/../../gtsam/nonlinear/tests/priorFactor.xml",
factor_deserialized_xml); factor_deserialized_xml);
std::cout << "checkpoint: " << __FILE__ << ", " << __LINE__ << std::endl;
EXPECT(assert_equal(factor, factor_deserialized_xml)); EXPECT(assert_equal(factor, factor_deserialized_xml));
std::cout << "checkpoint: " << __FILE__ << ", " << __LINE__ << std::endl;
} }
TEST(Serialization, ISAM2) { TEST(Serialization, ISAM2) {
std::cout << "ISAM2 open" << std::endl;
gtsam::ISAM2Params parameters; gtsam::ISAM2Params parameters;
gtsam::ISAM2 solver(parameters); gtsam::ISAM2 solver(parameters);
gtsam::NonlinearFactorGraph graph; gtsam::NonlinearFactorGraph graph;
@ -229,7 +207,6 @@ TEST(Serialization, ISAM2) {
EXPECT(false); EXPECT(false);
} }
EXPECT(assert_equal(p1, p2)); EXPECT(assert_equal(p1, p2));
std::cout << "ISAM close" << std::endl;
} }
/* ************************************************************************* */ /* ************************************************************************* */