From 780345bc2764753aae8fbf277dfe477375eff59e Mon Sep 17 00:00:00 2001 From: Gerry Chen Date: Tue, 9 Jun 2020 02:24:58 -0400 Subject: [PATCH 01/29] put file stream inside scope to force buffer flush This was already fixed for serializeXML but not for serializeToXMLFile or deserializeFromXMLFile. --- gtsam/base/serialization.h | 12 ++++-- gtsam/base/serializationTestHelpers.h | 57 +++++++++++++++++++++++++++ 2 files changed, 65 insertions(+), 4 deletions(-) diff --git a/gtsam/base/serialization.h b/gtsam/base/serialization.h index e475465de..088029903 100644 --- a/gtsam/base/serialization.h +++ b/gtsam/base/serialization.h @@ -106,8 +106,10 @@ bool serializeToXMLFile(const T& input, const std::string& filename, const std:: std::ofstream out_archive_stream(filename.c_str()); if (!out_archive_stream.is_open()) return false; - boost::archive::xml_oarchive out_archive(out_archive_stream); - out_archive << boost::serialization::make_nvp(name.c_str(), input);; + { + boost::archive::xml_oarchive out_archive(out_archive_stream); + out_archive << boost::serialization::make_nvp(name.c_str(), input);; + } out_archive_stream.close(); return true; } @@ -117,8 +119,10 @@ bool deserializeFromXMLFile(const std::string& filename, T& output, const std::s std::ifstream in_archive_stream(filename.c_str()); if (!in_archive_stream.is_open()) return false; - boost::archive::xml_iarchive in_archive(in_archive_stream); - in_archive >> boost::serialization::make_nvp(name.c_str(), output); + { + boost::archive::xml_iarchive in_archive(in_archive_stream); + in_archive >> boost::serialization::make_nvp(name.c_str(), output); + } in_archive_stream.close(); return true; } diff --git a/gtsam/base/serializationTestHelpers.h b/gtsam/base/serializationTestHelpers.h index 06b3462e9..178b256a6 100644 --- a/gtsam/base/serializationTestHelpers.h +++ b/gtsam/base/serializationTestHelpers.h @@ -26,6 +26,7 @@ #include #include +#include // whether to print the serialized text to stdout @@ -40,6 +41,13 @@ T create() { return T(); } +std::string resetFilesystem() { + // Create files in folder in build folder + boost::filesystem::remove_all("actual"); + boost::filesystem::create_directory("actual"); + return "actual/"; +} + // Templated round-trip serialization template void roundtrip(const T& input, T& output) { @@ -50,11 +58,22 @@ void roundtrip(const T& input, T& output) { deserialize(serialized, output); } +// Templated round-trip serialization using a file +template +void roundtripFile(const T& input, T& output) { + std::string path = resetFilesystem(); + + serializeToFile(input, path + "graph.dat"); + deserializeFromFile(path + "graph.dat", output); +} + // This version requires equality operator template bool equality(const T& input = T()) { T output = create(); roundtrip(input,output); + if (input != output) return false; + roundtripFile(input,output); return input==output; } @@ -63,6 +82,8 @@ template bool equalsObj(const T& input = T()) { T output = create(); roundtrip(input,output); + if (!assert_equal(input, output)) return false; + roundtripFile(input,output); return assert_equal(input, output); } @@ -71,6 +92,8 @@ template bool equalsDereferenced(const T& input) { T output = create(); roundtrip(input,output); + if (!input->equals(*output)) return false; + roundtripFile(input,output); return input->equals(*output); } @@ -85,11 +108,25 @@ void roundtripXML(const T& input, T& output) { deserializeXML(serialized, output); } +// Templated round-trip serialization using XML File +template +void roundtripXMLFile(const T& input, T& output) { + std::string path = resetFilesystem(); + + // Serialize + serializeToXMLFile(input, path + "graph.xml"); + + // De-serialize + deserializeFromXMLFile(path + "graph.xml", output); +} + // This version requires equality operator template bool equalityXML(const T& input = T()) { T output = create(); roundtripXML(input,output); + if (input != output) return false; + roundtripXMLFile(input,output); return input==output; } @@ -98,6 +135,8 @@ template bool equalsXML(const T& input = T()) { T output = create(); roundtripXML(input,output); + if (!assert_equal(input, output)) return false; + roundtripXMLFile(input, output); return assert_equal(input, output); } @@ -106,6 +145,8 @@ template bool equalsDereferencedXML(const T& input = T()) { T output = create(); roundtripXML(input,output); + if (!input->equals(*output)) return false; + roundtripXMLFile(input, output); return input->equals(*output); } @@ -120,11 +161,23 @@ void roundtripBinary(const T& input, T& output) { deserializeBinary(serialized, output); } +// Templated round-trip serialization using XML +template +void roundtripBinaryFile(const T& input, T& output) { + std::string path = resetFilesystem(); + // Serialize + serializeToBinaryFile(input, path + "graph.bin"); + // De-serialize + deserializeFromBinaryFile(path + "graph.bin", output); +} + // This version requires equality operator template bool equalityBinary(const T& input = T()) { T output = create(); roundtripBinary(input,output); + if (input != output) return false; + roundtripBinaryFile(input,output); return input==output; } @@ -133,6 +186,8 @@ template bool equalsBinary(const T& input = T()) { T output = create(); roundtripBinary(input,output); + if (!assert_equal(input, output)) return false; + roundtripBinaryFile(input,output); return assert_equal(input, output); } @@ -141,6 +196,8 @@ template bool equalsDereferencedBinary(const T& input = T()) { T output = create(); roundtripBinary(input,output); + if (!input->equals(*output)) return false; + roundtripBinaryFile(input,output); return input->equals(*output); } From c94736b6b6959820efe628d52cc8cd17c0269cdc Mon Sep 17 00:00:00 2001 From: Gerry Chen Date: Tue, 9 Jun 2020 02:39:54 -0400 Subject: [PATCH 02/29] bypass assert_equal tests for file roundtrips --- gtsam/base/serializationTestHelpers.h | 6 ------ 1 file changed, 6 deletions(-) diff --git a/gtsam/base/serializationTestHelpers.h b/gtsam/base/serializationTestHelpers.h index 178b256a6..d29899072 100644 --- a/gtsam/base/serializationTestHelpers.h +++ b/gtsam/base/serializationTestHelpers.h @@ -82,8 +82,6 @@ template bool equalsObj(const T& input = T()) { T output = create(); roundtrip(input,output); - if (!assert_equal(input, output)) return false; - roundtripFile(input,output); return assert_equal(input, output); } @@ -135,8 +133,6 @@ template bool equalsXML(const T& input = T()) { T output = create(); roundtripXML(input,output); - if (!assert_equal(input, output)) return false; - roundtripXMLFile(input, output); return assert_equal(input, output); } @@ -186,8 +182,6 @@ template bool equalsBinary(const T& input = T()) { T output = create(); roundtripBinary(input,output); - if (!assert_equal(input, output)) return false; - roundtripBinaryFile(input,output); return assert_equal(input, output); } From 686b0effbf4e6d222ed26c17d2c00bb7dc878551 Mon Sep 17 00:00:00 2001 From: Gerry Chen Date: Tue, 9 Jun 2020 02:48:53 -0400 Subject: [PATCH 03/29] better comments on serializationTestHelper functions --- gtsam/base/serializationTestHelpers.h | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/gtsam/base/serializationTestHelpers.h b/gtsam/base/serializationTestHelpers.h index d29899072..031a6278f 100644 --- a/gtsam/base/serializationTestHelpers.h +++ b/gtsam/base/serializationTestHelpers.h @@ -41,8 +41,8 @@ T create() { return T(); } +// Creates or empties a folder in the build folder and returns the relative path std::string resetFilesystem() { - // Create files in folder in build folder boost::filesystem::remove_all("actual"); boost::filesystem::create_directory("actual"); return "actual/"; @@ -157,7 +157,7 @@ void roundtripBinary(const T& input, T& output) { deserializeBinary(serialized, output); } -// Templated round-trip serialization using XML +// Templated round-trip serialization using Binary file template void roundtripBinaryFile(const T& input, T& output) { std::string path = resetFilesystem(); From 8a9ade00254e403f15471b17ce9fe75fcf0da084 Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Thu, 11 Jun 2020 10:58:44 -0500 Subject: [PATCH 04/29] remove extra semicolon --- gtsam/base/serialization.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/gtsam/base/serialization.h b/gtsam/base/serialization.h index 088029903..191e0ecfb 100644 --- a/gtsam/base/serialization.h +++ b/gtsam/base/serialization.h @@ -108,7 +108,7 @@ bool serializeToXMLFile(const T& input, const std::string& filename, const std:: return false; { boost::archive::xml_oarchive out_archive(out_archive_stream); - out_archive << boost::serialization::make_nvp(name.c_str(), input);; + out_archive << boost::serialization::make_nvp(name.c_str(), input); } out_archive_stream.close(); return true; From 0a44315a7f3b1b2f6e1953e5b73ece40c7097a01 Mon Sep 17 00:00:00 2001 From: David Date: Sat, 20 Jun 2020 08:46:06 +1000 Subject: [PATCH 05/29] Add Pose3-Point3 factor --- gtsam_unstable/slam/PoseToPointFactor.h | 95 +++++++++++++++++++ .../slam/tests/testPoseToPointFactor.h | 84 ++++++++++++++++ 2 files changed, 179 insertions(+) create mode 100644 gtsam_unstable/slam/PoseToPointFactor.h create mode 100644 gtsam_unstable/slam/tests/testPoseToPointFactor.h diff --git a/gtsam_unstable/slam/PoseToPointFactor.h b/gtsam_unstable/slam/PoseToPointFactor.h new file mode 100644 index 000000000..98efd6a0b --- /dev/null +++ b/gtsam_unstable/slam/PoseToPointFactor.h @@ -0,0 +1,95 @@ +/** + * @file PoseToPointFactor.hpp + * @brief This factor can be used to track a 3D landmark over time by providing + * local measurements of its location. + * @author David Wisth + **/ +#pragma once + +#include +#include +#include +#include + +namespace gtsam { + +/** + * A class for a measurement between a pose and a point. + * @addtogroup SLAM + */ +class PoseToPointFactor: public NoiseModelFactor2 { + +private: + + typedef PoseToPointFactor This; + typedef NoiseModelFactor2 Base; + + Point3 measured_; /** the point measurement */ + +public: + + // shorthand for a smart pointer to a factor + typedef boost::shared_ptr shared_ptr; + + /** default constructor - only use for serialization */ + PoseToPointFactor() {} + + /** Constructor */ + PoseToPointFactor(Key key1, Key key2, const Point3& measured, + const SharedNoiseModel& model) : + Base(model, key1, key2), measured_(measured) + { + } + + virtual ~PoseToPointFactor() {} + + /** implement functions needed for Testable */ + + /** print */ + virtual void print(const std::string& s, const KeyFormatter& keyFormatter = DefaultKeyFormatter) const { + std::cout << s << "PoseToPointFactor(" + << keyFormatter(this->key1()) << "," + << keyFormatter(this->key2()) << ")\n" + << " measured: " << measured_.transpose() << std::endl; + this->noiseModel_->print(" noise model: "); + } + + /** equals */ + virtual bool equals(const NonlinearFactor& expected, double tol=1e-9) const { + const This *e = dynamic_cast (&expected); + return e != nullptr && Base::equals(*e, tol) && traits::Equals(this->measured_, e->measured_, tol); + } + + /** implement functions needed to derive from Factor */ + + /** vector of errors + * Error = pose_est.inverse()*point_est - measured_ + * (The error is in the measurement coordinate system) + */ + Vector evaluateError(const Pose3& W_T_WI, + const Point3& W_r_WC, + boost::optional H1 = boost::none, + boost::optional H2 = boost::none) const + { + return W_T_WI.transformTo(W_r_WC, H1, H2) - measured_; + } + + /** return the measured */ + const Point3& measured() const { + return measured_; + } + +private: + + /** Serialization function */ + friend class boost::serialization::access; + template + void serialize(ARCHIVE & ar, const unsigned int /*version*/) { + ar & boost::serialization::make_nvp("NoiseModelFactor2", + boost::serialization::base_object(*this)); + ar & BOOST_SERIALIZATION_NVP(measured_); + } + +}; // \class PoseToPointFactor + +} /// namespace gtsam diff --git a/gtsam_unstable/slam/tests/testPoseToPointFactor.h b/gtsam_unstable/slam/tests/testPoseToPointFactor.h new file mode 100644 index 000000000..0a13e78e2 --- /dev/null +++ b/gtsam_unstable/slam/tests/testPoseToPointFactor.h @@ -0,0 +1,84 @@ +/** + * @file testPoseToPointFactor.cpp + * @brief + * @author David Wisth + * @date June 20, 2020 + */ + +#include +#include +#include + +using namespace gtsam; +using namespace gtsam::noiseModel; + +/// Verify zero error when there is no noise +TEST(LandmarkFactor, errorNoiseless) { + Pose3 pose = Pose3::identity(); + Point3 point(1.0, 2.0, 3.0); + Point3 noise(0.0, 0.0, 0.0); + Point3 measured = t + noise; + + Key pose_key(1); + Key point_key(2); + PoseToPointFactor factor(pose_key, point_key, measured, Isotropic::Sigma(3, 0.05)); + Vector expectedError = Vector3(0.0, 0.0, 0.0); + Vector actualError = factor.evaluateError(pose, point); + EXPECT(assert_equal(expectedError,actualError, 1E-5)); +} + +/// Verify expected error in test scenario +TEST(LandmarkFactor, errorNoise) { + Pose3 pose = Pose3::identity(); + Point3 point(1.0 , 2.0, 3.0); + Point3 noise(-1.0, 0.5, 0.3); + Point3 measured = t + noise; + + Key pose_key(1); + Key point_key(2); + PoseToPointFactor factor(pose_key, point_key, measured, Isotropic::Sigma(3, 0.05)); + Vector expectedError = noise; + Vector actualError = factor.evaluateError(pose, point); + EXPECT(assert_equal(expectedError,actualError, 1E-5)); +} + +/// Check Jacobians are correct +TEST(LandmarkFactor, jacobian) { + // Measurement + gtsam::Point3 l_meas = gtsam::Point3(1, 2, 3); + + // Linearisation point + gtsam::Point3 p_t = gtsam::Point3(-5, 12, 2); + gtsam::Rot3 p_R = gtsam::Rot3::RzRyRx(1.5*M_PI, -0.3*M_PI, 0.4*M_PI); + Pose3 p(p_R, p_t); + + gtsam::Point3 l = gtsam::Point3(3, 0, 5); + + // Factor + Key pose_key(1); + Key point_key(2); + SharedGaussian noise = noiseModel::Diagonal::Sigmas(Vector3(0.1, 0.1, 0.1)); + PoseToPointFactor factor(pose_key, point_key, l_meas, noise); + + // Calculate numerical derivatives + boost::function f = boost::bind( + &LandmarkFactor::evaluateError, factor, _1, _2, boost::none, boost::none); + Matrix numerical_H1 = numericalDerivative21(f, p, l); + Matrix numerical_H2 = numericalDerivative22(f, p, l); + + // Use the factor to calculate the derivative + Matrix actual_H1; + Matrix actual_H2; + factor.evaluateError(p, l, actual_H1, actual_H2); + + // Verify we get the expected error + EXPECT_TRUE(assert_equal(numerical_H1, actual_H1, 1e-8)); + EXPECT_TRUE(assert_equal(numerical_H2, actual_H2, 1e-8)); +} + +/* ************************************************************************* */ +int main() { + TestResult tr; + return TestRegistry::runAllTests(tr); +} +/* ************************************************************************* */ From c422815b9402a0a0840c2902b8df647e6d527ca5 Mon Sep 17 00:00:00 2001 From: David Date: Sat, 20 Jun 2020 09:03:17 +1000 Subject: [PATCH 06/29] Update incorrect test name --- gtsam_unstable/slam/tests/testPoseToPointFactor.h | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/gtsam_unstable/slam/tests/testPoseToPointFactor.h b/gtsam_unstable/slam/tests/testPoseToPointFactor.h index 0a13e78e2..4b2793700 100644 --- a/gtsam_unstable/slam/tests/testPoseToPointFactor.h +++ b/gtsam_unstable/slam/tests/testPoseToPointFactor.h @@ -13,7 +13,7 @@ using namespace gtsam; using namespace gtsam::noiseModel; /// Verify zero error when there is no noise -TEST(LandmarkFactor, errorNoiseless) { +TEST(PoseToPointFactor, errorNoiseless) { Pose3 pose = Pose3::identity(); Point3 point(1.0, 2.0, 3.0); Point3 noise(0.0, 0.0, 0.0); @@ -28,7 +28,7 @@ TEST(LandmarkFactor, errorNoiseless) { } /// Verify expected error in test scenario -TEST(LandmarkFactor, errorNoise) { +TEST(PoseToPointFactor, errorNoise) { Pose3 pose = Pose3::identity(); Point3 point(1.0 , 2.0, 3.0); Point3 noise(-1.0, 0.5, 0.3); @@ -43,7 +43,7 @@ TEST(LandmarkFactor, errorNoise) { } /// Check Jacobians are correct -TEST(LandmarkFactor, jacobian) { +TEST(PoseToPointFactor, jacobian) { // Measurement gtsam::Point3 l_meas = gtsam::Point3(1, 2, 3); From 0ee4e3b77eaaa879d5e995d92714698e94d11455 Mon Sep 17 00:00:00 2001 From: David Date: Sat, 20 Jun 2020 09:45:24 +1000 Subject: [PATCH 07/29] Add more documentation and clang-format --- gtsam_unstable/slam/PoseToPointFactor.h | 81 +++++++++---------- .../slam/tests/testPoseToPointFactor.h | 22 ++--- 2 files changed, 50 insertions(+), 53 deletions(-) diff --git a/gtsam_unstable/slam/PoseToPointFactor.h b/gtsam_unstable/slam/PoseToPointFactor.h index 98efd6a0b..ec7da22ef 100644 --- a/gtsam_unstable/slam/PoseToPointFactor.h +++ b/gtsam_unstable/slam/PoseToPointFactor.h @@ -1,15 +1,15 @@ /** * @file PoseToPointFactor.hpp - * @brief This factor can be used to track a 3D landmark over time by providing - * local measurements of its location. + * @brief This factor can be used to track a 3D landmark over time by + *providing local measurements of its location. * @author David Wisth **/ #pragma once -#include -#include #include #include +#include +#include namespace gtsam { @@ -17,17 +17,14 @@ namespace gtsam { * A class for a measurement between a pose and a point. * @addtogroup SLAM */ -class PoseToPointFactor: public NoiseModelFactor2 { - -private: - +class PoseToPointFactor : public NoiseModelFactor2 { + private: typedef PoseToPointFactor This; typedef NoiseModelFactor2 Base; - Point3 measured_; /** the point measurement */ - -public: + Point3 measured_; /** the point measurement in local coordinates */ + public: // shorthand for a smart pointer to a factor typedef boost::shared_ptr shared_ptr; @@ -36,60 +33,58 @@ public: /** Constructor */ PoseToPointFactor(Key key1, Key key2, const Point3& measured, - const SharedNoiseModel& model) : - Base(model, key1, key2), measured_(measured) - { - } + const SharedNoiseModel& model) + : Base(model, key1, key2), measured_(measured) {} virtual ~PoseToPointFactor() {} /** implement functions needed for Testable */ /** print */ - virtual void print(const std::string& s, const KeyFormatter& keyFormatter = DefaultKeyFormatter) const { - std::cout << s << "PoseToPointFactor(" - << keyFormatter(this->key1()) << "," - << keyFormatter(this->key2()) << ")\n" - << " measured: " << measured_.transpose() << std::endl; + virtual void print(const std::string& s, const KeyFormatter& keyFormatter = + DefaultKeyFormatter) const { + std::cout << s << "PoseToPointFactor(" << keyFormatter(this->key1()) << "," + << keyFormatter(this->key2()) << ")\n" + << " measured: " << measured_.transpose() << std::endl; this->noiseModel_->print(" noise model: "); } /** equals */ - virtual bool equals(const NonlinearFactor& expected, double tol=1e-9) const { - const This *e = dynamic_cast (&expected); - return e != nullptr && Base::equals(*e, tol) && traits::Equals(this->measured_, e->measured_, tol); + virtual bool equals(const NonlinearFactor& expected, + double tol = 1e-9) const { + const This* e = dynamic_cast(&expected); + return e != nullptr && Base::equals(*e, tol) && + traits::Equals(this->measured_, e->measured_, tol); } /** implement functions needed to derive from Factor */ /** vector of errors - * Error = pose_est.inverse()*point_est - measured_ - * (The error is in the measurement coordinate system) - */ - Vector evaluateError(const Pose3& W_T_WI, - const Point3& W_r_WC, + * @brief Error = wTwi.inverse()*wPwp - measured_ + * @param wTwi The pose of the sensor in world coordinates + * @param wPwp The estimated point location in world coordinates + * + * Note: measured_ and the error are in local coordiantes. + */ + Vector evaluateError(const Pose3& wTwi, const Point3& wPwp, boost::optional H1 = boost::none, - boost::optional H2 = boost::none) const - { - return W_T_WI.transformTo(W_r_WC, H1, H2) - measured_; + boost::optional H2 = boost::none) const { + return wTwi.transformTo(wPwp, H1, H2) - measured_; } /** return the measured */ - const Point3& measured() const { - return measured_; - } - -private: + const Point3& measured() const { return measured_; } + private: /** Serialization function */ friend class boost::serialization::access; - template - void serialize(ARCHIVE & ar, const unsigned int /*version*/) { - ar & boost::serialization::make_nvp("NoiseModelFactor2", - boost::serialization::base_object(*this)); - ar & BOOST_SERIALIZATION_NVP(measured_); + template + void serialize(ARCHIVE& ar, const unsigned int /*version*/) { + ar& boost::serialization::make_nvp( + "NoiseModelFactor2", boost::serialization::base_object(*this)); + ar& BOOST_SERIALIZATION_NVP(measured_); } -}; // \class PoseToPointFactor +}; // \class PoseToPointFactor -} /// namespace gtsam +} // namespace gtsam diff --git a/gtsam_unstable/slam/tests/testPoseToPointFactor.h b/gtsam_unstable/slam/tests/testPoseToPointFactor.h index 4b2793700..8f8563e9d 100644 --- a/gtsam_unstable/slam/tests/testPoseToPointFactor.h +++ b/gtsam_unstable/slam/tests/testPoseToPointFactor.h @@ -5,9 +5,9 @@ * @date June 20, 2020 */ +#include #include #include -#include using namespace gtsam; using namespace gtsam::noiseModel; @@ -21,25 +21,27 @@ TEST(PoseToPointFactor, errorNoiseless) { Key pose_key(1); Key point_key(2); - PoseToPointFactor factor(pose_key, point_key, measured, Isotropic::Sigma(3, 0.05)); + PoseToPointFactor factor(pose_key, point_key, measured, + Isotropic::Sigma(3, 0.05)); Vector expectedError = Vector3(0.0, 0.0, 0.0); Vector actualError = factor.evaluateError(pose, point); - EXPECT(assert_equal(expectedError,actualError, 1E-5)); + EXPECT(assert_equal(expectedError, actualError, 1E-5)); } /// Verify expected error in test scenario TEST(PoseToPointFactor, errorNoise) { Pose3 pose = Pose3::identity(); - Point3 point(1.0 , 2.0, 3.0); + Point3 point(1.0, 2.0, 3.0); Point3 noise(-1.0, 0.5, 0.3); Point3 measured = t + noise; Key pose_key(1); Key point_key(2); - PoseToPointFactor factor(pose_key, point_key, measured, Isotropic::Sigma(3, 0.05)); + PoseToPointFactor factor(pose_key, point_key, measured, + Isotropic::Sigma(3, 0.05)); Vector expectedError = noise; Vector actualError = factor.evaluateError(pose, point); - EXPECT(assert_equal(expectedError,actualError, 1E-5)); + EXPECT(assert_equal(expectedError, actualError, 1E-5)); } /// Check Jacobians are correct @@ -48,8 +50,8 @@ TEST(PoseToPointFactor, jacobian) { gtsam::Point3 l_meas = gtsam::Point3(1, 2, 3); // Linearisation point - gtsam::Point3 p_t = gtsam::Point3(-5, 12, 2); - gtsam::Rot3 p_R = gtsam::Rot3::RzRyRx(1.5*M_PI, -0.3*M_PI, 0.4*M_PI); + gtsam::Point3 p_t = gtsam::Point3(-5, 12, 2); + gtsam::Rot3 p_R = gtsam::Rot3::RzRyRx(1.5 * M_PI, -0.3 * M_PI, 0.4 * M_PI); Pose3 p(p_R, p_t); gtsam::Point3 l = gtsam::Point3(3, 0, 5); @@ -61,8 +63,8 @@ TEST(PoseToPointFactor, jacobian) { PoseToPointFactor factor(pose_key, point_key, l_meas, noise); // Calculate numerical derivatives - boost::function f = boost::bind( - &LandmarkFactor::evaluateError, factor, _1, _2, boost::none, boost::none); + auto f = boost::bind(&PoseToPointFactor::evaluateError, factor, _1, _2, + boost::none, boost::none); Matrix numerical_H1 = numericalDerivative21(f, p, l); Matrix numerical_H2 = numericalDerivative22(f, p, l); From 37673771aec059e14705fad69a0282a9c55e3eba Mon Sep 17 00:00:00 2001 From: Fan Jiang Date: Sat, 20 Jun 2020 22:21:17 -0400 Subject: [PATCH 08/29] Fixed all alignment problems --- gtsam.h | 2 +- gtsam/base/make_shared.h | 44 ++++++++++++++++++++++++++++++++++++++++ gtsam/base/types.h | 26 ++++++++++++++++++++++++ gtsam/geometry/SOn.h | 4 ++-- wrap/Module.cpp | 5 ++++- 5 files changed, 77 insertions(+), 4 deletions(-) create mode 100644 gtsam/base/make_shared.h diff --git a/gtsam.h b/gtsam.h index 614db91c7..cf232efa5 100644 --- a/gtsam.h +++ b/gtsam.h @@ -281,7 +281,7 @@ virtual class Value { }; #include -template +template virtual class GenericValue : gtsam::Value { void serializable() const; }; diff --git a/gtsam/base/make_shared.h b/gtsam/base/make_shared.h new file mode 100644 index 000000000..c8b63f5d4 --- /dev/null +++ b/gtsam/base/make_shared.h @@ -0,0 +1,44 @@ +/* ---------------------------------------------------------------------------- + + * GTSAM Copyright 2020, Georgia Tech Research Corporation, + * Atlanta, Georgia 30332-0415 + * All Rights Reserved + * Authors: Frank Dellaert, et al. (see THANKS for the full author list) + + * See LICENSE for the license information + + * -------------------------------------------------------------------------- */ + +/** + * @file make_shared.h + * @brief make_shared trampoline function to ensure proper alignment + * @author Fan Jiang + */ + +#pragma once + +#include +#include + +#include + +#include + +namespace gtsam { + + /** + * And our own `make_shared` as a layer of wrapping on `boost::make_shared` + */ + template + boost::enable_if_t::value, boost::shared_ptr> make_shared(Args&&... args) + { + return boost::allocate_shared(Eigen::aligned_allocator(), std::forward (args)...); + } + + template + boost::enable_if_t::value, boost::shared_ptr> make_shared(Args&&... args) + { + return boost::make_shared(std::forward (args)...); + } + +} \ No newline at end of file diff --git a/gtsam/base/types.h b/gtsam/base/types.h index 2fa6eebb6..3abbdfe81 100644 --- a/gtsam/base/types.h +++ b/gtsam/base/types.h @@ -230,3 +230,29 @@ namespace std { #ifdef ERROR #undef ERROR #endif + +namespace gtsam { + + /** + * A trait to mark classes that need special alignment. + * Please refer to https://github.com/PointCloudLibrary/pcl/pull/3163 + */ +#if __cplusplus < 201703L + template using void_t = void; +#endif + + template> + struct has_custom_allocator : std::false_type { + }; + template + struct has_custom_allocator> : std::true_type { + }; + +} + +/** + * This is necessary for the Cython wrapper to work properly, and possibly reduce future misalignment problems. + */ +#define GTSAM_MAKE_ALIGNED_OPERATOR_NEW \ + EIGEN_MAKE_ALIGNED_OPERATOR_NEW \ + using _custom_allocator_type_trait = void; \ No newline at end of file diff --git a/gtsam/geometry/SOn.h b/gtsam/geometry/SOn.h index 5313d3018..767b12020 100644 --- a/gtsam/geometry/SOn.h +++ b/gtsam/geometry/SOn.h @@ -20,8 +20,8 @@ #include #include +#include #include - #include #include // TODO(frank): how to avoid? @@ -54,7 +54,7 @@ class SO : public LieGroup, internal::DimensionSO(N)> { using VectorN2 = Eigen::Matrix; using MatrixDD = Eigen::Matrix; - EIGEN_MAKE_ALIGNED_OPERATOR_NEW + GTSAM_MAKE_ALIGNED_OPERATOR_NEW protected: MatrixNN matrix_; ///< Rotation matrix diff --git a/wrap/Module.cpp b/wrap/Module.cpp index a7db9e1f6..ec02dc412 100644 --- a/wrap/Module.cpp +++ b/wrap/Module.cpp @@ -350,7 +350,10 @@ void Module::emit_cython_pxd(FileWriter& pxdFile) const { " T* get()\n" " long use_count() const\n" " T& operator*()\n\n" - " cdef shared_ptr[T] dynamic_pointer_cast[T,U](const shared_ptr[U]& r)\n" + " cdef shared_ptr[T] dynamic_pointer_cast[T,U](const shared_ptr[U]& r)\n\n"; + + // gtsam alignment-friendly shared_ptr + pxdFile.oss << "cdef extern from \"gtsam/base/make_shared.h\" namespace \"gtsam\":\n" " cdef shared_ptr[T] make_shared[T](const T& r)\n\n"; for(const TypedefPair& types: typedefs) From fad4fe39f28797f11a61461f3f0224f173046b2e Mon Sep 17 00:00:00 2001 From: Fan Jiang Date: Sat, 20 Jun 2020 22:48:40 -0400 Subject: [PATCH 09/29] Add missing include --- gtsam/base/make_shared.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/gtsam/base/make_shared.h b/gtsam/base/make_shared.h index c8b63f5d4..c5ac98f9c 100644 --- a/gtsam/base/make_shared.h +++ b/gtsam/base/make_shared.h @@ -20,7 +20,7 @@ #include #include -#include +#include #include From 693253f3768bbd618a688a8c173b6f1bd576fdec Mon Sep 17 00:00:00 2001 From: Fan Jiang Date: Sat, 20 Jun 2020 22:52:58 -0400 Subject: [PATCH 10/29] Fix wrap tests --- wrap/tests/expected-cython/geometry.pxd | 2 ++ 1 file changed, 2 insertions(+) diff --git a/wrap/tests/expected-cython/geometry.pxd b/wrap/tests/expected-cython/geometry.pxd index 0d9adac5f..3527840a3 100644 --- a/wrap/tests/expected-cython/geometry.pxd +++ b/wrap/tests/expected-cython/geometry.pxd @@ -16,6 +16,8 @@ cdef extern from "boost/shared_ptr.hpp" namespace "boost": T& operator*() cdef shared_ptr[T] dynamic_pointer_cast[T,U](const shared_ptr[U]& r) + +cdef extern from "gtsam/base/make_shared.h" namespace "gtsam": cdef shared_ptr[T] make_shared[T](const T& r) cdef extern from "gtsam/geometry/Point2.h" namespace "gtsam": From eab53f69de01ac06b9d2d20821539b4be4fade21 Mon Sep 17 00:00:00 2001 From: Fan Jiang Date: Mon, 22 Jun 2020 13:37:50 -0400 Subject: [PATCH 11/29] Address Frank's comments --- gtsam/base/make_shared.h | 14 +++++++------- 1 file changed, 7 insertions(+), 7 deletions(-) diff --git a/gtsam/base/make_shared.h b/gtsam/base/make_shared.h index c5ac98f9c..03de30497 100644 --- a/gtsam/base/make_shared.h +++ b/gtsam/base/make_shared.h @@ -17,28 +17,28 @@ #pragma once -#include #include -#include - #include +#include +#include + + namespace gtsam { - /** - * And our own `make_shared` as a layer of wrapping on `boost::make_shared` - */ + /// Add our own `make_shared` as a layer of wrapping on `boost::make_shared` template boost::enable_if_t::value, boost::shared_ptr> make_shared(Args&&... args) { return boost::allocate_shared(Eigen::aligned_allocator(), std::forward (args)...); } + /// Fall back to the boost version if no need for alignment template boost::enable_if_t::value, boost::shared_ptr> make_shared(Args&&... args) { return boost::make_shared(std::forward (args)...); } -} \ No newline at end of file +} From 8f923fa081f0702cb36681675833476c17f692ce Mon Sep 17 00:00:00 2001 From: Fan Jiang Date: Mon, 22 Jun 2020 15:18:31 -0400 Subject: [PATCH 12/29] Move away from boost --- gtsam/base/make_shared.h | 13 ++++++++++--- 1 file changed, 10 insertions(+), 3 deletions(-) diff --git a/gtsam/base/make_shared.h b/gtsam/base/make_shared.h index 03de30497..966dd516d 100644 --- a/gtsam/base/make_shared.h +++ b/gtsam/base/make_shared.h @@ -22,21 +22,28 @@ #include #include -#include +#include + +#if __cplusplus <= 201103L +namespace gtsam { + template + using enable_if_t = typename std::enable_if::type; +} +#endif namespace gtsam { /// Add our own `make_shared` as a layer of wrapping on `boost::make_shared` template - boost::enable_if_t::value, boost::shared_ptr> make_shared(Args&&... args) + gtsam::enable_if_t::value, boost::shared_ptr> make_shared(Args&&... args) { return boost::allocate_shared(Eigen::aligned_allocator(), std::forward (args)...); } /// Fall back to the boost version if no need for alignment template - boost::enable_if_t::value, boost::shared_ptr> make_shared(Args&&... args) + gtsam::enable_if_t::value, boost::shared_ptr> make_shared(Args&&... args) { return boost::make_shared(std::forward (args)...); } From a796f74b8004d7cc12acaf3d20c9b3827a590770 Mon Sep 17 00:00:00 2001 From: Gerry Chen Date: Mon, 22 Jun 2020 20:24:32 -0400 Subject: [PATCH 13/29] use boost paths append to have platform agnostic path separators --- gtsam/base/serializationTestHelpers.h | 27 ++++++++++++++------------- 1 file changed, 14 insertions(+), 13 deletions(-) diff --git a/gtsam/base/serializationTestHelpers.h b/gtsam/base/serializationTestHelpers.h index 031a6278f..602fd68f6 100644 --- a/gtsam/base/serializationTestHelpers.h +++ b/gtsam/base/serializationTestHelpers.h @@ -42,10 +42,11 @@ T create() { } // Creates or empties a folder in the build folder and returns the relative path -std::string resetFilesystem() { - boost::filesystem::remove_all("actual"); - boost::filesystem::create_directory("actual"); - return "actual/"; +boost::filesystem::path resetFilesystem( + boost::filesystem::path folder = "actual") { + boost::filesystem::remove_all(folder); + boost::filesystem::create_directory(folder); + return folder; } // Templated round-trip serialization @@ -61,10 +62,10 @@ void roundtrip(const T& input, T& output) { // Templated round-trip serialization using a file template void roundtripFile(const T& input, T& output) { - std::string path = resetFilesystem(); + boost::filesystem::path path = resetFilesystem()/"graph.dat"; - serializeToFile(input, path + "graph.dat"); - deserializeFromFile(path + "graph.dat", output); + serializeToFile(input, path.string()); + deserializeFromFile(path.string(), output); } // This version requires equality operator @@ -109,13 +110,13 @@ void roundtripXML(const T& input, T& output) { // Templated round-trip serialization using XML File template void roundtripXMLFile(const T& input, T& output) { - std::string path = resetFilesystem(); + boost::filesystem::path path = resetFilesystem()/"graph.xml"; // Serialize - serializeToXMLFile(input, path + "graph.xml"); + serializeToXMLFile(input, path.string()); // De-serialize - deserializeFromXMLFile(path + "graph.xml", output); + deserializeFromXMLFile(path.string(), output); } // This version requires equality operator @@ -160,11 +161,11 @@ void roundtripBinary(const T& input, T& output) { // Templated round-trip serialization using Binary file template void roundtripBinaryFile(const T& input, T& output) { - std::string path = resetFilesystem(); + boost::filesystem::path path = resetFilesystem()/"graph.bin"; // Serialize - serializeToBinaryFile(input, path + "graph.bin"); + serializeToBinaryFile(input, path.string()); // De-serialize - deserializeFromBinaryFile(path + "graph.bin", output); + deserializeFromBinaryFile(path.string(), output); } // This version requires equality operator From 327cbc515ff93db6f6547ed3deead1bdf9cfdb2e Mon Sep 17 00:00:00 2001 From: Gerry Chen Date: Mon, 22 Jun 2020 21:15:07 -0400 Subject: [PATCH 14/29] Separate stream creation and serialization Recommended by @ProfFan in #343 with the objective of making (de)serialize to string and to file more similar --- gtsam/base/serialization.h | 86 +++++++++++++++++++++++--------------- 1 file changed, 53 insertions(+), 33 deletions(-) diff --git a/gtsam/base/serialization.h b/gtsam/base/serialization.h index 191e0ecfb..031ee3a3e 100644 --- a/gtsam/base/serialization.h +++ b/gtsam/base/serialization.h @@ -44,18 +44,28 @@ namespace gtsam { // Serialization directly to strings in compressed format template -std::string serialize(const T& input) { - std::ostringstream out_archive_stream; +void serialize(const T& input, std::ostream & out_archive_stream) { boost::archive::text_oarchive out_archive(out_archive_stream); out_archive << input; +} + +template +void deserialize(std::istream & in_archive_stream, T& output) { + boost::archive::text_iarchive in_archive(in_archive_stream); + in_archive >> output; +} + +template +std::string serialize(const T& input) { + std::ostringstream out_archive_stream; + serialize(input, out_archive_stream); return out_archive_stream.str(); } template void deserialize(const std::string& serialized, T& output) { std::istringstream in_archive_stream(serialized); - boost::archive::text_iarchive in_archive(in_archive_stream); - in_archive >> output; + deserialize(in_archive_stream, output); } template @@ -63,8 +73,7 @@ bool serializeToFile(const T& input, const std::string& filename) { std::ofstream out_archive_stream(filename.c_str()); if (!out_archive_stream.is_open()) return false; - boost::archive::text_oarchive out_archive(out_archive_stream); - out_archive << input; + serialize(input, out_archive_stream); out_archive_stream.close(); return true; } @@ -74,31 +83,37 @@ bool deserializeFromFile(const std::string& filename, T& output) { std::ifstream in_archive_stream(filename.c_str()); if (!in_archive_stream.is_open()) return false; - boost::archive::text_iarchive in_archive(in_archive_stream); - in_archive >> output; + deserialize(in_archive_stream, output); in_archive_stream.close(); return true; } // Serialization to XML format with named structures +template +void serializeXML(const T& input, std::ostream& out_archive_stream, + const std::string& name = "data") { + boost::archive::xml_oarchive out_archive(out_archive_stream); + out_archive << boost::serialization::make_nvp(name.c_str(), input); +} + +template +void deserializeXML(std::istream& in_archive_stream, T& output, + const std::string& name = "data") { + boost::archive::xml_iarchive in_archive(in_archive_stream); + in_archive >> boost::serialization::make_nvp(name.c_str(), output); +} + template std::string serializeXML(const T& input, const std::string& name="data") { std::ostringstream out_archive_stream; - // braces to flush out_archive as it goes out of scope before taking str() - // fixes crash with boost 1.66-1.68 - // see https://github.com/boostorg/serialization/issues/82 - { - boost::archive::xml_oarchive out_archive(out_archive_stream); - out_archive << boost::serialization::make_nvp(name.c_str(), input); - } + serializeXML(input, out_archive_stream, name); return out_archive_stream.str(); } template void deserializeXML(const std::string& serialized, T& output, const std::string& name="data") { std::istringstream in_archive_stream(serialized); - boost::archive::xml_iarchive in_archive(in_archive_stream); - in_archive >> boost::serialization::make_nvp(name.c_str(), output); + deserializeXML(in_archive_stream, output, name); } template @@ -106,10 +121,7 @@ bool serializeToXMLFile(const T& input, const std::string& filename, const std:: std::ofstream out_archive_stream(filename.c_str()); if (!out_archive_stream.is_open()) return false; - { - boost::archive::xml_oarchive out_archive(out_archive_stream); - out_archive << boost::serialization::make_nvp(name.c_str(), input); - } + serializeXML(input, out_archive_stream, name); out_archive_stream.close(); return true; } @@ -119,28 +131,38 @@ bool deserializeFromXMLFile(const std::string& filename, T& output, const std::s std::ifstream in_archive_stream(filename.c_str()); if (!in_archive_stream.is_open()) return false; - { - boost::archive::xml_iarchive in_archive(in_archive_stream); - in_archive >> boost::serialization::make_nvp(name.c_str(), output); - } + deserializeXML(in_archive_stream, output, name); in_archive_stream.close(); return true; } +// Serialization to binary format with named structures +template +void serializeBinary(const T& input, std::ostream& out_archive_stream, + const std::string& name = "data") { + boost::archive::binary_oarchive out_archive(out_archive_stream); + out_archive << boost::serialization::make_nvp(name.c_str(), input); +} + +template +void deserializeBinary(std::istream& in_archive_stream, T& output, + const std::string& name = "data") { + boost::archive::binary_iarchive in_archive(in_archive_stream); + in_archive >> boost::serialization::make_nvp(name.c_str(), output); +} + // Serialization to binary format with named structures template std::string serializeBinary(const T& input, const std::string& name="data") { std::ostringstream out_archive_stream; - boost::archive::binary_oarchive out_archive(out_archive_stream); - out_archive << boost::serialization::make_nvp(name.c_str(), input); + serializeBinary(input, out_archive_stream, name); return out_archive_stream.str(); } template void deserializeBinary(const std::string& serialized, T& output, const std::string& name="data") { std::istringstream in_archive_stream(serialized); - boost::archive::binary_iarchive in_archive(in_archive_stream); - in_archive >> boost::serialization::make_nvp(name.c_str(), output); + deserializeBinary(in_archive_stream, output, name); } template @@ -148,8 +170,7 @@ bool serializeToBinaryFile(const T& input, const std::string& filename, const st std::ofstream out_archive_stream(filename.c_str()); if (!out_archive_stream.is_open()) return false; - boost::archive::binary_oarchive out_archive(out_archive_stream); - out_archive << boost::serialization::make_nvp(name.c_str(), input); + serializeBinary(input, out_archive_stream, name); out_archive_stream.close(); return true; } @@ -159,8 +180,7 @@ bool deserializeFromBinaryFile(const std::string& filename, T& output, const std std::ifstream in_archive_stream(filename.c_str()); if (!in_archive_stream.is_open()) return false; - boost::archive::binary_iarchive in_archive(in_archive_stream); - in_archive >> boost::serialization::make_nvp(name.c_str(), output); + deserializeBinary(in_archive_stream, output, name); in_archive_stream.close(); return true; } From a4737d47066c0ee0e533bea393f4da14347e9abf Mon Sep 17 00:00:00 2001 From: Gerry Chen Date: Mon, 22 Jun 2020 21:18:43 -0400 Subject: [PATCH 15/29] formatting to Google style --- gtsam/base/serialization.h | 78 +++++++++++++++++++------------------- 1 file changed, 40 insertions(+), 38 deletions(-) diff --git a/gtsam/base/serialization.h b/gtsam/base/serialization.h index 031ee3a3e..aaf06275c 100644 --- a/gtsam/base/serialization.h +++ b/gtsam/base/serialization.h @@ -43,46 +43,44 @@ namespace gtsam { // Serialization directly to strings in compressed format -template -void serialize(const T& input, std::ostream & out_archive_stream) { +template +void serialize(const T& input, std::ostream& out_archive_stream) { boost::archive::text_oarchive out_archive(out_archive_stream); out_archive << input; } -template -void deserialize(std::istream & in_archive_stream, T& output) { +template +void deserialize(std::istream& in_archive_stream, T& output) { boost::archive::text_iarchive in_archive(in_archive_stream); in_archive >> output; } -template +template std::string serialize(const T& input) { std::ostringstream out_archive_stream; serialize(input, out_archive_stream); return out_archive_stream.str(); } -template +template void deserialize(const std::string& serialized, T& output) { std::istringstream in_archive_stream(serialized); deserialize(in_archive_stream, output); } -template +template bool serializeToFile(const T& input, const std::string& filename) { std::ofstream out_archive_stream(filename.c_str()); - if (!out_archive_stream.is_open()) - return false; + if (!out_archive_stream.is_open()) return false; serialize(input, out_archive_stream); out_archive_stream.close(); return true; } -template +template bool deserializeFromFile(const std::string& filename, T& output) { std::ifstream in_archive_stream(filename.c_str()); - if (!in_archive_stream.is_open()) - return false; + if (!in_archive_stream.is_open()) return false; deserialize(in_archive_stream, output); in_archive_stream.close(); return true; @@ -103,34 +101,36 @@ void deserializeXML(std::istream& in_archive_stream, T& output, in_archive >> boost::serialization::make_nvp(name.c_str(), output); } -template -std::string serializeXML(const T& input, const std::string& name="data") { +template +std::string serializeXML(const T& input, + const std::string& name = "data") { std::ostringstream out_archive_stream; serializeXML(input, out_archive_stream, name); return out_archive_stream.str(); } -template -void deserializeXML(const std::string& serialized, T& output, const std::string& name="data") { +template +void deserializeXML(const std::string& serialized, T& output, + const std::string& name = "data") { std::istringstream in_archive_stream(serialized); deserializeXML(in_archive_stream, output, name); } -template -bool serializeToXMLFile(const T& input, const std::string& filename, const std::string& name="data") { +template +bool serializeToXMLFile(const T& input, const std::string& filename, + const std::string& name = "data") { std::ofstream out_archive_stream(filename.c_str()); - if (!out_archive_stream.is_open()) - return false; + if (!out_archive_stream.is_open()) return false; serializeXML(input, out_archive_stream, name); out_archive_stream.close(); return true; } -template -bool deserializeFromXMLFile(const std::string& filename, T& output, const std::string& name="data") { +template +bool deserializeFromXMLFile(const std::string& filename, T& output, + const std::string& name = "data") { std::ifstream in_archive_stream(filename.c_str()); - if (!in_archive_stream.is_open()) - return false; + if (!in_archive_stream.is_open()) return false; deserializeXML(in_archive_stream, output, name); in_archive_stream.close(); return true; @@ -139,7 +139,7 @@ bool deserializeFromXMLFile(const std::string& filename, T& output, const std::s // Serialization to binary format with named structures template void serializeBinary(const T& input, std::ostream& out_archive_stream, - const std::string& name = "data") { + const std::string& name = "data") { boost::archive::binary_oarchive out_archive(out_archive_stream); out_archive << boost::serialization::make_nvp(name.c_str(), input); } @@ -152,37 +152,39 @@ void deserializeBinary(std::istream& in_archive_stream, T& output, } // Serialization to binary format with named structures -template -std::string serializeBinary(const T& input, const std::string& name="data") { +template +std::string serializeBinary(const T& input, + const std::string& name = "data") { std::ostringstream out_archive_stream; serializeBinary(input, out_archive_stream, name); return out_archive_stream.str(); } -template -void deserializeBinary(const std::string& serialized, T& output, const std::string& name="data") { +template +void deserializeBinary(const std::string& serialized, T& output, + const std::string& name = "data") { std::istringstream in_archive_stream(serialized); deserializeBinary(in_archive_stream, output, name); } -template -bool serializeToBinaryFile(const T& input, const std::string& filename, const std::string& name="data") { +template +bool serializeToBinaryFile(const T& input, const std::string& filename, + const std::string& name = "data") { std::ofstream out_archive_stream(filename.c_str()); - if (!out_archive_stream.is_open()) - return false; + if (!out_archive_stream.is_open()) return false; serializeBinary(input, out_archive_stream, name); out_archive_stream.close(); return true; } -template -bool deserializeFromBinaryFile(const std::string& filename, T& output, const std::string& name="data") { +template +bool deserializeFromBinaryFile(const std::string& filename, T& output, + const std::string& name = "data") { std::ifstream in_archive_stream(filename.c_str()); - if (!in_archive_stream.is_open()) - return false; + if (!in_archive_stream.is_open()) return false; deserializeBinary(in_archive_stream, output, name); in_archive_stream.close(); return true; } -} // \namespace gtsam +} // namespace gtsam From 82db82bbf5d46bb64dc50ba52507b39ee7f061ed Mon Sep 17 00:00:00 2001 From: Gerry Chen Date: Mon, 22 Jun 2020 23:08:39 -0400 Subject: [PATCH 16/29] fixed unit test failure on `testSerializationBase` object `output` was getting reused, but should be re-loaded into a "blank" object each time. --- gtsam/base/serializationTestHelpers.h | 46 ++++++++++++--------------- 1 file changed, 20 insertions(+), 26 deletions(-) diff --git a/gtsam/base/serializationTestHelpers.h b/gtsam/base/serializationTestHelpers.h index 602fd68f6..bac166e5b 100644 --- a/gtsam/base/serializationTestHelpers.h +++ b/gtsam/base/serializationTestHelpers.h @@ -44,8 +44,8 @@ T create() { // Creates or empties a folder in the build folder and returns the relative path boost::filesystem::path resetFilesystem( boost::filesystem::path folder = "actual") { - boost::filesystem::remove_all(folder); - boost::filesystem::create_directory(folder); + // boost::filesystem::remove_all(folder); + // boost::filesystem::create_directory(folder); return folder; } @@ -71,11 +71,10 @@ void roundtripFile(const T& input, T& output) { // This version requires equality operator template bool equality(const T& input = T()) { - T output = create(); + T output = create(), outputf = create(); roundtrip(input,output); - if (input != output) return false; - roundtripFile(input,output); - return input==output; + roundtripFile(input,outputf); + return (input==output) && (input==outputf); } // This version requires Testable @@ -89,11 +88,10 @@ bool equalsObj(const T& input = T()) { // De-referenced version for pointers, requires equals method template bool equalsDereferenced(const T& input) { - T output = create(); + T output = create(), outputf = create(); roundtrip(input,output); - if (!input->equals(*output)) return false; - roundtripFile(input,output); - return input->equals(*output); + roundtripFile(input,outputf); + return (input->equals(*output)) && (input->equals(*outputf)); } // Templated round-trip serialization using XML @@ -122,11 +120,10 @@ void roundtripXMLFile(const T& input, T& output) { // This version requires equality operator template bool equalityXML(const T& input = T()) { - T output = create(); + T output = create(), outputf = create(); roundtripXML(input,output); - if (input != output) return false; - roundtripXMLFile(input,output); - return input==output; + roundtripXMLFile(input,outputf); + return (input==output) && (input==outputf); } // This version requires Testable @@ -140,11 +137,10 @@ bool equalsXML(const T& input = T()) { // This version is for pointers, requires equals method template bool equalsDereferencedXML(const T& input = T()) { - T output = create(); + T output = create(), outputf = create(); roundtripXML(input,output); - if (!input->equals(*output)) return false; - roundtripXMLFile(input, output); - return input->equals(*output); + roundtripXMLFile(input, outputf); + return (input->equals(*output)) && (input->equals(*outputf)); } // Templated round-trip serialization using XML @@ -171,11 +167,10 @@ void roundtripBinaryFile(const T& input, T& output) { // This version requires equality operator template bool equalityBinary(const T& input = T()) { - T output = create(); + T output = create(), outputf = create(); roundtripBinary(input,output); - if (input != output) return false; - roundtripBinaryFile(input,output); - return input==output; + roundtripBinaryFile(input,outputf); + return (input==output) && (input==outputf); } // This version requires Testable @@ -189,11 +184,10 @@ bool equalsBinary(const T& input = T()) { // This version is for pointers, requires equals method template bool equalsDereferencedBinary(const T& input = T()) { - T output = create(); + T output = create(), outputf = create(); roundtripBinary(input,output); - if (!input->equals(*output)) return false; - roundtripBinaryFile(input,output); - return input->equals(*output); + roundtripBinaryFile(input,outputf); + return (input->equals(*output)) && (input->equals(*outputf)); } } // \namespace serializationTestHelpers From a0a3b8f459df37349a7b4af7d6b52016142204cb Mon Sep 17 00:00:00 2001 From: Gerry Chen Date: Tue, 23 Jun 2020 09:52:29 -0400 Subject: [PATCH 17/29] reset filesystem - forgot to uncomment these after debugging --- gtsam/base/serializationTestHelpers.h | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/gtsam/base/serializationTestHelpers.h b/gtsam/base/serializationTestHelpers.h index bac166e5b..5d67b2687 100644 --- a/gtsam/base/serializationTestHelpers.h +++ b/gtsam/base/serializationTestHelpers.h @@ -44,8 +44,8 @@ T create() { // Creates or empties a folder in the build folder and returns the relative path boost::filesystem::path resetFilesystem( boost::filesystem::path folder = "actual") { - // boost::filesystem::remove_all(folder); - // boost::filesystem::create_directory(folder); + boost::filesystem::remove_all(folder); + boost::filesystem::create_directory(folder); return folder; } From b41809203f636878dbbc0aad718ac6f7343e82e6 Mon Sep 17 00:00:00 2001 From: Fan Jiang Date: Tue, 23 Jun 2020 18:37:12 -0400 Subject: [PATCH 18/29] Revise comments --- gtsam/base/types.h | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/gtsam/base/types.h b/gtsam/base/types.h index 3abbdfe81..93c475c40 100644 --- a/gtsam/base/types.h +++ b/gtsam/base/types.h @@ -235,7 +235,8 @@ namespace gtsam { /** * A trait to mark classes that need special alignment. - * Please refer to https://github.com/PointCloudLibrary/pcl/pull/3163 + * This is required to make boost::make_shared and etc respect alignment, which is essential for the Python + * wrappers to work properly. */ #if __cplusplus < 201703L template using void_t = void; From de7332fceac3224d4ea693a8f1631300b3345c74 Mon Sep 17 00:00:00 2001 From: Gerry Chen Date: Wed, 24 Jun 2020 02:39:44 -0400 Subject: [PATCH 19/29] remove file roundtrip test for pointers --- gtsam/base/serializationTestHelpers.h | 15 ++++++--------- 1 file changed, 6 insertions(+), 9 deletions(-) diff --git a/gtsam/base/serializationTestHelpers.h b/gtsam/base/serializationTestHelpers.h index 5d67b2687..78f9d6d10 100644 --- a/gtsam/base/serializationTestHelpers.h +++ b/gtsam/base/serializationTestHelpers.h @@ -88,10 +88,9 @@ bool equalsObj(const T& input = T()) { // De-referenced version for pointers, requires equals method template bool equalsDereferenced(const T& input) { - T output = create(), outputf = create(); + T output = create(); roundtrip(input,output); - roundtripFile(input,outputf); - return (input->equals(*output)) && (input->equals(*outputf)); + return input->equals(*output); } // Templated round-trip serialization using XML @@ -137,10 +136,9 @@ bool equalsXML(const T& input = T()) { // This version is for pointers, requires equals method template bool equalsDereferencedXML(const T& input = T()) { - T output = create(), outputf = create(); + T output = create(); roundtripXML(input,output); - roundtripXMLFile(input, outputf); - return (input->equals(*output)) && (input->equals(*outputf)); + return input->equals(*output); } // Templated round-trip serialization using XML @@ -184,10 +182,9 @@ bool equalsBinary(const T& input = T()) { // This version is for pointers, requires equals method template bool equalsDereferencedBinary(const T& input = T()) { - T output = create(), outputf = create(); + T output = create(); roundtripBinary(input,output); - roundtripBinaryFile(input,outputf); - return (input->equals(*output)) && (input->equals(*outputf)); + return input->equals(*output); } } // \namespace serializationTestHelpers From 7d7475b881ffc9f21ce2f49c3e4d3890e9e6d21f Mon Sep 17 00:00:00 2001 From: Fan Jiang Date: Wed, 24 Jun 2020 14:15:46 -0400 Subject: [PATCH 20/29] Style fixes as commented by @dellaert --- gtsam/base/make_shared.h | 22 +++++++++++++--------- gtsam/base/types.h | 19 ++++++++++--------- 2 files changed, 23 insertions(+), 18 deletions(-) diff --git a/gtsam/base/make_shared.h b/gtsam/base/make_shared.h index 966dd516d..c7d98cdee 100644 --- a/gtsam/base/make_shared.h +++ b/gtsam/base/make_shared.h @@ -25,27 +25,31 @@ #include -#if __cplusplus <= 201103L namespace gtsam { template using enable_if_t = typename std::enable_if::type; } -#endif namespace gtsam { - /// Add our own `make_shared` as a layer of wrapping on `boost::make_shared` + /** Add our own `make_shared` as a layer of wrapping on `boost::make_shared` + * This solves the problem with the stock `make_shared` that custom alignment is not respected, causing SEGFAULTs + * at runtime, which is notoriously hard to debug. + * + * @tparam T The type of object being constructed + * @tparam Args Type of the arguments of the constructor + * @param args Arguments of the constructor + * @return The object created as a boost::shared_ptr + */ template - gtsam::enable_if_t::value, boost::shared_ptr> make_shared(Args&&... args) - { - return boost::allocate_shared(Eigen::aligned_allocator(), std::forward (args)...); + gtsam::enable_if_t::value, boost::shared_ptr> make_shared(Args &&... args) { + return boost::allocate_shared(Eigen::aligned_allocator(), std::forward(args)...); } /// Fall back to the boost version if no need for alignment template - gtsam::enable_if_t::value, boost::shared_ptr> make_shared(Args&&... args) - { - return boost::make_shared(std::forward (args)...); + gtsam::enable_if_t::value, boost::shared_ptr> make_shared(Args &&... args) { + return boost::make_shared(std::forward(args)...); } } diff --git a/gtsam/base/types.h b/gtsam/base/types.h index 93c475c40..a4b2fb6ea 100644 --- a/gtsam/base/types.h +++ b/gtsam/base/types.h @@ -233,27 +233,28 @@ namespace std { namespace gtsam { + /// Convenience void_t as we assume C++11, it will not conflict the std one in C++17 as this is in `gtsam::` + template using void_t = void; + /** - * A trait to mark classes that need special alignment. + * A SFINAE trait to mark classes that need special alignment. * This is required to make boost::make_shared and etc respect alignment, which is essential for the Python * wrappers to work properly. */ -#if __cplusplus < 201703L - template using void_t = void; -#endif - template> - struct has_custom_allocator : std::false_type { + struct needs_eigen_aligned_allocator : std::false_type { }; template - struct has_custom_allocator> : std::true_type { + struct needs_eigen_aligned_allocator> : std::true_type { }; } /** - * This is necessary for the Cython wrapper to work properly, and possibly reduce future misalignment problems. + * This marks a GTSAM object to require alignment. With this macro an object will automatically be allocated in aligned + * memory when one uses `gtsam::make_shared`. It reduces future misalignment problems that is hard to debug. + * See https://eigen.tuxfamily.org/dox/group__DenseMatrixManipulation__Alignement.html for details */ #define GTSAM_MAKE_ALIGNED_OPERATOR_NEW \ EIGEN_MAKE_ALIGNED_OPERATOR_NEW \ - using _custom_allocator_type_trait = void; \ No newline at end of file + using _eigen_aligned_allocator_trait = void; From 6d75e992e896f54a1bd3956ff5f8cd1dddf5e814 Mon Sep 17 00:00:00 2001 From: Gerry Chen Date: Wed, 24 Jun 2020 14:16:00 -0400 Subject: [PATCH 21/29] serialization docstrings --- gtsam/base/serialization.h | 37 ++++++++++++++++++++++++--- gtsam/base/serializationTestHelpers.h | 17 +----------- 2 files changed, 34 insertions(+), 20 deletions(-) diff --git a/gtsam/base/serialization.h b/gtsam/base/serialization.h index aaf06275c..1a319ab17 100644 --- a/gtsam/base/serialization.h +++ b/gtsam/base/serialization.h @@ -42,19 +42,25 @@ namespace gtsam { -// Serialization directly to strings in compressed format +/** @name Standard serialization + * Serialization in default compressed format + */ +///@{ +/// serializes to a stream template void serialize(const T& input, std::ostream& out_archive_stream) { boost::archive::text_oarchive out_archive(out_archive_stream); out_archive << input; } +/// deserializes from a stream template void deserialize(std::istream& in_archive_stream, T& output) { boost::archive::text_iarchive in_archive(in_archive_stream); in_archive >> output; } +/// serializes to a string template std::string serialize(const T& input) { std::ostringstream out_archive_stream; @@ -62,12 +68,14 @@ std::string serialize(const T& input) { return out_archive_stream.str(); } +/// deserializes from a string template void deserialize(const std::string& serialized, T& output) { std::istringstream in_archive_stream(serialized); deserialize(in_archive_stream, output); } +/// serializes to a file template bool serializeToFile(const T& input, const std::string& filename) { std::ofstream out_archive_stream(filename.c_str()); @@ -77,6 +85,7 @@ bool serializeToFile(const T& input, const std::string& filename) { return true; } +/// deserializes from a file template bool deserializeFromFile(const std::string& filename, T& output) { std::ifstream in_archive_stream(filename.c_str()); @@ -85,8 +94,13 @@ bool deserializeFromFile(const std::string& filename, T& output) { in_archive_stream.close(); return true; } +///@} -// Serialization to XML format with named structures +/** @name XML Serialization + * Serialization to XML format with named structures + */ +///@{ +/// serializes to a stream in XML template void serializeXML(const T& input, std::ostream& out_archive_stream, const std::string& name = "data") { @@ -94,6 +108,7 @@ void serializeXML(const T& input, std::ostream& out_archive_stream, out_archive << boost::serialization::make_nvp(name.c_str(), input); } +/// deserializes from a stream in XML template void deserializeXML(std::istream& in_archive_stream, T& output, const std::string& name = "data") { @@ -101,6 +116,7 @@ void deserializeXML(std::istream& in_archive_stream, T& output, in_archive >> boost::serialization::make_nvp(name.c_str(), output); } +/// serializes to a string in XML template std::string serializeXML(const T& input, const std::string& name = "data") { @@ -109,6 +125,7 @@ std::string serializeXML(const T& input, return out_archive_stream.str(); } +/// deserializes from a string in XML template void deserializeXML(const std::string& serialized, T& output, const std::string& name = "data") { @@ -116,6 +133,7 @@ void deserializeXML(const std::string& serialized, T& output, deserializeXML(in_archive_stream, output, name); } +/// serializes to an XML file template bool serializeToXMLFile(const T& input, const std::string& filename, const std::string& name = "data") { @@ -126,6 +144,7 @@ bool serializeToXMLFile(const T& input, const std::string& filename, return true; } +/// deserializes from an XML file template bool deserializeFromXMLFile(const std::string& filename, T& output, const std::string& name = "data") { @@ -135,8 +154,13 @@ bool deserializeFromXMLFile(const std::string& filename, T& output, in_archive_stream.close(); return true; } +///@} -// Serialization to binary format with named structures +/** @name Binary Serialization + * Serialization to binary format with named structures + */ +///@{ +/// serializes to a stream in binary template void serializeBinary(const T& input, std::ostream& out_archive_stream, const std::string& name = "data") { @@ -144,6 +168,7 @@ void serializeBinary(const T& input, std::ostream& out_archive_stream, out_archive << boost::serialization::make_nvp(name.c_str(), input); } +/// deserializes from a stream in binary template void deserializeBinary(std::istream& in_archive_stream, T& output, const std::string& name = "data") { @@ -151,7 +176,7 @@ void deserializeBinary(std::istream& in_archive_stream, T& output, in_archive >> boost::serialization::make_nvp(name.c_str(), output); } -// Serialization to binary format with named structures +/// serializes to a string in binary template std::string serializeBinary(const T& input, const std::string& name = "data") { @@ -160,6 +185,7 @@ std::string serializeBinary(const T& input, return out_archive_stream.str(); } +/// deserializes from a string in binary template void deserializeBinary(const std::string& serialized, T& output, const std::string& name = "data") { @@ -167,6 +193,7 @@ void deserializeBinary(const std::string& serialized, T& output, deserializeBinary(in_archive_stream, output, name); } +/// serializes to a binary file template bool serializeToBinaryFile(const T& input, const std::string& filename, const std::string& name = "data") { @@ -177,6 +204,7 @@ bool serializeToBinaryFile(const T& input, const std::string& filename, return true; } +/// deserializes from a binary file template bool deserializeFromBinaryFile(const std::string& filename, T& output, const std::string& name = "data") { @@ -186,5 +214,6 @@ bool deserializeFromBinaryFile(const std::string& filename, T& output, in_archive_stream.close(); return true; } +///@} } // namespace gtsam diff --git a/gtsam/base/serializationTestHelpers.h b/gtsam/base/serializationTestHelpers.h index 78f9d6d10..5994a5e51 100644 --- a/gtsam/base/serializationTestHelpers.h +++ b/gtsam/base/serializationTestHelpers.h @@ -52,10 +52,8 @@ boost::filesystem::path resetFilesystem( // Templated round-trip serialization template void roundtrip(const T& input, T& output) { - // Serialize std::string serialized = serialize(input); if (verbose) std::cout << serialized << std::endl << std::endl; - deserialize(serialized, output); } @@ -63,12 +61,11 @@ void roundtrip(const T& input, T& output) { template void roundtripFile(const T& input, T& output) { boost::filesystem::path path = resetFilesystem()/"graph.dat"; - serializeToFile(input, path.string()); deserializeFromFile(path.string(), output); } -// This version requires equality operator +// This version requires equality operator and uses string and file round-trips template bool equality(const T& input = T()) { T output = create(), outputf = create(); @@ -96,11 +93,8 @@ bool equalsDereferenced(const T& input) { // Templated round-trip serialization using XML template void roundtripXML(const T& input, T& output) { - // Serialize std::string serialized = serializeXML(input); if (verbose) std::cout << serialized << std::endl << std::endl; - - // De-serialize deserializeXML(serialized, output); } @@ -108,11 +102,7 @@ void roundtripXML(const T& input, T& output) { template void roundtripXMLFile(const T& input, T& output) { boost::filesystem::path path = resetFilesystem()/"graph.xml"; - - // Serialize serializeToXMLFile(input, path.string()); - - // De-serialize deserializeFromXMLFile(path.string(), output); } @@ -144,11 +134,8 @@ bool equalsDereferencedXML(const T& input = T()) { // Templated round-trip serialization using XML template void roundtripBinary(const T& input, T& output) { - // Serialize std::string serialized = serializeBinary(input); if (verbose) std::cout << serialized << std::endl << std::endl; - - // De-serialize deserializeBinary(serialized, output); } @@ -156,9 +143,7 @@ void roundtripBinary(const T& input, T& output) { template void roundtripBinaryFile(const T& input, T& output) { boost::filesystem::path path = resetFilesystem()/"graph.bin"; - // Serialize serializeToBinaryFile(input, path.string()); - // De-serialize deserializeFromBinaryFile(path.string(), output); } From b37be7d640567be9b78c699d158c88035d4f789e Mon Sep 17 00:00:00 2001 From: Gerry Chen Date: Wed, 24 Jun 2020 14:33:08 -0400 Subject: [PATCH 22/29] rename serialization functions with less ambiguous names According to Varun's suggestion. Note: string functions should be automatically inlined by compiler to avoid passing big strings. --- gtsam/base/serialization.h | 88 +++++++++++++++++++++++++++----------- 1 file changed, 64 insertions(+), 24 deletions(-) diff --git a/gtsam/base/serialization.h b/gtsam/base/serialization.h index 1a319ab17..f589ecc5e 100644 --- a/gtsam/base/serialization.h +++ b/gtsam/base/serialization.h @@ -48,31 +48,31 @@ namespace gtsam { ///@{ /// serializes to a stream template -void serialize(const T& input, std::ostream& out_archive_stream) { +void serializeToStream(const T& input, std::ostream& out_archive_stream) { boost::archive::text_oarchive out_archive(out_archive_stream); out_archive << input; } /// deserializes from a stream template -void deserialize(std::istream& in_archive_stream, T& output) { +void deserializeFromStream(std::istream& in_archive_stream, T& output) { boost::archive::text_iarchive in_archive(in_archive_stream); in_archive >> output; } /// serializes to a string template -std::string serialize(const T& input) { +std::string serializeToString(const T& input) { std::ostringstream out_archive_stream; - serialize(input, out_archive_stream); + serializeToStream(input, out_archive_stream); return out_archive_stream.str(); } /// deserializes from a string template -void deserialize(const std::string& serialized, T& output) { +void deserializeFromString(const std::string& serialized, T& output) { std::istringstream in_archive_stream(serialized); - deserialize(in_archive_stream, output); + deserializeFromStream(in_archive_stream, output); } /// serializes to a file @@ -80,7 +80,7 @@ template bool serializeToFile(const T& input, const std::string& filename) { std::ofstream out_archive_stream(filename.c_str()); if (!out_archive_stream.is_open()) return false; - serialize(input, out_archive_stream); + serializeToStream(input, out_archive_stream); out_archive_stream.close(); return true; } @@ -90,10 +90,22 @@ template bool deserializeFromFile(const std::string& filename, T& output) { std::ifstream in_archive_stream(filename.c_str()); if (!in_archive_stream.is_open()) return false; - deserialize(in_archive_stream, output); + deserializeFromStream(in_archive_stream, output); in_archive_stream.close(); return true; } + +/// serializes to a string +template +std::string serialize(const T& input) { + return serializeToString(input); +} + +/// deserializes from a string +template +void deserialize(const std::string& serialized, T& output) { + deserializeFromString(serialized, output); +} ///@} /** @name XML Serialization @@ -102,7 +114,7 @@ bool deserializeFromFile(const std::string& filename, T& output) { ///@{ /// serializes to a stream in XML template -void serializeXML(const T& input, std::ostream& out_archive_stream, +void serializeToXMLStream(const T& input, std::ostream& out_archive_stream, const std::string& name = "data") { boost::archive::xml_oarchive out_archive(out_archive_stream); out_archive << boost::serialization::make_nvp(name.c_str(), input); @@ -110,7 +122,7 @@ void serializeXML(const T& input, std::ostream& out_archive_stream, /// deserializes from a stream in XML template -void deserializeXML(std::istream& in_archive_stream, T& output, +void deserializeFromXMLStream(std::istream& in_archive_stream, T& output, const std::string& name = "data") { boost::archive::xml_iarchive in_archive(in_archive_stream); in_archive >> boost::serialization::make_nvp(name.c_str(), output); @@ -118,19 +130,19 @@ void deserializeXML(std::istream& in_archive_stream, T& output, /// serializes to a string in XML template -std::string serializeXML(const T& input, +std::string serializeToXMLString(const T& input, const std::string& name = "data") { std::ostringstream out_archive_stream; - serializeXML(input, out_archive_stream, name); + serializeToXMLStream(input, out_archive_stream, name); return out_archive_stream.str(); } /// deserializes from a string in XML template -void deserializeXML(const std::string& serialized, T& output, +void deserializeFromXMLString(const std::string& serialized, T& output, const std::string& name = "data") { std::istringstream in_archive_stream(serialized); - deserializeXML(in_archive_stream, output, name); + deserializeFromXMLStream(in_archive_stream, output, name); } /// serializes to an XML file @@ -139,7 +151,7 @@ bool serializeToXMLFile(const T& input, const std::string& filename, const std::string& name = "data") { std::ofstream out_archive_stream(filename.c_str()); if (!out_archive_stream.is_open()) return false; - serializeXML(input, out_archive_stream, name); + serializeToXMLStream(input, out_archive_stream, name); out_archive_stream.close(); return true; } @@ -150,10 +162,24 @@ bool deserializeFromXMLFile(const std::string& filename, T& output, const std::string& name = "data") { std::ifstream in_archive_stream(filename.c_str()); if (!in_archive_stream.is_open()) return false; - deserializeXML(in_archive_stream, output, name); + deserializeFromXMLStream(in_archive_stream, output, name); in_archive_stream.close(); return true; } + +/// serializes to a string in XML +template +std::string serializeXML(const T& input, + const std::string& name = "data") { + return serializeToXMLString(input, name); +} + +/// deserializes from a string in XML +template +void deserializeXML(const std::string& serialized, T& output, + const std::string& name = "data") { + deserializeFromXMLString(serialized, output, name); +} ///@} /** @name Binary Serialization @@ -162,7 +188,7 @@ bool deserializeFromXMLFile(const std::string& filename, T& output, ///@{ /// serializes to a stream in binary template -void serializeBinary(const T& input, std::ostream& out_archive_stream, +void serializeToBinaryStream(const T& input, std::ostream& out_archive_stream, const std::string& name = "data") { boost::archive::binary_oarchive out_archive(out_archive_stream); out_archive << boost::serialization::make_nvp(name.c_str(), input); @@ -170,7 +196,7 @@ void serializeBinary(const T& input, std::ostream& out_archive_stream, /// deserializes from a stream in binary template -void deserializeBinary(std::istream& in_archive_stream, T& output, +void deserializeFromBinaryStream(std::istream& in_archive_stream, T& output, const std::string& name = "data") { boost::archive::binary_iarchive in_archive(in_archive_stream); in_archive >> boost::serialization::make_nvp(name.c_str(), output); @@ -178,19 +204,19 @@ void deserializeBinary(std::istream& in_archive_stream, T& output, /// serializes to a string in binary template -std::string serializeBinary(const T& input, +std::string serializeToBinaryString(const T& input, const std::string& name = "data") { std::ostringstream out_archive_stream; - serializeBinary(input, out_archive_stream, name); + serializeToBinaryStream(input, out_archive_stream, name); return out_archive_stream.str(); } /// deserializes from a string in binary template -void deserializeBinary(const std::string& serialized, T& output, +void deserializeFromBinaryString(const std::string& serialized, T& output, const std::string& name = "data") { std::istringstream in_archive_stream(serialized); - deserializeBinary(in_archive_stream, output, name); + deserializeFromBinaryStream(in_archive_stream, output, name); } /// serializes to a binary file @@ -199,7 +225,7 @@ bool serializeToBinaryFile(const T& input, const std::string& filename, const std::string& name = "data") { std::ofstream out_archive_stream(filename.c_str()); if (!out_archive_stream.is_open()) return false; - serializeBinary(input, out_archive_stream, name); + serializeToBinaryStream(input, out_archive_stream, name); out_archive_stream.close(); return true; } @@ -210,10 +236,24 @@ bool deserializeFromBinaryFile(const std::string& filename, T& output, const std::string& name = "data") { std::ifstream in_archive_stream(filename.c_str()); if (!in_archive_stream.is_open()) return false; - deserializeBinary(in_archive_stream, output, name); + deserializeFromBinaryStream(in_archive_stream, output, name); in_archive_stream.close(); return true; } + +/// serializes to a string in binary +template +std::string serializeBinary(const T& input, + const std::string& name = "data") { + return serializeToBinaryString(input, name); +} + +/// deserializes from a string in binary +template +void deserializeBinary(const std::string& serialized, T& output, + const std::string& name = "data") { + deserializeFromBinaryString(serialized, output, name); +} ///@} } // namespace gtsam From 6dbd7c243abc91489c010261bde27685c491acac Mon Sep 17 00:00:00 2001 From: Fan Jiang Date: Wed, 24 Jun 2020 16:25:46 -0400 Subject: [PATCH 23/29] Add comments --- gtsam/base/make_shared.h | 14 +++++++++++++- gtsam/base/types.h | 12 +++++++++++- 2 files changed, 24 insertions(+), 2 deletions(-) diff --git a/gtsam/base/make_shared.h b/gtsam/base/make_shared.h index c7d98cdee..5281eec6d 100644 --- a/gtsam/base/make_shared.h +++ b/gtsam/base/make_shared.h @@ -26,16 +26,28 @@ #include namespace gtsam { + /// An shorthand alias for accessing the ::type inside std::enable_if that can be used in a template directly template using enable_if_t = typename std::enable_if::type; } namespace gtsam { - /** Add our own `make_shared` as a layer of wrapping on `boost::make_shared` + /** + * Add our own `make_shared` as a layer of wrapping on `boost::make_shared` * This solves the problem with the stock `make_shared` that custom alignment is not respected, causing SEGFAULTs * at runtime, which is notoriously hard to debug. * + * Explanation + * =============== + * The template `needs_eigen_aligned_allocator::value` will evaluate to `std::true_type` if the type alias + * `_eigen_aligned_allocator_trait = void` is present in a class, which is automatically added by the + * `GTSAM_MAKE_ALIGNED_OPERATOR_NEW` macro. + * + * This function declaration will only be taken when the above condition is true, so if some object does not need to + * be aligned, `gtsam::make_shared` will fall back to the next definition, which is a simple wrapper for + * `boost::make_shared`. + * * @tparam T The type of object being constructed * @tparam Args Type of the arguments of the constructor * @param args Arguments of the constructor diff --git a/gtsam/base/types.h b/gtsam/base/types.h index a4b2fb6ea..b54cc2f2a 100644 --- a/gtsam/base/types.h +++ b/gtsam/base/types.h @@ -238,8 +238,18 @@ namespace gtsam { /** * A SFINAE trait to mark classes that need special alignment. + * * This is required to make boost::make_shared and etc respect alignment, which is essential for the Python * wrappers to work properly. + * + * Explanation + * ============= + * When a GTSAM type is not declared with the type alias `_eigen_aligned_allocator_trait = void`, the first template + * will be taken so `needs_eigen_aligned_allocator` will be resolved to `std::false_type`. + * + * Otherwise, it will resolve to the second template, which will be resolved to `std::true_type`. + * + * Please refer to `gtsam/base/make_shared.h` for an example. */ template> struct needs_eigen_aligned_allocator : std::false_type { @@ -253,7 +263,7 @@ namespace gtsam { /** * This marks a GTSAM object to require alignment. With this macro an object will automatically be allocated in aligned * memory when one uses `gtsam::make_shared`. It reduces future misalignment problems that is hard to debug. - * See https://eigen.tuxfamily.org/dox/group__DenseMatrixManipulation__Alignement.html for details + * See https://eigen.tuxfamily.org/dox/group__DenseMatrixManipulation__Alignement.html for detailed explanation. */ #define GTSAM_MAKE_ALIGNED_OPERATOR_NEW \ EIGEN_MAKE_ALIGNED_OPERATOR_NEW \ From fb21c553a05555ce4be3de305836d62fa1113bbe Mon Sep 17 00:00:00 2001 From: Fan Jiang Date: Wed, 24 Jun 2020 17:15:00 -0400 Subject: [PATCH 24/29] Switch to the new alignment marker type --- gtsam/base/GenericValue.h | 2 +- gtsam/base/Manifold.h | 2 +- gtsam/base/types.h | 9 +++++++++ gtsam/geometry/BearingRange.h | 2 +- gtsam/geometry/CameraSet.h | 2 +- gtsam/geometry/EssentialMatrix.h | 2 +- gtsam/geometry/PinholeCamera.h | 2 +- gtsam/geometry/PinholePose.h | 4 ++-- gtsam/geometry/Pose2.h | 2 +- gtsam/geometry/Pose3.h | 2 +- gtsam/geometry/Rot3.h | 2 +- gtsam/geometry/SOn.h | 2 +- gtsam/geometry/Unit3.h | 2 +- gtsam/geometry/triangulation.h | 2 +- gtsam/navigation/AttitudeFactor.h | 4 ++-- gtsam/navigation/CombinedImuFactor.h | 6 +++--- gtsam/navigation/ImuBias.h | 2 +- gtsam/navigation/PreintegratedRotation.h | 4 ++-- gtsam/navigation/PreintegrationBase.h | 2 +- gtsam/navigation/PreintegrationParams.h | 2 +- gtsam/navigation/TangentPreintegration.h | 2 +- gtsam/nonlinear/ExpressionFactor.h | 2 +- gtsam/nonlinear/NonlinearEquality.h | 6 +++--- gtsam/nonlinear/PriorFactor.h | 2 +- gtsam/nonlinear/internal/ExpressionNode.h | 2 +- gtsam/slam/BetweenFactor.h | 2 +- gtsam/slam/EssentialMatrixConstraint.h | 2 +- gtsam/slam/EssentialMatrixFactor.h | 6 +++--- gtsam/slam/ProjectionFactor.h | 2 +- gtsam/slam/RotateFactor.h | 2 +- gtsam/slam/SmartFactorBase.h | 2 +- 31 files changed, 48 insertions(+), 39 deletions(-) diff --git a/gtsam/base/GenericValue.h b/gtsam/base/GenericValue.h index e1cb3bc2c..2ac3eb80c 100644 --- a/gtsam/base/GenericValue.h +++ b/gtsam/base/GenericValue.h @@ -181,7 +181,7 @@ public: // Alignment, see https://eigen.tuxfamily.org/dox/group__TopicStructHavingEigenMembers.html enum { NeedsToAlign = (sizeof(T) % 16) == 0 }; public: - EIGEN_MAKE_ALIGNED_OPERATOR_NEW_IF(NeedsToAlign) + GTSAM_MAKE_ALIGNED_OPERATOR_NEW_IF(NeedsToAlign) }; /// use this macro instead of BOOST_CLASS_EXPORT for GenericValues diff --git a/gtsam/base/Manifold.h b/gtsam/base/Manifold.h index f3653f099..9feb2b451 100644 --- a/gtsam/base/Manifold.h +++ b/gtsam/base/Manifold.h @@ -214,7 +214,7 @@ public: enum { NeedsToAlign = (sizeof(M1) % 16) == 0 || (sizeof(M2) % 16) == 0 }; public: - EIGEN_MAKE_ALIGNED_OPERATOR_NEW_IF(NeedsToAlign) + GTSAM_MAKE_ALIGNED_OPERATOR_NEW_IF(NeedsToAlign) }; // Define any direct product group to be a model of the multiplicative Group concept diff --git a/gtsam/base/types.h b/gtsam/base/types.h index b54cc2f2a..924f339b3 100644 --- a/gtsam/base/types.h +++ b/gtsam/base/types.h @@ -268,3 +268,12 @@ namespace gtsam { #define GTSAM_MAKE_ALIGNED_OPERATOR_NEW \ EIGEN_MAKE_ALIGNED_OPERATOR_NEW \ using _eigen_aligned_allocator_trait = void; + +/** + * This marks a GTSAM object to require alignment. With this macro an object will automatically be allocated in aligned + * memory when one uses `gtsam::make_shared`. It reduces future misalignment problems that is hard to debug. + * See https://eigen.tuxfamily.org/dox/group__DenseMatrixManipulation__Alignement.html for detailed explanation. + */ +#define GTSAM_MAKE_ALIGNED_OPERATOR_NEW_IF(NeedsToAlign) \ + EIGEN_MAKE_ALIGNED_OPERATOR_NEW_IF(NeedsToAlign) \ + using _eigen_aligned_allocator_trait = void; \ No newline at end of file diff --git a/gtsam/geometry/BearingRange.h b/gtsam/geometry/BearingRange.h index 7c73f3cbd..8db7abffe 100644 --- a/gtsam/geometry/BearingRange.h +++ b/gtsam/geometry/BearingRange.h @@ -162,7 +162,7 @@ private: NeedsToAlign = (sizeof(B) % 16) == 0 || (sizeof(R) % 16) == 0 }; public: - EIGEN_MAKE_ALIGNED_OPERATOR_NEW_IF(NeedsToAlign) + GTSAM_MAKE_ALIGNED_OPERATOR_NEW_IF(NeedsToAlign) }; // Declare this to be both Testable and a Manifold diff --git a/gtsam/geometry/CameraSet.h b/gtsam/geometry/CameraSet.h index ecf9a572d..feab8e0fa 100644 --- a/gtsam/geometry/CameraSet.h +++ b/gtsam/geometry/CameraSet.h @@ -319,7 +319,7 @@ private: } public: - EIGEN_MAKE_ALIGNED_OPERATOR_NEW + GTSAM_MAKE_ALIGNED_OPERATOR_NEW }; template diff --git a/gtsam/geometry/EssentialMatrix.h b/gtsam/geometry/EssentialMatrix.h index 3235fdedd..ca719eb37 100644 --- a/gtsam/geometry/EssentialMatrix.h +++ b/gtsam/geometry/EssentialMatrix.h @@ -212,7 +212,7 @@ class EssentialMatrix { /// @} public: - EIGEN_MAKE_ALIGNED_OPERATOR_NEW + GTSAM_MAKE_ALIGNED_OPERATOR_NEW }; template<> diff --git a/gtsam/geometry/PinholeCamera.h b/gtsam/geometry/PinholeCamera.h index c52127a45..9a80b937b 100644 --- a/gtsam/geometry/PinholeCamera.h +++ b/gtsam/geometry/PinholeCamera.h @@ -325,7 +325,7 @@ private: } public: - EIGEN_MAKE_ALIGNED_OPERATOR_NEW + GTSAM_MAKE_ALIGNED_OPERATOR_NEW }; // manifold traits diff --git a/gtsam/geometry/PinholePose.h b/gtsam/geometry/PinholePose.h index 935962423..60088577c 100644 --- a/gtsam/geometry/PinholePose.h +++ b/gtsam/geometry/PinholePose.h @@ -222,7 +222,7 @@ private: } public: - EIGEN_MAKE_ALIGNED_OPERATOR_NEW + GTSAM_MAKE_ALIGNED_OPERATOR_NEW }; // end of class PinholeBaseK @@ -425,7 +425,7 @@ private: } public: - EIGEN_MAKE_ALIGNED_OPERATOR_NEW + GTSAM_MAKE_ALIGNED_OPERATOR_NEW }; // end of class PinholePose diff --git a/gtsam/geometry/Pose2.h b/gtsam/geometry/Pose2.h index 388318827..2a1f108ca 100644 --- a/gtsam/geometry/Pose2.h +++ b/gtsam/geometry/Pose2.h @@ -317,7 +317,7 @@ public: public: // Align for Point2, which is either derived from, or is typedef, of Vector2 - EIGEN_MAKE_ALIGNED_OPERATOR_NEW + GTSAM_MAKE_ALIGNED_OPERATOR_NEW }; // Pose2 /** specialization for pose2 wedge function (generic template in Lie.h) */ diff --git a/gtsam/geometry/Pose3.h b/gtsam/geometry/Pose3.h index fa55f98de..ced3b904b 100644 --- a/gtsam/geometry/Pose3.h +++ b/gtsam/geometry/Pose3.h @@ -355,7 +355,7 @@ public: #ifdef GTSAM_USE_QUATERNIONS // Align if we are using Quaternions public: - EIGEN_MAKE_ALIGNED_OPERATOR_NEW + GTSAM_MAKE_ALIGNED_OPERATOR_NEW #endif }; // Pose3 class diff --git a/gtsam/geometry/Rot3.h b/gtsam/geometry/Rot3.h index fc3a8b3f2..8f24f07c8 100644 --- a/gtsam/geometry/Rot3.h +++ b/gtsam/geometry/Rot3.h @@ -544,7 +544,7 @@ namespace gtsam { #ifdef GTSAM_USE_QUATERNIONS // only align if quaternion, Matrix3 has no alignment requirements public: - EIGEN_MAKE_ALIGNED_OPERATOR_NEW + GTSAM_MAKE_ALIGNED_OPERATOR_NEW #endif }; diff --git a/gtsam/geometry/SOn.h b/gtsam/geometry/SOn.h index 767b12020..a08f87783 100644 --- a/gtsam/geometry/SOn.h +++ b/gtsam/geometry/SOn.h @@ -54,7 +54,7 @@ class SO : public LieGroup, internal::DimensionSO(N)> { using VectorN2 = Eigen::Matrix; using MatrixDD = Eigen::Matrix; - GTSAM_MAKE_ALIGNED_OPERATOR_NEW + GTSAM_MAKE_ALIGNED_OPERATOR_NEW_IF(true) protected: MatrixNN matrix_; ///< Rotation matrix diff --git a/gtsam/geometry/Unit3.h b/gtsam/geometry/Unit3.h index f1a9c1a69..b80e6e4d8 100644 --- a/gtsam/geometry/Unit3.h +++ b/gtsam/geometry/Unit3.h @@ -214,7 +214,7 @@ private: /// @} public: - EIGEN_MAKE_ALIGNED_OPERATOR_NEW + GTSAM_MAKE_ALIGNED_OPERATOR_NEW }; // Define GTSAM traits diff --git a/gtsam/geometry/triangulation.h b/gtsam/geometry/triangulation.h index 586b7b165..8cdf0fdc0 100644 --- a/gtsam/geometry/triangulation.h +++ b/gtsam/geometry/triangulation.h @@ -215,7 +215,7 @@ struct CameraProjectionMatrix { private: const Matrix3 K_; public: - EIGEN_MAKE_ALIGNED_OPERATOR_NEW + GTSAM_MAKE_ALIGNED_OPERATOR_NEW }; /** diff --git a/gtsam/navigation/AttitudeFactor.h b/gtsam/navigation/AttitudeFactor.h index db588008e..5a0031caf 100644 --- a/gtsam/navigation/AttitudeFactor.h +++ b/gtsam/navigation/AttitudeFactor.h @@ -139,7 +139,7 @@ private: } public: - EIGEN_MAKE_ALIGNED_OPERATOR_NEW + GTSAM_MAKE_ALIGNED_OPERATOR_NEW }; /// traits @@ -219,7 +219,7 @@ private: } public: - EIGEN_MAKE_ALIGNED_OPERATOR_NEW + GTSAM_MAKE_ALIGNED_OPERATOR_NEW }; /// traits diff --git a/gtsam/navigation/CombinedImuFactor.h b/gtsam/navigation/CombinedImuFactor.h index ca9b2ca1a..6b3bf979a 100644 --- a/gtsam/navigation/CombinedImuFactor.h +++ b/gtsam/navigation/CombinedImuFactor.h @@ -100,7 +100,7 @@ private: } public: - EIGEN_MAKE_ALIGNED_OPERATOR_NEW + GTSAM_MAKE_ALIGNED_OPERATOR_NEW }; @@ -210,7 +210,7 @@ public: } public: - EIGEN_MAKE_ALIGNED_OPERATOR_NEW + GTSAM_MAKE_ALIGNED_OPERATOR_NEW }; /** @@ -332,7 +332,7 @@ private: } public: - EIGEN_MAKE_ALIGNED_OPERATOR_NEW + GTSAM_MAKE_ALIGNED_OPERATOR_NEW }; // class CombinedImuFactor diff --git a/gtsam/navigation/ImuBias.h b/gtsam/navigation/ImuBias.h index ff1a53025..d52b4eb29 100644 --- a/gtsam/navigation/ImuBias.h +++ b/gtsam/navigation/ImuBias.h @@ -171,7 +171,7 @@ private: public: - EIGEN_MAKE_ALIGNED_OPERATOR_NEW + GTSAM_MAKE_ALIGNED_OPERATOR_NEW /// @} }; // ConstantBias class diff --git a/gtsam/navigation/PreintegratedRotation.h b/gtsam/navigation/PreintegratedRotation.h index 71ef5d08f..12938a625 100644 --- a/gtsam/navigation/PreintegratedRotation.h +++ b/gtsam/navigation/PreintegratedRotation.h @@ -69,7 +69,7 @@ struct GTSAM_EXPORT PreintegratedRotationParams { #ifdef GTSAM_USE_QUATERNIONS // Align if we are using Quaternions public: - EIGEN_MAKE_ALIGNED_OPERATOR_NEW + GTSAM_MAKE_ALIGNED_OPERATOR_NEW #endif }; @@ -182,7 +182,7 @@ class GTSAM_EXPORT PreintegratedRotation { #ifdef GTSAM_USE_QUATERNIONS // Align if we are using Quaternions public: - EIGEN_MAKE_ALIGNED_OPERATOR_NEW + GTSAM_MAKE_ALIGNED_OPERATOR_NEW #endif }; diff --git a/gtsam/navigation/PreintegrationBase.h b/gtsam/navigation/PreintegrationBase.h index 9926d207a..eb30c1f13 100644 --- a/gtsam/navigation/PreintegrationBase.h +++ b/gtsam/navigation/PreintegrationBase.h @@ -214,7 +214,7 @@ class GTSAM_EXPORT PreintegrationBase { #endif public: - EIGEN_MAKE_ALIGNED_OPERATOR_NEW + GTSAM_MAKE_ALIGNED_OPERATOR_NEW }; } /// namespace gtsam diff --git a/gtsam/navigation/PreintegrationParams.h b/gtsam/navigation/PreintegrationParams.h index 962fef277..4bff625ca 100644 --- a/gtsam/navigation/PreintegrationParams.h +++ b/gtsam/navigation/PreintegrationParams.h @@ -84,7 +84,7 @@ protected: #ifdef GTSAM_USE_QUATERNIONS // Align if we are using Quaternions public: - EIGEN_MAKE_ALIGNED_OPERATOR_NEW + GTSAM_MAKE_ALIGNED_OPERATOR_NEW #endif }; diff --git a/gtsam/navigation/TangentPreintegration.h b/gtsam/navigation/TangentPreintegration.h index 11945e53a..edf76e562 100644 --- a/gtsam/navigation/TangentPreintegration.h +++ b/gtsam/navigation/TangentPreintegration.h @@ -141,7 +141,7 @@ private: } public: - EIGEN_MAKE_ALIGNED_OPERATOR_NEW + GTSAM_MAKE_ALIGNED_OPERATOR_NEW }; } /// namespace gtsam diff --git a/gtsam/nonlinear/ExpressionFactor.h b/gtsam/nonlinear/ExpressionFactor.h index 04d82fe9a..c42b2bdfc 100644 --- a/gtsam/nonlinear/ExpressionFactor.h +++ b/gtsam/nonlinear/ExpressionFactor.h @@ -209,7 +209,7 @@ private: // Alignment, see https://eigen.tuxfamily.org/dox/group__TopicStructHavingEigenMembers.html enum { NeedsToAlign = (sizeof(T) % 16) == 0 }; public: - EIGEN_MAKE_ALIGNED_OPERATOR_NEW_IF(NeedsToAlign) + GTSAM_MAKE_ALIGNED_OPERATOR_NEW_IF(NeedsToAlign) }; // ExpressionFactor diff --git a/gtsam/nonlinear/NonlinearEquality.h b/gtsam/nonlinear/NonlinearEquality.h index d4eb655c3..1bba57051 100644 --- a/gtsam/nonlinear/NonlinearEquality.h +++ b/gtsam/nonlinear/NonlinearEquality.h @@ -175,7 +175,7 @@ public: /// @} - EIGEN_MAKE_ALIGNED_OPERATOR_NEW + GTSAM_MAKE_ALIGNED_OPERATOR_NEW private: @@ -265,7 +265,7 @@ public: traits::Print(value_, "Value"); } - EIGEN_MAKE_ALIGNED_OPERATOR_NEW + GTSAM_MAKE_ALIGNED_OPERATOR_NEW private: @@ -331,7 +331,7 @@ public: return traits::Local(x1,x2); } - EIGEN_MAKE_ALIGNED_OPERATOR_NEW + GTSAM_MAKE_ALIGNED_OPERATOR_NEW private: diff --git a/gtsam/nonlinear/PriorFactor.h b/gtsam/nonlinear/PriorFactor.h index 8d8c67d5c..0afbaa588 100644 --- a/gtsam/nonlinear/PriorFactor.h +++ b/gtsam/nonlinear/PriorFactor.h @@ -114,7 +114,7 @@ namespace gtsam { // Alignment, see https://eigen.tuxfamily.org/dox/group__TopicStructHavingEigenMembers.html enum { NeedsToAlign = (sizeof(T) % 16) == 0 }; public: - EIGEN_MAKE_ALIGNED_OPERATOR_NEW_IF(NeedsToAlign) + GTSAM_MAKE_ALIGNED_OPERATOR_NEW_IF(NeedsToAlign) }; } /// namespace gtsam diff --git a/gtsam/nonlinear/internal/ExpressionNode.h b/gtsam/nonlinear/internal/ExpressionNode.h index 0011efb74..0ae37f130 100644 --- a/gtsam/nonlinear/internal/ExpressionNode.h +++ b/gtsam/nonlinear/internal/ExpressionNode.h @@ -150,7 +150,7 @@ public: return constant_; } - EIGEN_MAKE_ALIGNED_OPERATOR_NEW + GTSAM_MAKE_ALIGNED_OPERATOR_NEW }; //----------------------------------------------------------------------------- diff --git a/gtsam/slam/BetweenFactor.h b/gtsam/slam/BetweenFactor.h index 23138b9e6..b1d4904aa 100644 --- a/gtsam/slam/BetweenFactor.h +++ b/gtsam/slam/BetweenFactor.h @@ -126,7 +126,7 @@ namespace gtsam { // Alignment, see https://eigen.tuxfamily.org/dox/group__TopicStructHavingEigenMembers.html enum { NeedsToAlign = (sizeof(VALUE) % 16) == 0 }; public: - EIGEN_MAKE_ALIGNED_OPERATOR_NEW_IF(NeedsToAlign) + GTSAM_MAKE_ALIGNED_OPERATOR_NEW_IF(NeedsToAlign) }; // \class BetweenFactor /// traits diff --git a/gtsam/slam/EssentialMatrixConstraint.h b/gtsam/slam/EssentialMatrixConstraint.h index 179200fe1..e474ce5b3 100644 --- a/gtsam/slam/EssentialMatrixConstraint.h +++ b/gtsam/slam/EssentialMatrixConstraint.h @@ -105,7 +105,7 @@ private: } public: - EIGEN_MAKE_ALIGNED_OPERATOR_NEW + GTSAM_MAKE_ALIGNED_OPERATOR_NEW }; // \class EssentialMatrixConstraint diff --git a/gtsam/slam/EssentialMatrixFactor.h b/gtsam/slam/EssentialMatrixFactor.h index 8bd155a14..c214a2f48 100644 --- a/gtsam/slam/EssentialMatrixFactor.h +++ b/gtsam/slam/EssentialMatrixFactor.h @@ -81,7 +81,7 @@ public: } public: - EIGEN_MAKE_ALIGNED_OPERATOR_NEW + GTSAM_MAKE_ALIGNED_OPERATOR_NEW }; /** @@ -201,7 +201,7 @@ public: } public: - EIGEN_MAKE_ALIGNED_OPERATOR_NEW + GTSAM_MAKE_ALIGNED_OPERATOR_NEW }; // EssentialMatrixFactor2 @@ -286,7 +286,7 @@ public: } public: - EIGEN_MAKE_ALIGNED_OPERATOR_NEW + GTSAM_MAKE_ALIGNED_OPERATOR_NEW }; // EssentialMatrixFactor3 diff --git a/gtsam/slam/ProjectionFactor.h b/gtsam/slam/ProjectionFactor.h index 856913aae..0bed15fdc 100644 --- a/gtsam/slam/ProjectionFactor.h +++ b/gtsam/slam/ProjectionFactor.h @@ -189,7 +189,7 @@ namespace gtsam { } public: - EIGEN_MAKE_ALIGNED_OPERATOR_NEW + GTSAM_MAKE_ALIGNED_OPERATOR_NEW }; /// traits diff --git a/gtsam/slam/RotateFactor.h b/gtsam/slam/RotateFactor.h index b6ccc36a2..948fffe13 100644 --- a/gtsam/slam/RotateFactor.h +++ b/gtsam/slam/RotateFactor.h @@ -113,7 +113,7 @@ public: return error; } - EIGEN_MAKE_ALIGNED_OPERATOR_NEW + GTSAM_MAKE_ALIGNED_OPERATOR_NEW }; } // namespace gtsam diff --git a/gtsam/slam/SmartFactorBase.h b/gtsam/slam/SmartFactorBase.h index 34f9b9e9f..717a9c1f2 100644 --- a/gtsam/slam/SmartFactorBase.h +++ b/gtsam/slam/SmartFactorBase.h @@ -81,7 +81,7 @@ protected: mutable FBlocks Fs; public: - EIGEN_MAKE_ALIGNED_OPERATOR_NEW + GTSAM_MAKE_ALIGNED_OPERATOR_NEW /// shorthand for a smart pointer to a factor typedef boost::shared_ptr shared_ptr; From a4ef531a32b6fa078a24cd30ef17cbdb9580688e Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Wed, 24 Jun 2020 19:23:37 -0500 Subject: [PATCH 25/29] print Eigen Unsupported status message correctly --- gtsam/3rdparty/CMakeLists.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/gtsam/3rdparty/CMakeLists.txt b/gtsam/3rdparty/CMakeLists.txt index 89149d964..c8fecc339 100644 --- a/gtsam/3rdparty/CMakeLists.txt +++ b/gtsam/3rdparty/CMakeLists.txt @@ -17,7 +17,7 @@ if(NOT GTSAM_USE_SYSTEM_EIGEN) endforeach(eigen_dir) if(GTSAM_WITH_EIGEN_UNSUPPORTED) - message("-- Installing Eigen Unsupported modules") + message(STATUS "Installing Eigen Unsupported modules") # do the same for the unsupported eigen folder file(GLOB_RECURSE unsupported_eigen_headers "${CMAKE_CURRENT_SOURCE_DIR}/Eigen/unsupported/Eigen/*.h") From 7f1384b0f26e89136237e538779c6f6b0972c6b4 Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Wed, 24 Jun 2020 19:25:56 -0500 Subject: [PATCH 26/29] wrap the biasHat function for PreintegratedMeasurement --- gtsam.h | 2 ++ 1 file changed, 2 insertions(+) diff --git a/gtsam.h b/gtsam.h index 614db91c7..bf4d7f4d1 100644 --- a/gtsam.h +++ b/gtsam.h @@ -2955,6 +2955,7 @@ class PreintegratedImuMeasurements { gtsam::Rot3 deltaRij() const; Vector deltaPij() const; Vector deltaVij() const; + gtsam::imuBias::ConstantBias biasHat() const; Vector biasHatVector() const; gtsam::NavState predict(const gtsam::NavState& state_i, const gtsam::imuBias::ConstantBias& bias) const; @@ -3016,6 +3017,7 @@ class PreintegratedCombinedMeasurements { gtsam::Rot3 deltaRij() const; Vector deltaPij() const; Vector deltaVij() const; + gtsam::imuBias::ConstantBias biasHat() const; Vector biasHatVector() const; gtsam::NavState predict(const gtsam::NavState& state_i, const gtsam::imuBias::ConstantBias& bias) const; From 350808d9dc7b6e2e31814e6b59ede8d59c9dfe8b Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Wed, 24 Jun 2020 19:27:45 -0500 Subject: [PATCH 27/29] added .gitignore for when building the sample cmake projects --- cmake/.gitignore | 1 + 1 file changed, 1 insertion(+) create mode 100644 cmake/.gitignore diff --git a/cmake/.gitignore b/cmake/.gitignore new file mode 100644 index 000000000..6f467448b --- /dev/null +++ b/cmake/.gitignore @@ -0,0 +1 @@ +**/build \ No newline at end of file From 17568e67793ad831b02ec701ef6734bbfe950f68 Mon Sep 17 00:00:00 2001 From: Fan Jiang Date: Thu, 25 Jun 2020 00:14:21 -0400 Subject: [PATCH 28/29] Add missing lf --- gtsam/base/types.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/gtsam/base/types.h b/gtsam/base/types.h index 924f339b3..c5dac9ab7 100644 --- a/gtsam/base/types.h +++ b/gtsam/base/types.h @@ -276,4 +276,4 @@ namespace gtsam { */ #define GTSAM_MAKE_ALIGNED_OPERATOR_NEW_IF(NeedsToAlign) \ EIGEN_MAKE_ALIGNED_OPERATOR_NEW_IF(NeedsToAlign) \ - using _eigen_aligned_allocator_trait = void; \ No newline at end of file + using _eigen_aligned_allocator_trait = void; From c8583e921a2c370d244b7cf04e8f1a56a44d7f50 Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Thu, 25 Jun 2020 10:28:59 -0500 Subject: [PATCH 29/29] Revert "added .gitignore for when building the sample cmake projects" This reverts commit 350808d9dc7b6e2e31814e6b59ede8d59c9dfe8b. --- cmake/.gitignore | 1 - 1 file changed, 1 deletion(-) delete mode 100644 cmake/.gitignore diff --git a/cmake/.gitignore b/cmake/.gitignore deleted file mode 100644 index 6f467448b..000000000 --- a/cmake/.gitignore +++ /dev/null @@ -1 +0,0 @@ -**/build \ No newline at end of file