From 04c12c364fbf93ce5264b4f78049a8590e6d8cdf Mon Sep 17 00:00:00 2001 From: John Lambert Date: Thu, 1 Oct 2020 23:40:54 -0400 Subject: [PATCH 01/44] add --- python/gtsam/examples/SFMExample_bal.py | 117 ++++++++++++++++++++++++ 1 file changed, 117 insertions(+) create mode 100644 python/gtsam/examples/SFMExample_bal.py diff --git a/python/gtsam/examples/SFMExample_bal.py b/python/gtsam/examples/SFMExample_bal.py new file mode 100644 index 000000000..8efc8ec19 --- /dev/null +++ b/python/gtsam/examples/SFMExample_bal.py @@ -0,0 +1,117 @@ +""" + GTSAM Copyright 2010, 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 + + Solve a structure-from-motion problem from a "Bundle Adjustment in the Large" file + Author: John Lambert +""" + +import argparse +import logging + +import matplotlib.pyplot as plt +import numpy as np + +import gtsam +from gtsam import ( + PinholeCameraCal3Bundler, + readBal, + symbol_shorthand +) + +C = symbol_shorthand.C +P = symbol_shorthand.P + +import pdb + +#include + +# We will be using a projection factor that ties a SFM_Camera to a 3D point. +# An SFM_Camera is defined in datase.h as a camera with unknown Cal3Bundler calibration +# and has a total of 9 free parameters +#typedef GeneralSFMFactor MyFactor; + +PinholeCameraCal3Bundler +def run(args): + """ Run LM optimization with BAL input data and report resulting error """ + # Find default file, but if an argument is given, try loading a file + if args.input_file: + input_file = args.input_file + else: + input_file = gtsam.findExampleDataFile("dubrovnik-3-7-pre") + + pdb.set_trace() + # # Load the SfM data from file + mydata = readBal(input_file) + logging.info(f"read {mydata.number_tracks()} tracks on {mydata.number_cameras()} cameras\n") + + # # Create a factor graph + graph = gtsam.NonlinearFactorGraph() + + # # We share *one* noiseModel between all projection factors + noise = gtsam.noiseModel.Isotropic.Sigma(2, 1.0) # one pixel in u and v + + # Add measurements to the factor graph + j = 0 + pdb.set_trace() + for t_idx in range(mydata.number_tracks()): + track = mydata.track(t_idx) # SfmTrack + # retrieve the SfmMeasurement objects + for m_idx in range(track.number_measurements()): + # i represents the camera index, and uv is the 2d measurement + i, uv = track.measurement(m_idx) + #graph.emplace_shared(uv, noise, C(i), P(j)) # note use of shorthand symbols C and P + #graph.add + j += 1 + pdb.set_trace() + + # # Add a prior on pose x1. This indirectly specifies where the origin is. + # # and a prior on the position of the first landmark to fix the scale + graph.push_back(gtsam.PriorFactorVector( + C(0), mydata.camera(0), gtsam.noiseModel.Isotropic.Sigma(9, 0.1))) + graph.push_back(gtsam.PriorFactorVector( + P(0), mydata.track(0).point3(), gtsam.noiseModel.Isotropic.Sigma(3, 0.1))) + + # # Create initial estimate + initial = gtsam.Values() + + i = 0 + # add each SfmCamera + for cam_idx in range(mydata.number_cameras()): + camera = mydata.camera(cam_idx) + initial.insert(C(i), camera) + i += 1 + + j = 0 + # add each SfmTrack + for t_idx in range(mydata.number_tracks()): + track = mydata.track(t_idx) + initial.insert(P(j), track.point3()) + j += 1 + + # Optimize the graph and print results + try: + params = gtsam.LevenbergMarquardtParams() + params.setVerbosityLM("ERROR") + lm = gtsam.LevenbergMarquardtOptimizer(graph, initial, params) + result = lm.optimize() + except Exception as e: + logging.exception("LM Optimization failed") + return + + logging.info(f"final error: {graph.error(result)}") + + +if __name__ == "__main__": + parser = argparse.ArgumentParser() + parser.add_argument('-i', '--input_file', type=str, default="", + help='Read SFM data from the specified BAL file') + run(parser.parse_args()) + + + + From 06ac62724927abc947aec6e87017f8b2bd5df39a Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Sun, 4 Oct 2020 19:55:08 -0400 Subject: [PATCH 02/44] added normalize function to orthogonalize the rotation after composition --- gtsam/geometry/Rot3.h | 7 +++++++ gtsam/geometry/Rot3M.cpp | 28 +++++++++++++++++++++++++++- gtsam/geometry/Rot3Q.cpp | 6 +++++- gtsam/geometry/tests/testRot3.cpp | 20 ++++++++++++++++++++ 4 files changed, 59 insertions(+), 2 deletions(-) diff --git a/gtsam/geometry/Rot3.h b/gtsam/geometry/Rot3.h index de9d2b420..db5367c8f 100644 --- a/gtsam/geometry/Rot3.h +++ b/gtsam/geometry/Rot3.h @@ -430,6 +430,13 @@ namespace gtsam { */ Matrix3 transpose() const; + /** + * Normalize rotation so that its determinant is 1. + * This means either re-orthogonalizing the Matrix representation or + * normalizing the quaternion representation. + */ + Rot3 normalize(const Rot3& R) const; + /// @deprecated, this is base 1, and was just confusing Point3 column(int index) const; diff --git a/gtsam/geometry/Rot3M.cpp b/gtsam/geometry/Rot3M.cpp index 500941a16..ffc468dfc 100644 --- a/gtsam/geometry/Rot3M.cpp +++ b/gtsam/geometry/Rot3M.cpp @@ -108,9 +108,35 @@ Rot3 Rot3::RzRyRx(double x, double y, double z, OptionalJacobian<3, 1> Hx, ); } +/* ************************************************************************* */ +Rot3 Rot3::normalize(const Rot3& R) const { + /// Implementation from here: https://stackoverflow.com/a/23082112/1236990 + /// Theory: https://drive.google.com/file/d/0B9rLLz1XQKmaZTlQdV81QjNoZTA/view + + /// Essentially, this computes the orthogonalization error, distributes the + /// error to the x and y rows, and then performs a Taylor expansion to + /// orthogonalize. + + Matrix3 rot = R.matrix(), rot_new; + + if (std::fabs(rot.determinant()-1) < 1e-12) return R; + + Vector3 x = rot.block<1, 3>(0, 0), y = rot.block<1, 3>(1, 0); + double error = x.dot(y); + + Vector3 x_ort = x - (error / 2) * y, y_ort = y - (error / 2) * x; + Vector3 z_ort = x_ort.cross(y_ort); + + rot_new.block<1, 3>(0, 0) = 0.5 * (3 - x_ort.dot(x_ort)) * x_ort; + rot_new.block<1, 3>(1, 0) = 0.5 * (3 - y_ort.dot(y_ort)) * y_ort; + rot_new.block<1, 3>(2, 0) = 0.5 * (3 - z_ort.dot(z_ort)) * z_ort; + + return Rot3(rot_new); +} + /* ************************************************************************* */ Rot3 Rot3::operator*(const Rot3& R2) const { - return Rot3(rot_*R2.rot_); + return normalize(Rot3(rot_*R2.rot_)); } /* ************************************************************************* */ diff --git a/gtsam/geometry/Rot3Q.cpp b/gtsam/geometry/Rot3Q.cpp index 6e1871c64..d4400b0dc 100644 --- a/gtsam/geometry/Rot3Q.cpp +++ b/gtsam/geometry/Rot3Q.cpp @@ -86,9 +86,13 @@ namespace gtsam { gtsam::Quaternion(Eigen::AngleAxisd(x, Eigen::Vector3d::UnitX()))); } + /* ************************************************************************* */ + Rot3 Rot3::normalize(const Rot3& R) const { + return Rot3(R.quaternion_.normalized()); + } /* ************************************************************************* */ Rot3 Rot3::operator*(const Rot3& R2) const { - return Rot3(quaternion_ * R2.quaternion_); + return normalize(Rot3(quaternion_ * R2.quaternion_)); } /* ************************************************************************* */ diff --git a/gtsam/geometry/tests/testRot3.cpp b/gtsam/geometry/tests/testRot3.cpp index a7c6f5a77..e86029026 100644 --- a/gtsam/geometry/tests/testRot3.cpp +++ b/gtsam/geometry/tests/testRot3.cpp @@ -910,6 +910,26 @@ TEST(Rot3, yaw_derivative) { CHECK(assert_equal(num, calc)); } +/* ************************************************************************* */ +TEST(Rot3, determinant) { + size_t degree = 1; + Rot3 R_w0; // Zero rotation + Rot3 R_w1 = Rot3::Ry(degree * M_PI / 180); + + Rot3 R_01, R_w2; + double actual, expected = 1.0; + + for (size_t i = 2; i < 360; ++i) { + R_01 = R_w0.between(R_w1); + R_w2 = R_w1 * R_01; + R_w0 = R_w1; + R_w1 = R_w2; + actual = R_w2.matrix().determinant(); + + EXPECT_DOUBLES_EQUAL(expected, actual, 1e-7); + } +} + /* ************************************************************************* */ int main() { TestResult tr; From 2e1cc3ca3517eca5431a07405453f776b28c9aeb Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Mon, 5 Oct 2020 13:25:30 -0400 Subject: [PATCH 03/44] normalized needs to be called explicitly --- gtsam/geometry/Rot3.h | 2 +- gtsam/geometry/Rot3M.cpp | 18 ++++++++++-------- gtsam/geometry/Rot3Q.cpp | 6 +++--- gtsam/geometry/tests/testRot3.cpp | 2 +- 4 files changed, 15 insertions(+), 13 deletions(-) diff --git a/gtsam/geometry/Rot3.h b/gtsam/geometry/Rot3.h index db5367c8f..b1e46308d 100644 --- a/gtsam/geometry/Rot3.h +++ b/gtsam/geometry/Rot3.h @@ -435,7 +435,7 @@ namespace gtsam { * This means either re-orthogonalizing the Matrix representation or * normalizing the quaternion representation. */ - Rot3 normalize(const Rot3& R) const; + Rot3 normalized() const; /// @deprecated, this is base 1, and was just confusing Point3 column(int index) const; diff --git a/gtsam/geometry/Rot3M.cpp b/gtsam/geometry/Rot3M.cpp index ffc468dfc..c372d403b 100644 --- a/gtsam/geometry/Rot3M.cpp +++ b/gtsam/geometry/Rot3M.cpp @@ -109,7 +109,7 @@ Rot3 Rot3::RzRyRx(double x, double y, double z, OptionalJacobian<3, 1> Hx, } /* ************************************************************************* */ -Rot3 Rot3::normalize(const Rot3& R) const { +Rot3 Rot3::normalized() const { /// Implementation from here: https://stackoverflow.com/a/23082112/1236990 /// Theory: https://drive.google.com/file/d/0B9rLLz1XQKmaZTlQdV81QjNoZTA/view @@ -117,9 +117,11 @@ Rot3 Rot3::normalize(const Rot3& R) const { /// error to the x and y rows, and then performs a Taylor expansion to /// orthogonalize. - Matrix3 rot = R.matrix(), rot_new; + Matrix3 rot = rot_.matrix(), rot_orth; - if (std::fabs(rot.determinant()-1) < 1e-12) return R; + // Check if determinant is already 1. + // If yes, then return the current Rot3. + if (std::fabs(rot.determinant()-1) < 1e-12) return Rot3(rot_); Vector3 x = rot.block<1, 3>(0, 0), y = rot.block<1, 3>(1, 0); double error = x.dot(y); @@ -127,16 +129,16 @@ Rot3 Rot3::normalize(const Rot3& R) const { Vector3 x_ort = x - (error / 2) * y, y_ort = y - (error / 2) * x; Vector3 z_ort = x_ort.cross(y_ort); - rot_new.block<1, 3>(0, 0) = 0.5 * (3 - x_ort.dot(x_ort)) * x_ort; - rot_new.block<1, 3>(1, 0) = 0.5 * (3 - y_ort.dot(y_ort)) * y_ort; - rot_new.block<1, 3>(2, 0) = 0.5 * (3 - z_ort.dot(z_ort)) * z_ort; + rot_orth.block<1, 3>(0, 0) = 0.5 * (3 - x_ort.dot(x_ort)) * x_ort; + rot_orth.block<1, 3>(1, 0) = 0.5 * (3 - y_ort.dot(y_ort)) * y_ort; + rot_orth.block<1, 3>(2, 0) = 0.5 * (3 - z_ort.dot(z_ort)) * z_ort; - return Rot3(rot_new); + return Rot3(rot_orth); } /* ************************************************************************* */ Rot3 Rot3::operator*(const Rot3& R2) const { - return normalize(Rot3(rot_*R2.rot_)); + return Rot3(rot_*R2.rot_); } /* ************************************************************************* */ diff --git a/gtsam/geometry/Rot3Q.cpp b/gtsam/geometry/Rot3Q.cpp index d4400b0dc..523255d87 100644 --- a/gtsam/geometry/Rot3Q.cpp +++ b/gtsam/geometry/Rot3Q.cpp @@ -87,12 +87,12 @@ namespace gtsam { } /* ************************************************************************* */ - Rot3 Rot3::normalize(const Rot3& R) const { - return Rot3(R.quaternion_.normalized()); + Rot3 Rot3::normalized() const { + return Rot3(quaternion_.normalized()); } /* ************************************************************************* */ Rot3 Rot3::operator*(const Rot3& R2) const { - return normalize(Rot3(quaternion_ * R2.quaternion_)); + return Rot3(quaternion_ * R2.quaternion_); } /* ************************************************************************* */ diff --git a/gtsam/geometry/tests/testRot3.cpp b/gtsam/geometry/tests/testRot3.cpp index e86029026..7b792f8bd 100644 --- a/gtsam/geometry/tests/testRot3.cpp +++ b/gtsam/geometry/tests/testRot3.cpp @@ -923,7 +923,7 @@ TEST(Rot3, determinant) { R_01 = R_w0.between(R_w1); R_w2 = R_w1 * R_01; R_w0 = R_w1; - R_w1 = R_w2; + R_w1 = R_w2.normalized(); actual = R_w2.matrix().determinant(); EXPECT_DOUBLES_EQUAL(expected, actual, 1e-7); From 08636189fb57069ed0ec308b25a768f6cf0caf1d Mon Sep 17 00:00:00 2001 From: John Lambert Date: Mon, 5 Oct 2020 14:35:27 -0400 Subject: [PATCH 04/44] add WIP PR --- gtsam/gtsam.i | 5 ++++- python/gtsam/examples/SFMExample_bal.py | 26 ++++++++++++++----------- 2 files changed, 19 insertions(+), 12 deletions(-) diff --git a/gtsam/gtsam.i b/gtsam/gtsam.i index e5f323d72..1a239541d 100644 --- a/gtsam/gtsam.i +++ b/gtsam/gtsam.i @@ -1107,6 +1107,7 @@ typedef gtsam::PinholeCamera PinholeCameraCal3_S2; //typedef gtsam::PinholeCamera PinholeCameraCal3DS2; //typedef gtsam::PinholeCamera PinholeCameraCal3Unified; typedef gtsam::PinholeCamera PinholeCameraCal3Bundler; +//typedef gtsam::PinholeCamera SfmCamera; #include class StereoCamera { @@ -2528,7 +2529,7 @@ class NonlinearISAM { #include #include -template +template virtual class PriorFactor : gtsam::NoiseModelFactor { PriorFactor(size_t key, const T& prior, const gtsam::noiseModel::Base* noiseModel); T prior() const; @@ -2673,6 +2674,8 @@ virtual class GeneralSFMFactor : gtsam::NoiseModelFactor { typedef gtsam::GeneralSFMFactor GeneralSFMFactorCal3_S2; //TODO (Issue 237) due to lack of jacobians of Cal3DS2_Base::calibrate, GeneralSFMFactor does not apply to Cal3DS2 //typedef gtsam::GeneralSFMFactor GeneralSFMFactorCal3DS2; +//typedef gtsam::GeneralSFMFactor GeneralSFMFactorCal3Bundler; + template virtual class GeneralSFMFactor2 : gtsam::NoiseModelFactor { diff --git a/python/gtsam/examples/SFMExample_bal.py b/python/gtsam/examples/SFMExample_bal.py index 8efc8ec19..258ec8917 100644 --- a/python/gtsam/examples/SFMExample_bal.py +++ b/python/gtsam/examples/SFMExample_bal.py @@ -18,7 +18,9 @@ import numpy as np import gtsam from gtsam import ( + #GeneralSFMFactorCal3Bundler, PinholeCameraCal3Bundler, + PriorFactorSfmCamera, readBal, symbol_shorthand ) @@ -28,14 +30,10 @@ P = symbol_shorthand.P import pdb -#include - # We will be using a projection factor that ties a SFM_Camera to a 3D point. -# An SFM_Camera is defined in datase.h as a camera with unknown Cal3Bundler calibration +# An SFM_Camera is defined in dataset.h as a camera with unknown Cal3Bundler calibration # and has a total of 9 free parameters -#typedef GeneralSFMFactor MyFactor; -PinholeCameraCal3Bundler def run(args): """ Run LM optimization with BAL input data and report resulting error """ # Find default file, but if an argument is given, try loading a file @@ -64,17 +62,23 @@ def run(args): for m_idx in range(track.number_measurements()): # i represents the camera index, and uv is the 2d measurement i, uv = track.measurement(m_idx) - #graph.emplace_shared(uv, noise, C(i), P(j)) # note use of shorthand symbols C and P - #graph.add + # note use of shorthand symbols C and P + #graph.add(GeneralSFMFactorCal3Bundler(uv, noise, C(i), P(j))) j += 1 pdb.set_trace() # # Add a prior on pose x1. This indirectly specifies where the origin is. # # and a prior on the position of the first landmark to fix the scale - graph.push_back(gtsam.PriorFactorVector( - C(0), mydata.camera(0), gtsam.noiseModel.Isotropic.Sigma(9, 0.1))) - graph.push_back(gtsam.PriorFactorVector( - P(0), mydata.track(0).point3(), gtsam.noiseModel.Isotropic.Sigma(3, 0.1))) + graph.push_back( + gtsam.PriorFactorSfmCamera( + C(0), mydata.camera(0), gtsam.noiseModel.Isotropic.Sigma(9, 0.1) + ) + ) + graph.push_back( + gtsam.PriorFactorPoint3( + P(0), mydata.track(0).point3(), gtsam.noiseModel.Isotropic.Sigma(3, 0.1) + ) + ) # # Create initial estimate initial = gtsam.Values() From 5fb7229fa67fd14b671611dc5b8daf21f5179342 Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Mon, 5 Oct 2020 22:28:27 -0400 Subject: [PATCH 05/44] Moved normalize next to ClosestTo and add more docs --- gtsam/geometry/Rot3.h | 29 +++++++++++++++++++++-------- gtsam/geometry/Rot3M.cpp | 1 - 2 files changed, 21 insertions(+), 9 deletions(-) diff --git a/gtsam/geometry/Rot3.h b/gtsam/geometry/Rot3.h index b1e46308d..2334312f6 100644 --- a/gtsam/geometry/Rot3.h +++ b/gtsam/geometry/Rot3.h @@ -262,9 +262,29 @@ namespace gtsam { static Rot3 AlignTwoPairs(const Unit3& a_p, const Unit3& b_p, // const Unit3& a_q, const Unit3& b_q); - /// Static, named constructor that finds Rot3 element closest to M in Frobenius norm. + /** + * Static, named constructor that finds Rot3 element closest to M in Frobenius norm. + * + * Uses Full SVD to compute the orthogonal matrix, thus is highly accurate and robust. + * + * N. J. Higham. Matrix nearness problems and applications. + * In M. J. C. Gover and S. Barnett, editors, Applications of Matrix Theory, pages 1–27. + * Oxford University Press, 1989. + */ static Rot3 ClosestTo(const Matrix3& M) { return Rot3(SO3::ClosestTo(M)); } + /** + * Normalize rotation so that its determinant is 1. + * This means either re-orthogonalizing the Matrix representation or + * normalizing the quaternion representation. + * + * This method is akin to `ClosestTo` but uses a computationally cheaper + * algorithm. + * + * Ref: https://drive.google.com/file/d/0B9rLLz1XQKmaZTlQdV81QjNoZTA/view + */ + Rot3 normalized() const; + /// @} /// @name Testable /// @{ @@ -430,13 +450,6 @@ namespace gtsam { */ Matrix3 transpose() const; - /** - * Normalize rotation so that its determinant is 1. - * This means either re-orthogonalizing the Matrix representation or - * normalizing the quaternion representation. - */ - Rot3 normalized() const; - /// @deprecated, this is base 1, and was just confusing Point3 column(int index) const; diff --git a/gtsam/geometry/Rot3M.cpp b/gtsam/geometry/Rot3M.cpp index c372d403b..02e5b771f 100644 --- a/gtsam/geometry/Rot3M.cpp +++ b/gtsam/geometry/Rot3M.cpp @@ -111,7 +111,6 @@ Rot3 Rot3::RzRyRx(double x, double y, double z, OptionalJacobian<3, 1> Hx, /* ************************************************************************* */ Rot3 Rot3::normalized() const { /// Implementation from here: https://stackoverflow.com/a/23082112/1236990 - /// Theory: https://drive.google.com/file/d/0B9rLLz1XQKmaZTlQdV81QjNoZTA/view /// Essentially, this computes the orthogonalization error, distributes the /// error to the x and y rows, and then performs a Taylor expansion to From e9e87526c41699a544fb07ae0beedca87658643e Mon Sep 17 00:00:00 2001 From: Jose Luis Blanco Claraco Date: Tue, 6 Oct 2020 18:10:06 +0200 Subject: [PATCH 06/44] refactor cmake scripts into smaller files --- CMakeLists.txt | 551 +------------------------ cmake/GtsamBuildTypes.cmake | 14 + cmake/handle_allocators.cmake | 34 ++ cmake/handle_boost.cmake | 56 +++ cmake/handle_ccache.cmake | 14 + cmake/handle_cpack.cmake | 28 ++ cmake/handle_eigen.cmake | 75 ++++ cmake/handle_final_checks.cmake | 10 + cmake/handle_general_options.cmake | 46 +++ cmake/handle_global_build_flags.cmake | 52 +++ cmake/handle_mkl.cmake | 17 + cmake/handle_openmp.cmake | 11 + cmake/handle_perftools.cmake | 4 + cmake/handle_print_configuration.cmake | 104 +++++ cmake/handle_python.cmake | 26 ++ cmake/handle_tbb.cmake | 24 ++ cmake/handle_uninstall.cmake | 10 + matlab/CMakeLists.txt | 7 +- 18 files changed, 545 insertions(+), 538 deletions(-) create mode 100644 cmake/handle_allocators.cmake create mode 100644 cmake/handle_boost.cmake create mode 100644 cmake/handle_ccache.cmake create mode 100644 cmake/handle_cpack.cmake create mode 100644 cmake/handle_eigen.cmake create mode 100644 cmake/handle_final_checks.cmake create mode 100644 cmake/handle_general_options.cmake create mode 100644 cmake/handle_global_build_flags.cmake create mode 100644 cmake/handle_mkl.cmake create mode 100644 cmake/handle_openmp.cmake create mode 100644 cmake/handle_perftools.cmake create mode 100644 cmake/handle_print_configuration.cmake create mode 100644 cmake/handle_python.cmake create mode 100644 cmake/handle_tbb.cmake create mode 100644 cmake/handle_uninstall.cmake diff --git a/CMakeLists.txt b/CMakeLists.txt index 8b546ebc2..831ee00f3 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -22,17 +22,10 @@ set (CMAKE_PROJECT_VERSION_PATCH ${GTSAM_VERSION_PATCH}) ############################################################################### # Gather information, perform checks, set defaults -# Set the default install path to home -#set (CMAKE_INSTALL_PREFIX ${HOME} CACHE PATH "Install prefix for library") - set(CMAKE_MODULE_PATH "${CMAKE_MODULE_PATH}" "${CMAKE_CURRENT_SOURCE_DIR}/cmake") include(GtsamMakeConfigFile) include(GNUInstallDirs) -# Record the root dir for gtsam - needed during external builds, e.g., ROS -set(GTSAM_SOURCE_ROOT_DIR ${CMAKE_CURRENT_SOURCE_DIR}) -message(STATUS "GTSAM_SOURCE_ROOT_DIR: [${GTSAM_SOURCE_ROOT_DIR}]") - # Load build type flags and default to Debug mode include(GtsamBuildTypes) @@ -45,399 +38,21 @@ if(${CMAKE_SOURCE_DIR} STREQUAL ${CMAKE_BINARY_DIR}) message(FATAL_ERROR "In-source builds not allowed. Please make a new directory (called a build directory) and run CMake from there. You may need to remove CMakeCache.txt. ") endif() -# See whether gtsam_unstable is available (it will be present only if we're using a git checkout) -if(EXISTS "${PROJECT_SOURCE_DIR}/gtsam_unstable" AND IS_DIRECTORY "${PROJECT_SOURCE_DIR}/gtsam_unstable") - set(GTSAM_UNSTABLE_AVAILABLE 1) -else() - set(GTSAM_UNSTABLE_AVAILABLE 0) -endif() +include(cmake/handle_boost.cmake) # Boost +include(cmake/handle_ccache.cmake) # ccache +include(cmake/handle_cpack.cmake) # CPack +include(cmake/handle_eigen.cmake) # Eigen3 +include(cmake/handle_general_options.cmake) # CMake build options +include(cmake/handle_mkl.cmake) # MKL +include(cmake/handle_openmp.cmake) # OpenMP +include(cmake/handle_perftools.cmake) # Google perftools +include(cmake/handle_python.cmake) # Python options and commands +include(cmake/handle_tbb.cmake) # TBB +include(cmake/handle_uninstall.cmake) # for "make uninstall" -# ---------------------------------------------------------------------------- -# Uninstall target, for "make uninstall" -# ---------------------------------------------------------------------------- -configure_file( - "${CMAKE_CURRENT_SOURCE_DIR}/cmake/cmake_uninstall.cmake.in" - "${CMAKE_CURRENT_BINARY_DIR}/cmake_uninstall.cmake" - IMMEDIATE @ONLY) +include(cmake/handle_allocators.cmake) # Must be after tbb, pertools -add_custom_target(uninstall - "${CMAKE_COMMAND}" -P "${CMAKE_CURRENT_BINARY_DIR}/cmake_uninstall.cmake") - - -############################################################################### -# Set up options - -# Configurable Options -if(GTSAM_UNSTABLE_AVAILABLE) - option(GTSAM_BUILD_UNSTABLE "Enable/Disable libgtsam_unstable" ON) - option(GTSAM_UNSTABLE_BUILD_PYTHON "Enable/Disable Python wrapper for libgtsam_unstable" ON) - option(GTSAM_UNSTABLE_INSTALL_MATLAB_TOOLBOX "Enable/Disable MATLAB wrapper for libgtsam_unstable" OFF) -endif() -option(BUILD_SHARED_LIBS "Build shared gtsam library, instead of static" ON) -option(GTSAM_USE_QUATERNIONS "Enable/Disable using an internal Quaternion representation for rotations instead of rotation matrices. If enable, Rot3::EXPMAP is enforced by default." OFF) -option(GTSAM_POSE3_EXPMAP "Enable/Disable using Pose3::EXPMAP as the default mode. If disabled, Pose3::FIRST_ORDER will be used." ON) -option(GTSAM_ROT3_EXPMAP "Ignore if GTSAM_USE_QUATERNIONS is OFF (Rot3::EXPMAP by default). Otherwise, enable Rot3::EXPMAP, or if disabled, use Rot3::CAYLEY." ON) -option(GTSAM_ENABLE_CONSISTENCY_CHECKS "Enable/Disable expensive consistency checks" OFF) -option(GTSAM_WITH_TBB "Use Intel Threaded Building Blocks (TBB) if available" ON) -option(GTSAM_WITH_EIGEN_MKL "Eigen will use Intel MKL if available" OFF) -option(GTSAM_WITH_EIGEN_MKL_OPENMP "Eigen, when using Intel MKL, will also use OpenMP for multithreading if available" OFF) -option(GTSAM_THROW_CHEIRALITY_EXCEPTION "Throw exception when a triangulated point is behind a camera" ON) -option(GTSAM_BUILD_PYTHON "Enable/Disable building & installation of Python module with pybind11" OFF) -option(GTSAM_ALLOW_DEPRECATED_SINCE_V41 "Allow use of methods/functions deprecated in GTSAM 4.1" ON) -option(GTSAM_SUPPORT_NESTED_DISSECTION "Support Metis-based nested dissection" ON) -option(GTSAM_TANGENT_PREINTEGRATION "Use new ImuFactor with integration on tangent space" ON) -if(NOT MSVC AND NOT XCODE_VERSION) - option(GTSAM_BUILD_WITH_CCACHE "Use ccache compiler cache" ON) -endif() - -if(NOT MSVC AND NOT XCODE_VERSION) - # Set the build type to upper case for downstream use - string(TOUPPER "${CMAKE_BUILD_TYPE}" CMAKE_BUILD_TYPE_UPPER) - - # Set the GTSAM_BUILD_TAG variable. - # If build type is Release, set to blank (""), else set to the build type. - if(${CMAKE_BUILD_TYPE_UPPER} STREQUAL "RELEASE") - set(GTSAM_BUILD_TAG "") # Don't create release mode tag on installed directory - else() - set(GTSAM_BUILD_TAG "${CMAKE_BUILD_TYPE}") - endif() -endif() - -# Options relating to MATLAB wrapper -# TODO: Check for matlab mex binary before handling building of binaries -option(GTSAM_INSTALL_MATLAB_TOOLBOX "Enable/Disable installation of matlab toolbox" OFF) -set(GTSAM_PYTHON_VERSION "Default" CACHE STRING "The version of Python to build the wrappers against.") - -# Check / set dependent variables for MATLAB wrapper -if(GTSAM_INSTALL_MATLAB_TOOLBOX AND GTSAM_BUILD_TYPE_POSTFIXES) - set(CURRENT_POSTFIX ${CMAKE_${CMAKE_BUILD_TYPE_UPPER}_POSTFIX}) -endif() - -if(GTSAM_INSTALL_MATLAB_TOOLBOX AND NOT BUILD_SHARED_LIBS) - message(FATAL_ERROR "GTSAM_INSTALL_MATLAB_TOOLBOX and BUILD_SHARED_LIBS=OFF. The MATLAB wrapper cannot be compiled with a static GTSAM library because mex modules are themselves shared libraries. If you want a self-contained mex module, enable GTSAM_MEX_BUILD_STATIC_MODULE instead of BUILD_SHARED_LIBS=OFF.") -endif() - -if(GTSAM_BUILD_PYTHON) - if(${GTSAM_PYTHON_VERSION} STREQUAL "Default") - # Get info about the Python3 interpreter - # https://cmake.org/cmake/help/latest/module/FindPython3.html#module:FindPython3 - find_package(Python3 COMPONENTS Interpreter Development) - - if(NOT ${Python3_FOUND}) - message(FATAL_ERROR "Cannot find Python3 interpreter. Please install Python >= 3.6.") - endif() - - set(GTSAM_PYTHON_VERSION "${Python3_VERSION_MAJOR}.${Python3_VERSION_MINOR}" - CACHE - STRING - "The version of Python to build the wrappers against." - FORCE) - endif() - - if(GTSAM_UNSTABLE_BUILD_PYTHON) - if (NOT GTSAM_BUILD_UNSTABLE) - message(WARNING "GTSAM_UNSTABLE_BUILD_PYTHON requires the unstable module to be enabled.") - set(GTSAM_UNSTABLE_BUILD_PYTHON OFF) - endif() - endif() - - set(GTSAM_PY_INSTALL_PATH "${CMAKE_INSTALL_PREFIX}/python") -endif() - -# Flags for choosing default packaging tools -set(CPACK_SOURCE_GENERATOR "TGZ" CACHE STRING "CPack Default Source Generator") -set(CPACK_GENERATOR "TGZ" CACHE STRING "CPack Default Binary Generator") - -if (CMAKE_GENERATOR STREQUAL "Ninja" AND - ((CMAKE_CXX_COMPILER_ID STREQUAL "GNU" AND NOT CMAKE_CXX_COMPILER_VERSION VERSION_LESS 4.9) OR - (CMAKE_CXX_COMPILER_ID STREQUAL "Clang" AND NOT CMAKE_CXX_COMPILER_VERSION VERSION_LESS 3.5))) - # Force colored warnings in Ninja's output, if the compiler has -fdiagnostics-color support. - # Rationale in https://github.com/ninja-build/ninja/issues/814 - add_compile_options(-fdiagnostics-color=always) -endif() - -############################################################################### -# Find boost - -# To change the path for boost, you will need to set: -# BOOST_ROOT: path to install prefix for boost -# Boost_NO_SYSTEM_PATHS: set to true to keep the find script from ignoring BOOST_ROOT - -if(MSVC) - # By default, boost only builds static libraries on windows - set(Boost_USE_STATIC_LIBS ON) # only find static libs - # If we ever reset above on windows and, ... - # If we use Boost shared libs, disable auto linking. - # Some libraries, at least Boost Program Options, rely on this to export DLL symbols. - if(NOT Boost_USE_STATIC_LIBS) - list_append_cache(GTSAM_COMPILE_DEFINITIONS_PUBLIC BOOST_ALL_NO_LIB BOOST_ALL_DYN_LINK) - endif() - # Virtual memory range for PCH exceeded on VS2015 - if(MSVC_VERSION LESS 1910) # older than VS2017 - list_append_cache(GTSAM_COMPILE_OPTIONS_PRIVATE -Zm295) - endif() -endif() - -# If building DLLs in MSVC, we need to avoid EIGEN_STATIC_ASSERT() -# or explicit instantiation will generate build errors. -# See: https://bitbucket.org/gtborg/gtsam/issues/417/fail-to-build-on-msvc-2017 -# -if(MSVC AND BUILD_SHARED_LIBS) - list_append_cache(GTSAM_COMPILE_DEFINITIONS_PUBLIC EIGEN_NO_STATIC_ASSERT) -endif() - -# Store these in variables so they are automatically replicated in GTSAMConfig.cmake and such. -set(BOOST_FIND_MINIMUM_VERSION 1.58) -set(BOOST_FIND_MINIMUM_COMPONENTS serialization system filesystem thread program_options date_time timer chrono regex) - -find_package(Boost ${BOOST_FIND_MINIMUM_VERSION} COMPONENTS ${BOOST_FIND_MINIMUM_COMPONENTS}) - -# Required components -if(NOT Boost_SERIALIZATION_LIBRARY OR NOT Boost_SYSTEM_LIBRARY OR NOT Boost_FILESYSTEM_LIBRARY OR - NOT Boost_THREAD_LIBRARY OR NOT Boost_DATE_TIME_LIBRARY) - message(FATAL_ERROR "Missing required Boost components >= v1.58, please install/upgrade Boost or configure your search paths.") -endif() - -option(GTSAM_DISABLE_NEW_TIMERS "Disables using Boost.chrono for timing" OFF) -# Allow for not using the timer libraries on boost < 1.48 (GTSAM timing code falls back to old timer library) -set(GTSAM_BOOST_LIBRARIES - Boost::serialization - Boost::system - Boost::filesystem - Boost::thread - Boost::date_time - Boost::regex -) -if (GTSAM_DISABLE_NEW_TIMERS) - message("WARNING: GTSAM timing instrumentation manually disabled") - list_append_cache(GTSAM_COMPILE_DEFINITIONS_PUBLIC DGTSAM_DISABLE_NEW_TIMERS) -else() - if(Boost_TIMER_LIBRARY) - list(APPEND GTSAM_BOOST_LIBRARIES Boost::timer Boost::chrono) - else() - list(APPEND GTSAM_BOOST_LIBRARIES rt) # When using the header-only boost timer library, need -lrt - message("WARNING: GTSAM timing instrumentation will use the older, less accurate, Boost timer library because boost older than 1.48 was found.") - endif() -endif() - -############################################################################### -# Find TBB -find_package(TBB 4.4 COMPONENTS tbb tbbmalloc) - -# Set up variables if we're using TBB -if(TBB_FOUND AND GTSAM_WITH_TBB) - set(GTSAM_USE_TBB 1) # This will go into config.h - if ((${TBB_VERSION_MAJOR} GREATER 2020) OR (${TBB_VERSION_MAJOR} EQUAL 2020)) - set(TBB_GREATER_EQUAL_2020 1) - else() - set(TBB_GREATER_EQUAL_2020 0) - endif() - # all definitions and link requisites will go via imported targets: - # tbb & tbbmalloc - list(APPEND GTSAM_ADDITIONAL_LIBRARIES tbb tbbmalloc) -else() - set(GTSAM_USE_TBB 0) # This will go into config.h -endif() - -############################################################################### -# Prohibit Timing build mode in combination with TBB -if(GTSAM_USE_TBB AND (CMAKE_BUILD_TYPE STREQUAL "Timing")) - message(FATAL_ERROR "Timing build mode cannot be used together with TBB. Use a sampling profiler such as Instruments or Intel VTune Amplifier instead.") -endif() - - -############################################################################### -# Find Google perftools -find_package(GooglePerfTools) - -############################################################################### -# Support ccache, if installed -if(NOT MSVC AND NOT XCODE_VERSION) - find_program(CCACHE_FOUND ccache) - if(CCACHE_FOUND) - if(GTSAM_BUILD_WITH_CCACHE) - set_property(GLOBAL PROPERTY RULE_LAUNCH_COMPILE ccache) - set_property(GLOBAL PROPERTY RULE_LAUNCH_LINK ccache) - else() - set_property(GLOBAL PROPERTY RULE_LAUNCH_COMPILE "") - set_property(GLOBAL PROPERTY RULE_LAUNCH_LINK "") - endif() - endif(CCACHE_FOUND) -endif() - -############################################################################### -# Find MKL -find_package(MKL) - -if(MKL_FOUND AND GTSAM_WITH_EIGEN_MKL) - set(GTSAM_USE_EIGEN_MKL 1) # This will go into config.h - set(EIGEN_USE_MKL_ALL 1) # This will go into config.h - it makes Eigen use MKL - list(APPEND GTSAM_ADDITIONAL_LIBRARIES ${MKL_LIBRARIES}) - - # --no-as-needed is required with gcc according to the MKL link advisor - if(CMAKE_CXX_COMPILER_ID STREQUAL "GNU") - set(CMAKE_EXE_LINKER_FLAGS "${CMAKE_EXE_LINKER_FLAGS} -Wl,--no-as-needed") - endif() -else() - set(GTSAM_USE_EIGEN_MKL 0) - set(EIGEN_USE_MKL_ALL 0) -endif() - -############################################################################### -# Find OpenMP (if we're also using MKL) -find_package(OpenMP) # do this here to generate correct message if disabled - -if(GTSAM_WITH_EIGEN_MKL AND GTSAM_WITH_EIGEN_MKL_OPENMP AND GTSAM_USE_EIGEN_MKL) - if(OPENMP_FOUND AND GTSAM_USE_EIGEN_MKL AND GTSAM_WITH_EIGEN_MKL_OPENMP) - set(GTSAM_USE_EIGEN_MKL_OPENMP 1) # This will go into config.h - list_append_cache(GTSAM_COMPILE_OPTIONS_PUBLIC ${OpenMP_CXX_FLAGS}) - endif() -endif() - - -############################################################################### -# Option for using system Eigen or GTSAM-bundled Eigen -### These patches only affect usage of MKL. If you want to enable MKL, you *must* -### use our patched version of Eigen -### See: http://eigen.tuxfamily.org/bz/show_bug.cgi?id=704 (Householder QR MKL selection) -### http://eigen.tuxfamily.org/bz/show_bug.cgi?id=705 (Fix MKL LLT return code) -option(GTSAM_USE_SYSTEM_EIGEN "Find and use system-installed Eigen. If 'off', use the one bundled with GTSAM" OFF) -option(GTSAM_WITH_EIGEN_UNSUPPORTED "Install Eigen's unsupported modules" OFF) - -# Switch for using system Eigen or GTSAM-bundled Eigen -if(GTSAM_USE_SYSTEM_EIGEN) - find_package(Eigen3 REQUIRED) - - # Use generic Eigen include paths e.g. - set(GTSAM_EIGEN_INCLUDE_FOR_INSTALL "${EIGEN3_INCLUDE_DIR}") - - # check if MKL is also enabled - can have one or the other, but not both! - # Note: Eigen >= v3.2.5 includes our patches - if(EIGEN_USE_MKL_ALL AND (EIGEN3_VERSION VERSION_LESS 3.2.5)) - message(FATAL_ERROR "MKL requires at least Eigen 3.2.5, and your system appears to have an older version. Disable GTSAM_USE_SYSTEM_EIGEN to use GTSAM's copy of Eigen, or disable GTSAM_WITH_EIGEN_MKL") - endif() - - # Check for Eigen version which doesn't work with MKL - # See http://eigen.tuxfamily.org/bz/show_bug.cgi?id=1527 for details. - if(EIGEN_USE_MKL_ALL AND (EIGEN3_VERSION VERSION_EQUAL 3.3.4)) - message(FATAL_ERROR "MKL does not work with Eigen 3.3.4 because of a bug in Eigen. See http://eigen.tuxfamily.org/bz/show_bug.cgi?id=1527. Disable GTSAM_USE_SYSTEM_EIGEN to use GTSAM's copy of Eigen, disable GTSAM_WITH_EIGEN_MKL, or upgrade/patch your installation of Eigen.") - endif() - - # The actual include directory (for BUILD cmake target interface): - set(GTSAM_EIGEN_INCLUDE_FOR_BUILD "${EIGEN3_INCLUDE_DIR}") -else() - # Use bundled Eigen include path. - # Clear any variables set by FindEigen3 - if(EIGEN3_INCLUDE_DIR) - set(EIGEN3_INCLUDE_DIR NOTFOUND CACHE STRING "" FORCE) - endif() - - # set full path to be used by external projects - # this will be added to GTSAM_INCLUDE_DIR by gtsam_extra.cmake.in - set(GTSAM_EIGEN_INCLUDE_FOR_INSTALL "include/gtsam/3rdparty/Eigen/") - - # The actual include directory (for BUILD cmake target interface): - set(GTSAM_EIGEN_INCLUDE_FOR_BUILD "${CMAKE_SOURCE_DIR}/gtsam/3rdparty/Eigen/") -endif() - -# Detect Eigen version: -set(EIGEN_VER_H "${GTSAM_EIGEN_INCLUDE_FOR_BUILD}/Eigen/src/Core/util/Macros.h") -if (EXISTS ${EIGEN_VER_H}) - file(READ "${EIGEN_VER_H}" STR_EIGEN_VERSION) - - # Extract the Eigen version from the Macros.h file, lines "#define EIGEN_WORLD_VERSION XX", etc... - - string(REGEX MATCH "EIGEN_WORLD_VERSION[ ]+[0-9]+" GTSAM_EIGEN_VERSION_WORLD "${STR_EIGEN_VERSION}") - string(REGEX MATCH "[0-9]+" GTSAM_EIGEN_VERSION_WORLD "${GTSAM_EIGEN_VERSION_WORLD}") - - string(REGEX MATCH "EIGEN_MAJOR_VERSION[ ]+[0-9]+" GTSAM_EIGEN_VERSION_MAJOR "${STR_EIGEN_VERSION}") - string(REGEX MATCH "[0-9]+" GTSAM_EIGEN_VERSION_MAJOR "${GTSAM_EIGEN_VERSION_MAJOR}") - - string(REGEX MATCH "EIGEN_MINOR_VERSION[ ]+[0-9]+" GTSAM_EIGEN_VERSION_MINOR "${STR_EIGEN_VERSION}") - string(REGEX MATCH "[0-9]+" GTSAM_EIGEN_VERSION_MINOR "${GTSAM_EIGEN_VERSION_MINOR}") - - set(GTSAM_EIGEN_VERSION "${GTSAM_EIGEN_VERSION_WORLD}.${GTSAM_EIGEN_VERSION_MAJOR}.${GTSAM_EIGEN_VERSION_MINOR}") - - message(STATUS "Found Eigen version: ${GTSAM_EIGEN_VERSION}") -else() - message(WARNING "Cannot determine Eigen version, missing file: `${EIGEN_VER_H}`") -endif () - -if (MSVC) - if (BUILD_SHARED_LIBS) - # mute eigen static assert to avoid errors in shared lib - list_append_cache(GTSAM_COMPILE_DEFINITIONS_PUBLIC EIGEN_NO_STATIC_ASSERT) - endif() - list_append_cache(GTSAM_COMPILE_OPTIONS_PRIVATE "/wd4244") # Disable loss of precision which is thrown all over our Eigen -endif() - -if (APPLE AND BUILD_SHARED_LIBS) - # Set the default install directory on macOS - set(CMAKE_INSTALL_NAME_DIR "${CMAKE_INSTALL_PREFIX}/lib") -endif() - -############################################################################### -# Global compile options - -# Build list of possible allocators -set(possible_allocators "") -if(GTSAM_USE_TBB) - list(APPEND possible_allocators TBB) - set(preferred_allocator TBB) -else() - list(APPEND possible_allocators BoostPool STL) - set(preferred_allocator STL) -endif() -if(GOOGLE_PERFTOOLS_FOUND) - list(APPEND possible_allocators tcmalloc) -endif() - -# Check if current allocator choice is valid and set cache option -list(FIND possible_allocators "${GTSAM_DEFAULT_ALLOCATOR}" allocator_valid) -if(allocator_valid EQUAL -1) - set(GTSAM_DEFAULT_ALLOCATOR ${preferred_allocator} CACHE STRING "Default allocator" FORCE) -else() - set(GTSAM_DEFAULT_ALLOCATOR ${preferred_allocator} CACHE STRING "Default allocator") -endif() -set_property(CACHE GTSAM_DEFAULT_ALLOCATOR PROPERTY STRINGS ${possible_allocators}) -mark_as_advanced(GTSAM_DEFAULT_ALLOCATOR) - -# Define compile flags depending on allocator -if("${GTSAM_DEFAULT_ALLOCATOR}" STREQUAL "BoostPool") - set(GTSAM_ALLOCATOR_BOOSTPOOL 1) -elseif("${GTSAM_DEFAULT_ALLOCATOR}" STREQUAL "STL") - set(GTSAM_ALLOCATOR_STL 1) -elseif("${GTSAM_DEFAULT_ALLOCATOR}" STREQUAL "TBB") - set(GTSAM_ALLOCATOR_TBB 1) -elseif("${GTSAM_DEFAULT_ALLOCATOR}" STREQUAL "tcmalloc") - set(GTSAM_ALLOCATOR_STL 1) # tcmalloc replaces malloc, so to use it we use the STL allocator - list(APPEND GTSAM_ADDITIONAL_LIBRARIES "tcmalloc") -endif() - -if(MSVC) - list_append_cache(GTSAM_COMPILE_DEFINITIONS_PRIVATE _CRT_SECURE_NO_WARNINGS _SCL_SECURE_NO_WARNINGS) - list_append_cache(GTSAM_COMPILE_OPTIONS_PRIVATE /wd4251 /wd4275 /wd4251 /wd4661 /wd4344 /wd4503) # Disable non-DLL-exported base class and other warnings - list_append_cache(GTSAM_COMPILE_OPTIONS_PRIVATE /bigobj) # Allow large object files for template-based code -endif() - -# GCC 4.8+ complains about local typedefs which we use for shared_ptr etc. -if(CMAKE_CXX_COMPILER_ID STREQUAL "GNU") - if (NOT CMAKE_CXX_COMPILER_VERSION VERSION_LESS 4.8) - list_append_cache(GTSAM_COMPILE_OPTIONS_PRIVATE -Wno-unused-local-typedefs) - endif() -endif() - -# As of XCode 7, clang also complains about this -if(CMAKE_CXX_COMPILER_ID STREQUAL "Clang") - if (NOT CMAKE_CXX_COMPILER_VERSION VERSION_LESS 7.0) - list_append_cache(GTSAM_COMPILE_OPTIONS_PRIVATE -Wno-unused-local-typedefs) - endif() -endif() - -if(GTSAM_ENABLE_CONSISTENCY_CHECKS) - # This should be made PUBLIC if GTSAM_EXTRA_CONSISTENCY_CHECKS is someday used in a public .h - list_append_cache(GTSAM_COMPILE_DEFINITIONS_PRIVATE GTSAM_EXTRA_CONSISTENCY_CHECKS) -endif() +include(cmake/handle_global_build_flags.cmake) # Build flags ############################################################################### # Add components @@ -477,7 +92,6 @@ endif() GtsamMakeConfigFile(GTSAM "${CMAKE_CURRENT_SOURCE_DIR}/gtsam_extra.cmake.in") export(TARGETS ${GTSAM_EXPORTED_TARGETS} FILE GTSAM-exports.cmake) - # Check for doxygen availability - optional dependency find_package(Doxygen) @@ -489,146 +103,11 @@ endif() # CMake Tools add_subdirectory(cmake) - -############################################################################### -# Set up CPack -set(CPACK_PACKAGE_DESCRIPTION_SUMMARY "GTSAM") -set(CPACK_PACKAGE_VENDOR "Frank Dellaert, Georgia Institute of Technology") -set(CPACK_PACKAGE_CONTACT "Frank Dellaert, dellaert@cc.gatech.edu") -set(CPACK_PACKAGE_DESCRIPTION_FILE "${CMAKE_CURRENT_SOURCE_DIR}/README.md") -set(CPACK_RESOURCE_FILE_LICENSE "${CMAKE_CURRENT_SOURCE_DIR}/LICENSE") -set(CPACK_PACKAGE_VERSION_MAJOR ${GTSAM_VERSION_MAJOR}) -set(CPACK_PACKAGE_VERSION_MINOR ${GTSAM_VERSION_MINOR}) -set(CPACK_PACKAGE_VERSION_PATCH ${GTSAM_VERSION_PATCH}) -set(CPACK_PACKAGE_INSTALL_DIRECTORY "CMake ${CMake_VERSION_MAJOR}.${CMake_VERSION_MINOR}") -#set(CPACK_INSTALLED_DIRECTORIES "doc;.") # Include doc directory -#set(CPACK_INSTALLED_DIRECTORIES ".") # FIXME: throws error -set(CPACK_SOURCE_IGNORE_FILES "/build*;/\\\\.;/makestats.sh$") -set(CPACK_SOURCE_IGNORE_FILES "${CPACK_SOURCE_IGNORE_FILES}" "/gtsam_unstable/") -set(CPACK_SOURCE_IGNORE_FILES "${CPACK_SOURCE_IGNORE_FILES}" "/package_scripts/") -set(CPACK_SOURCE_PACKAGE_FILE_NAME "gtsam-${GTSAM_VERSION_MAJOR}.${GTSAM_VERSION_MINOR}.${GTSAM_VERSION_PATCH}") -#set(CPACK_SOURCE_PACKAGE_FILE_NAME "gtsam-aspn${GTSAM_VERSION_PATCH}") # Used for creating ASPN tarballs - -# Deb-package specific cpack -set(CPACK_DEBIAN_PACKAGE_NAME "libgtsam-dev") -set(CPACK_DEBIAN_PACKAGE_DEPENDS "libboost-dev (>= 1.58)") #Example: "libc6 (>= 2.3.1-6), libgcc1 (>= 1:3.4.2-12)") - - -############################################################################### # Print configuration variables -message(STATUS "===============================================================") -message(STATUS "================ Configuration Options ======================") -print_config("CMAKE_CXX_COMPILER_ID type" "${CMAKE_CXX_COMPILER_ID}") -print_config("CMAKE_CXX_COMPILER_VERSION" "${CMAKE_CXX_COMPILER_VERSION}") -print_config("CMake version" "${CMAKE_VERSION}") -print_config("CMake generator" "${CMAKE_GENERATOR}") -print_config("CMake build tool" "${CMAKE_BUILD_TOOL}") -message(STATUS "Build flags ") -print_enabled_config(${GTSAM_BUILD_TESTS} "Build Tests") -print_enabled_config(${GTSAM_BUILD_EXAMPLES_ALWAYS} "Build examples with 'make all'") -print_enabled_config(${GTSAM_BUILD_TIMING_ALWAYS} "Build timing scripts with 'make all'") -if (DOXYGEN_FOUND) - print_enabled_config(${GTSAM_BUILD_DOCS} "Build Docs") -endif() -print_enabled_config(${BUILD_SHARED_LIBS} "Build shared GTSAM libraries") -print_enabled_config(${GTSAM_BUILD_TYPE_POSTFIXES} "Put build type in library name") -if(GTSAM_UNSTABLE_AVAILABLE) - print_enabled_config(${GTSAM_BUILD_UNSTABLE} "Build libgtsam_unstable ") - print_enabled_config(${GTSAM_UNSTABLE_BUILD_PYTHON} "Build GTSAM unstable Python ") - print_enabled_config(${GTSAM_UNSTABLE_INSTALL_MATLAB_TOOLBOX} "Build MATLAB Toolbox for unstable") -endif() - -if(NOT MSVC AND NOT XCODE_VERSION) - print_enabled_config(${GTSAM_BUILD_WITH_MARCH_NATIVE} "Build for native architecture ") - print_config("Build type" "${CMAKE_BUILD_TYPE}") - print_config("C compilation flags" "${CMAKE_C_FLAGS} ${CMAKE_C_FLAGS_${CMAKE_BUILD_TYPE_UPPER}}") - print_config("C++ compilation flags" "${CMAKE_CXX_FLAGS} ${CMAKE_CXX_FLAGS_${CMAKE_BUILD_TYPE_UPPER}}") -endif() - -print_build_options_for_target(gtsam) - -print_config("Use System Eigen" "${GTSAM_USE_SYSTEM_EIGEN} (Using version: ${GTSAM_EIGEN_VERSION})") - -if(GTSAM_USE_TBB) - print_config("Use Intel TBB" "Yes (Version: ${TBB_VERSION})") -elseif(TBB_FOUND) - print_config("Use Intel TBB" "TBB (Version: ${TBB_VERSION}) found but GTSAM_WITH_TBB is disabled") -else() - print_config("Use Intel TBB" "TBB not found") -endif() -if(GTSAM_USE_EIGEN_MKL) - print_config("Eigen will use MKL" "Yes") -elseif(MKL_FOUND) - print_config("Eigen will use MKL" "MKL found but GTSAM_WITH_EIGEN_MKL is disabled") -else() - print_config("Eigen will use MKL" "MKL not found") -endif() -if(GTSAM_USE_EIGEN_MKL_OPENMP) - print_config("Eigen will use MKL and OpenMP" "Yes") -elseif(OPENMP_FOUND AND NOT GTSAM_WITH_EIGEN_MKL) - print_config("Eigen will use MKL and OpenMP" "OpenMP found but GTSAM_WITH_EIGEN_MKL is disabled") -elseif(OPENMP_FOUND AND NOT MKL_FOUND) - print_config("Eigen will use MKL and OpenMP" "OpenMP found but MKL not found") -elseif(OPENMP_FOUND) - print_config("Eigen will use MKL and OpenMP" "OpenMP found but GTSAM_WITH_EIGEN_MKL_OPENMP is disabled") -else() - print_config("Eigen will use MKL and OpenMP" "OpenMP not found") -endif() -print_config("Default allocator" "${GTSAM_DEFAULT_ALLOCATOR}") - -if(GTSAM_THROW_CHEIRALITY_EXCEPTION) - print_config("Cheirality exceptions enabled" "YES") -else() - print_config("Cheirality exceptions enabled" "NO") -endif() - -if(NOT MSVC AND NOT XCODE_VERSION) - if(CCACHE_FOUND AND GTSAM_BUILD_WITH_CCACHE) - print_config("Build with ccache" "Yes") - elseif(CCACHE_FOUND) - print_config("Build with ccache" "ccache found but GTSAM_BUILD_WITH_CCACHE is disabled") - else() - print_config("Build with ccache" "No") - endif() -endif() - -message(STATUS "Packaging flags") -print_config("CPack Source Generator" "${CPACK_SOURCE_GENERATOR}") -print_config("CPack Generator" "${CPACK_GENERATOR}") - -message(STATUS "GTSAM flags ") -print_enabled_config(${GTSAM_USE_QUATERNIONS} "Quaternions as default Rot3 ") -print_enabled_config(${GTSAM_ENABLE_CONSISTENCY_CHECKS} "Runtime consistency checking ") -print_enabled_config(${GTSAM_ROT3_EXPMAP} "Rot3 retract is full ExpMap ") -print_enabled_config(${GTSAM_POSE3_EXPMAP} "Pose3 retract is full ExpMap ") -print_enabled_config(${GTSAM_ALLOW_DEPRECATED_SINCE_V41} "Allow features deprecated in GTSAM 4.1") -print_enabled_config(${GTSAM_SUPPORT_NESTED_DISSECTION} "Metis-based Nested Dissection ") -print_enabled_config(${GTSAM_TANGENT_PREINTEGRATION} "Use tangent-space preintegration") - -message(STATUS "MATLAB toolbox flags") -print_enabled_config(${GTSAM_INSTALL_MATLAB_TOOLBOX} "Install MATLAB toolbox ") -if (${GTSAM_INSTALL_MATLAB_TOOLBOX}) - print_config("MATLAB root" "${MATLAB_ROOT}") - print_config("MEX binary" "${MEX_COMMAND}") -endif() -message(STATUS "Python toolbox flags ") -print_enabled_config(${GTSAM_BUILD_PYTHON} "Build Python module with pybind ") -if(GTSAM_BUILD_PYTHON) - print_config("Python version" ${GTSAM_PYTHON_VERSION}) -endif() - -message(STATUS "===============================================================") +include(cmake/handle_print_configuration.cmake) # Print warnings at the end -if(GTSAM_WITH_TBB AND NOT TBB_FOUND) - message(WARNING "TBB 4.4 or newer was not found - this is ok, but note that GTSAM parallelization will be disabled. Set GTSAM_WITH_TBB to 'Off' to avoid this warning.") -endif() -if(GTSAM_WITH_EIGEN_MKL AND NOT MKL_FOUND) - message(WARNING "MKL was not found - this is ok, but note that MKL will be disabled. Set GTSAM_WITH_EIGEN_MKL to 'Off' to disable this warning. See INSTALL.md for notes on performance.") -endif() -if(GTSAM_WITH_EIGEN_MKL_OPENMP AND NOT OPENMP_FOUND AND MKL_FOUND) - message(WARNING "Your compiler does not support OpenMP. Set GTSAM_WITH_EIGEN_MKL_OPENMP to 'Off' to avoid this warning. See INSTALL.md for notes on performance.") -endif() +include(cmake/handle_final_checks.cmake) # Include CPack *after* all flags include(CPack) diff --git a/cmake/GtsamBuildTypes.cmake b/cmake/GtsamBuildTypes.cmake index 53dacd3f5..840d37427 100644 --- a/cmake/GtsamBuildTypes.cmake +++ b/cmake/GtsamBuildTypes.cmake @@ -263,3 +263,17 @@ function(gtsam_apply_build_flags target_name_) target_compile_options(${target_name_} PRIVATE ${GTSAM_COMPILE_OPTIONS_PRIVATE}) endfunction(gtsam_apply_build_flags) + + +if(NOT MSVC AND NOT XCODE_VERSION) + # Set the build type to upper case for downstream use + string(TOUPPER "${CMAKE_BUILD_TYPE}" CMAKE_BUILD_TYPE_UPPER) + + # Set the GTSAM_BUILD_TAG variable. + # If build type is Release, set to blank (""), else set to the build type. + if(${CMAKE_BUILD_TYPE_UPPER} STREQUAL "RELEASE") + set(GTSAM_BUILD_TAG "") # Don't create release mode tag on installed directory + else() + set(GTSAM_BUILD_TAG "${CMAKE_BUILD_TYPE}") + endif() +endif() diff --git a/cmake/handle_allocators.cmake b/cmake/handle_allocators.cmake new file mode 100644 index 000000000..63411b17b --- /dev/null +++ b/cmake/handle_allocators.cmake @@ -0,0 +1,34 @@ +# Build list of possible allocators +set(possible_allocators "") +if(GTSAM_USE_TBB) + list(APPEND possible_allocators TBB) + set(preferred_allocator TBB) +else() + list(APPEND possible_allocators BoostPool STL) + set(preferred_allocator STL) +endif() +if(GOOGLE_PERFTOOLS_FOUND) + list(APPEND possible_allocators tcmalloc) +endif() + +# Check if current allocator choice is valid and set cache option +list(FIND possible_allocators "${GTSAM_DEFAULT_ALLOCATOR}" allocator_valid) +if(allocator_valid EQUAL -1) + set(GTSAM_DEFAULT_ALLOCATOR ${preferred_allocator} CACHE STRING "Default allocator" FORCE) +else() + set(GTSAM_DEFAULT_ALLOCATOR ${preferred_allocator} CACHE STRING "Default allocator") +endif() +set_property(CACHE GTSAM_DEFAULT_ALLOCATOR PROPERTY STRINGS ${possible_allocators}) +mark_as_advanced(GTSAM_DEFAULT_ALLOCATOR) + +# Define compile flags depending on allocator +if("${GTSAM_DEFAULT_ALLOCATOR}" STREQUAL "BoostPool") + set(GTSAM_ALLOCATOR_BOOSTPOOL 1) +elseif("${GTSAM_DEFAULT_ALLOCATOR}" STREQUAL "STL") + set(GTSAM_ALLOCATOR_STL 1) +elseif("${GTSAM_DEFAULT_ALLOCATOR}" STREQUAL "TBB") + set(GTSAM_ALLOCATOR_TBB 1) +elseif("${GTSAM_DEFAULT_ALLOCATOR}" STREQUAL "tcmalloc") + set(GTSAM_ALLOCATOR_STL 1) # tcmalloc replaces malloc, so to use it we use the STL allocator + list(APPEND GTSAM_ADDITIONAL_LIBRARIES "tcmalloc") +endif() diff --git a/cmake/handle_boost.cmake b/cmake/handle_boost.cmake new file mode 100644 index 000000000..e73c2237d --- /dev/null +++ b/cmake/handle_boost.cmake @@ -0,0 +1,56 @@ +############################################################################### +# Find boost + +# To change the path for boost, you will need to set: +# BOOST_ROOT: path to install prefix for boost +# Boost_NO_SYSTEM_PATHS: set to true to keep the find script from ignoring BOOST_ROOT + +if(MSVC) + # By default, boost only builds static libraries on windows + set(Boost_USE_STATIC_LIBS ON) # only find static libs + # If we ever reset above on windows and, ... + # If we use Boost shared libs, disable auto linking. + # Some libraries, at least Boost Program Options, rely on this to export DLL symbols. + if(NOT Boost_USE_STATIC_LIBS) + list_append_cache(GTSAM_COMPILE_DEFINITIONS_PUBLIC BOOST_ALL_NO_LIB BOOST_ALL_DYN_LINK) + endif() + # Virtual memory range for PCH exceeded on VS2015 + if(MSVC_VERSION LESS 1910) # older than VS2017 + list_append_cache(GTSAM_COMPILE_OPTIONS_PRIVATE -Zm295) + endif() +endif() + + +# Store these in variables so they are automatically replicated in GTSAMConfig.cmake and such. +set(BOOST_FIND_MINIMUM_VERSION 1.58) +set(BOOST_FIND_MINIMUM_COMPONENTS serialization system filesystem thread program_options date_time timer chrono regex) + +find_package(Boost ${BOOST_FIND_MINIMUM_VERSION} COMPONENTS ${BOOST_FIND_MINIMUM_COMPONENTS}) + +# Required components +if(NOT Boost_SERIALIZATION_LIBRARY OR NOT Boost_SYSTEM_LIBRARY OR NOT Boost_FILESYSTEM_LIBRARY OR + NOT Boost_THREAD_LIBRARY OR NOT Boost_DATE_TIME_LIBRARY) + message(FATAL_ERROR "Missing required Boost components >= v1.58, please install/upgrade Boost or configure your search paths.") +endif() + +option(GTSAM_DISABLE_NEW_TIMERS "Disables using Boost.chrono for timing" OFF) +# Allow for not using the timer libraries on boost < 1.48 (GTSAM timing code falls back to old timer library) +set(GTSAM_BOOST_LIBRARIES + Boost::serialization + Boost::system + Boost::filesystem + Boost::thread + Boost::date_time + Boost::regex +) +if (GTSAM_DISABLE_NEW_TIMERS) + message("WARNING: GTSAM timing instrumentation manually disabled") + list_append_cache(GTSAM_COMPILE_DEFINITIONS_PUBLIC DGTSAM_DISABLE_NEW_TIMERS) +else() + if(Boost_TIMER_LIBRARY) + list(APPEND GTSAM_BOOST_LIBRARIES Boost::timer Boost::chrono) + else() + list(APPEND GTSAM_BOOST_LIBRARIES rt) # When using the header-only boost timer library, need -lrt + message("WARNING: GTSAM timing instrumentation will use the older, less accurate, Boost timer library because boost older than 1.48 was found.") + endif() +endif() diff --git a/cmake/handle_ccache.cmake b/cmake/handle_ccache.cmake new file mode 100644 index 000000000..9eabb1905 --- /dev/null +++ b/cmake/handle_ccache.cmake @@ -0,0 +1,14 @@ +############################################################################### +# Support ccache, if installed +if(NOT MSVC AND NOT XCODE_VERSION) + find_program(CCACHE_FOUND ccache) + if(CCACHE_FOUND) + if(GTSAM_BUILD_WITH_CCACHE) + set_property(GLOBAL PROPERTY RULE_LAUNCH_COMPILE ccache) + set_property(GLOBAL PROPERTY RULE_LAUNCH_LINK ccache) + else() + set_property(GLOBAL PROPERTY RULE_LAUNCH_COMPILE "") + set_property(GLOBAL PROPERTY RULE_LAUNCH_LINK "") + endif() + endif(CCACHE_FOUND) +endif() diff --git a/cmake/handle_cpack.cmake b/cmake/handle_cpack.cmake new file mode 100644 index 000000000..1c32433a4 --- /dev/null +++ b/cmake/handle_cpack.cmake @@ -0,0 +1,28 @@ +#JLBC: is all this actually used by someone? could it be removed? + +# Flags for choosing default packaging tools +set(CPACK_SOURCE_GENERATOR "TGZ" CACHE STRING "CPack Default Source Generator") +set(CPACK_GENERATOR "TGZ" CACHE STRING "CPack Default Binary Generator") + +############################################################################### +# Set up CPack +set(CPACK_PACKAGE_DESCRIPTION_SUMMARY "GTSAM") +set(CPACK_PACKAGE_VENDOR "Frank Dellaert, Georgia Institute of Technology") +set(CPACK_PACKAGE_CONTACT "Frank Dellaert, dellaert@cc.gatech.edu") +set(CPACK_PACKAGE_DESCRIPTION_FILE "${CMAKE_CURRENT_SOURCE_DIR}/README.md") +set(CPACK_RESOURCE_FILE_LICENSE "${CMAKE_CURRENT_SOURCE_DIR}/LICENSE") +set(CPACK_PACKAGE_VERSION_MAJOR ${GTSAM_VERSION_MAJOR}) +set(CPACK_PACKAGE_VERSION_MINOR ${GTSAM_VERSION_MINOR}) +set(CPACK_PACKAGE_VERSION_PATCH ${GTSAM_VERSION_PATCH}) +set(CPACK_PACKAGE_INSTALL_DIRECTORY "CMake ${CMake_VERSION_MAJOR}.${CMake_VERSION_MINOR}") +#set(CPACK_INSTALLED_DIRECTORIES "doc;.") # Include doc directory +#set(CPACK_INSTALLED_DIRECTORIES ".") # FIXME: throws error +set(CPACK_SOURCE_IGNORE_FILES "/build*;/\\\\.;/makestats.sh$") +set(CPACK_SOURCE_IGNORE_FILES "${CPACK_SOURCE_IGNORE_FILES}" "/gtsam_unstable/") +set(CPACK_SOURCE_IGNORE_FILES "${CPACK_SOURCE_IGNORE_FILES}" "/package_scripts/") +set(CPACK_SOURCE_PACKAGE_FILE_NAME "gtsam-${GTSAM_VERSION_MAJOR}.${GTSAM_VERSION_MINOR}.${GTSAM_VERSION_PATCH}") +#set(CPACK_SOURCE_PACKAGE_FILE_NAME "gtsam-aspn${GTSAM_VERSION_PATCH}") # Used for creating ASPN tarballs + +# Deb-package specific cpack +set(CPACK_DEBIAN_PACKAGE_NAME "libgtsam-dev") +set(CPACK_DEBIAN_PACKAGE_DEPENDS "libboost-dev (>= 1.58)") #Example: "libc6 (>= 2.3.1-6), libgcc1 (>= 1:3.4.2-12)") diff --git a/cmake/handle_eigen.cmake b/cmake/handle_eigen.cmake new file mode 100644 index 000000000..690da6971 --- /dev/null +++ b/cmake/handle_eigen.cmake @@ -0,0 +1,75 @@ +############################################################################### +# Option for using system Eigen or GTSAM-bundled Eigen +### These patches only affect usage of MKL. If you want to enable MKL, you *must* +### use our patched version of Eigen +### See: http://eigen.tuxfamily.org/bz/show_bug.cgi?id=704 (Householder QR MKL selection) +### http://eigen.tuxfamily.org/bz/show_bug.cgi?id=705 (Fix MKL LLT return code) +option(GTSAM_USE_SYSTEM_EIGEN "Find and use system-installed Eigen. If 'off', use the one bundled with GTSAM" OFF) +option(GTSAM_WITH_EIGEN_UNSUPPORTED "Install Eigen's unsupported modules" OFF) + +# Switch for using system Eigen or GTSAM-bundled Eigen +if(GTSAM_USE_SYSTEM_EIGEN) + find_package(Eigen3 REQUIRED) + + # Use generic Eigen include paths e.g. + set(GTSAM_EIGEN_INCLUDE_FOR_INSTALL "${EIGEN3_INCLUDE_DIR}") + + # check if MKL is also enabled - can have one or the other, but not both! + # Note: Eigen >= v3.2.5 includes our patches + if(EIGEN_USE_MKL_ALL AND (EIGEN3_VERSION VERSION_LESS 3.2.5)) + message(FATAL_ERROR "MKL requires at least Eigen 3.2.5, and your system appears to have an older version. Disable GTSAM_USE_SYSTEM_EIGEN to use GTSAM's copy of Eigen, or disable GTSAM_WITH_EIGEN_MKL") + endif() + + # Check for Eigen version which doesn't work with MKL + # See http://eigen.tuxfamily.org/bz/show_bug.cgi?id=1527 for details. + if(EIGEN_USE_MKL_ALL AND (EIGEN3_VERSION VERSION_EQUAL 3.3.4)) + message(FATAL_ERROR "MKL does not work with Eigen 3.3.4 because of a bug in Eigen. See http://eigen.tuxfamily.org/bz/show_bug.cgi?id=1527. Disable GTSAM_USE_SYSTEM_EIGEN to use GTSAM's copy of Eigen, disable GTSAM_WITH_EIGEN_MKL, or upgrade/patch your installation of Eigen.") + endif() + + # The actual include directory (for BUILD cmake target interface): + set(GTSAM_EIGEN_INCLUDE_FOR_BUILD "${EIGEN3_INCLUDE_DIR}") +else() + # Use bundled Eigen include path. + # Clear any variables set by FindEigen3 + if(EIGEN3_INCLUDE_DIR) + set(EIGEN3_INCLUDE_DIR NOTFOUND CACHE STRING "" FORCE) + endif() + + # set full path to be used by external projects + # this will be added to GTSAM_INCLUDE_DIR by gtsam_extra.cmake.in + set(GTSAM_EIGEN_INCLUDE_FOR_INSTALL "include/gtsam/3rdparty/Eigen/") + + # The actual include directory (for BUILD cmake target interface): + set(GTSAM_EIGEN_INCLUDE_FOR_BUILD "${CMAKE_SOURCE_DIR}/gtsam/3rdparty/Eigen/") +endif() + +# Detect Eigen version: +set(EIGEN_VER_H "${GTSAM_EIGEN_INCLUDE_FOR_BUILD}/Eigen/src/Core/util/Macros.h") +if (EXISTS ${EIGEN_VER_H}) + file(READ "${EIGEN_VER_H}" STR_EIGEN_VERSION) + + # Extract the Eigen version from the Macros.h file, lines "#define EIGEN_WORLD_VERSION XX", etc... + + string(REGEX MATCH "EIGEN_WORLD_VERSION[ ]+[0-9]+" GTSAM_EIGEN_VERSION_WORLD "${STR_EIGEN_VERSION}") + string(REGEX MATCH "[0-9]+" GTSAM_EIGEN_VERSION_WORLD "${GTSAM_EIGEN_VERSION_WORLD}") + + string(REGEX MATCH "EIGEN_MAJOR_VERSION[ ]+[0-9]+" GTSAM_EIGEN_VERSION_MAJOR "${STR_EIGEN_VERSION}") + string(REGEX MATCH "[0-9]+" GTSAM_EIGEN_VERSION_MAJOR "${GTSAM_EIGEN_VERSION_MAJOR}") + + string(REGEX MATCH "EIGEN_MINOR_VERSION[ ]+[0-9]+" GTSAM_EIGEN_VERSION_MINOR "${STR_EIGEN_VERSION}") + string(REGEX MATCH "[0-9]+" GTSAM_EIGEN_VERSION_MINOR "${GTSAM_EIGEN_VERSION_MINOR}") + + set(GTSAM_EIGEN_VERSION "${GTSAM_EIGEN_VERSION_WORLD}.${GTSAM_EIGEN_VERSION_MAJOR}.${GTSAM_EIGEN_VERSION_MINOR}") + + message(STATUS "Found Eigen version: ${GTSAM_EIGEN_VERSION}") +else() + message(WARNING "Cannot determine Eigen version, missing file: `${EIGEN_VER_H}`") +endif () + +if (MSVC) + if (BUILD_SHARED_LIBS) + # mute eigen static assert to avoid errors in shared lib + list_append_cache(GTSAM_COMPILE_DEFINITIONS_PUBLIC EIGEN_NO_STATIC_ASSERT) + endif() + list_append_cache(GTSAM_COMPILE_OPTIONS_PRIVATE "/wd4244") # Disable loss of precision which is thrown all over our Eigen +endif() diff --git a/cmake/handle_final_checks.cmake b/cmake/handle_final_checks.cmake new file mode 100644 index 000000000..f91fc7fdb --- /dev/null +++ b/cmake/handle_final_checks.cmake @@ -0,0 +1,10 @@ +# Print warnings at the end +if(GTSAM_WITH_TBB AND NOT TBB_FOUND) + message(WARNING "TBB 4.4 or newer was not found - this is ok, but note that GTSAM parallelization will be disabled. Set GTSAM_WITH_TBB to 'Off' to avoid this warning.") +endif() +if(GTSAM_WITH_EIGEN_MKL AND NOT MKL_FOUND) + message(WARNING "MKL was not found - this is ok, but note that MKL will be disabled. Set GTSAM_WITH_EIGEN_MKL to 'Off' to disable this warning. See INSTALL.md for notes on performance.") +endif() +if(GTSAM_WITH_EIGEN_MKL_OPENMP AND NOT OPENMP_FOUND AND MKL_FOUND) + message(WARNING "Your compiler does not support OpenMP. Set GTSAM_WITH_EIGEN_MKL_OPENMP to 'Off' to avoid this warning. See INSTALL.md for notes on performance.") +endif() diff --git a/cmake/handle_general_options.cmake b/cmake/handle_general_options.cmake new file mode 100644 index 000000000..27d73bd86 --- /dev/null +++ b/cmake/handle_general_options.cmake @@ -0,0 +1,46 @@ +############################################################################### +# Set up options + +# See whether gtsam_unstable is available (it will be present only if we're using a git checkout) +if(EXISTS "${PROJECT_SOURCE_DIR}/gtsam_unstable" AND IS_DIRECTORY "${PROJECT_SOURCE_DIR}/gtsam_unstable") + set(GTSAM_UNSTABLE_AVAILABLE 1) +else() + set(GTSAM_UNSTABLE_AVAILABLE 0) +endif() + +# Configurable Options +if(GTSAM_UNSTABLE_AVAILABLE) + option(GTSAM_BUILD_UNSTABLE "Enable/Disable libgtsam_unstable" ON) + option(GTSAM_UNSTABLE_BUILD_PYTHON "Enable/Disable Python wrapper for libgtsam_unstable" ON) + option(GTSAM_UNSTABLE_INSTALL_MATLAB_TOOLBOX "Enable/Disable MATLAB wrapper for libgtsam_unstable" OFF) +endif() +option(BUILD_SHARED_LIBS "Build shared gtsam library, instead of static" ON) +option(GTSAM_USE_QUATERNIONS "Enable/Disable using an internal Quaternion representation for rotations instead of rotation matrices. If enable, Rot3::EXPMAP is enforced by default." OFF) +option(GTSAM_POSE3_EXPMAP "Enable/Disable using Pose3::EXPMAP as the default mode. If disabled, Pose3::FIRST_ORDER will be used." ON) +option(GTSAM_ROT3_EXPMAP "Ignore if GTSAM_USE_QUATERNIONS is OFF (Rot3::EXPMAP by default). Otherwise, enable Rot3::EXPMAP, or if disabled, use Rot3::CAYLEY." ON) +option(GTSAM_ENABLE_CONSISTENCY_CHECKS "Enable/Disable expensive consistency checks" OFF) +option(GTSAM_WITH_TBB "Use Intel Threaded Building Blocks (TBB) if available" ON) +option(GTSAM_WITH_EIGEN_MKL "Eigen will use Intel MKL if available" OFF) +option(GTSAM_WITH_EIGEN_MKL_OPENMP "Eigen, when using Intel MKL, will also use OpenMP for multithreading if available" OFF) +option(GTSAM_THROW_CHEIRALITY_EXCEPTION "Throw exception when a triangulated point is behind a camera" ON) +option(GTSAM_BUILD_PYTHON "Enable/Disable building & installation of Python module with pybind11" OFF) +option(GTSAM_ALLOW_DEPRECATED_SINCE_V41 "Allow use of methods/functions deprecated in GTSAM 4.1" ON) +option(GTSAM_SUPPORT_NESTED_DISSECTION "Support Metis-based nested dissection" ON) +option(GTSAM_TANGENT_PREINTEGRATION "Use new ImuFactor with integration on tangent space" ON) +if(NOT MSVC AND NOT XCODE_VERSION) + option(GTSAM_BUILD_WITH_CCACHE "Use ccache compiler cache" ON) +endif() + +# Options relating to MATLAB wrapper +# TODO: Check for matlab mex binary before handling building of binaries +option(GTSAM_INSTALL_MATLAB_TOOLBOX "Enable/Disable installation of matlab toolbox" OFF) +set(GTSAM_PYTHON_VERSION "Default" CACHE STRING "The version of Python to build the wrappers against.") + +# Check / set dependent variables for MATLAB wrapper +if(GTSAM_INSTALL_MATLAB_TOOLBOX AND GTSAM_BUILD_TYPE_POSTFIXES) + set(CURRENT_POSTFIX ${CMAKE_${CMAKE_BUILD_TYPE_UPPER}_POSTFIX}) +endif() + +if(GTSAM_INSTALL_MATLAB_TOOLBOX AND NOT BUILD_SHARED_LIBS) + message(FATAL_ERROR "GTSAM_INSTALL_MATLAB_TOOLBOX and BUILD_SHARED_LIBS=OFF. The MATLAB wrapper cannot be compiled with a static GTSAM library because mex modules are themselves shared libraries. If you want a self-contained mex module, enable GTSAM_MEX_BUILD_STATIC_MODULE instead of BUILD_SHARED_LIBS=OFF.") +endif() diff --git a/cmake/handle_global_build_flags.cmake b/cmake/handle_global_build_flags.cmake new file mode 100644 index 000000000..f33e12b94 --- /dev/null +++ b/cmake/handle_global_build_flags.cmake @@ -0,0 +1,52 @@ +# JLBC: These should ideally be ported to "modern cmake" via target properties. +# + +if (CMAKE_GENERATOR STREQUAL "Ninja" AND + ((CMAKE_CXX_COMPILER_ID STREQUAL "GNU" AND NOT CMAKE_CXX_COMPILER_VERSION VERSION_LESS 4.9) OR + (CMAKE_CXX_COMPILER_ID STREQUAL "Clang" AND NOT CMAKE_CXX_COMPILER_VERSION VERSION_LESS 3.5))) + # Force colored warnings in Ninja's output, if the compiler has -fdiagnostics-color support. + # Rationale in https://github.com/ninja-build/ninja/issues/814 + add_compile_options(-fdiagnostics-color=always) +endif() + + +# If building DLLs in MSVC, we need to avoid EIGEN_STATIC_ASSERT() +# or explicit instantiation will generate build errors. +# See: https://bitbucket.org/gtborg/gtsam/issues/417/fail-to-build-on-msvc-2017 +# +if(MSVC AND BUILD_SHARED_LIBS) + list_append_cache(GTSAM_COMPILE_DEFINITIONS_PUBLIC EIGEN_NO_STATIC_ASSERT) +endif() + +if (APPLE AND BUILD_SHARED_LIBS) + # Set the default install directory on macOS + set(CMAKE_INSTALL_NAME_DIR "${CMAKE_INSTALL_PREFIX}/lib") +endif() + +############################################################################### +# Global compile options + +if(MSVC) + list_append_cache(GTSAM_COMPILE_DEFINITIONS_PRIVATE _CRT_SECURE_NO_WARNINGS _SCL_SECURE_NO_WARNINGS) + list_append_cache(GTSAM_COMPILE_OPTIONS_PRIVATE /wd4251 /wd4275 /wd4251 /wd4661 /wd4344 /wd4503) # Disable non-DLL-exported base class and other warnings + list_append_cache(GTSAM_COMPILE_OPTIONS_PRIVATE /bigobj) # Allow large object files for template-based code +endif() + +# GCC 4.8+ complains about local typedefs which we use for shared_ptr etc. +if(CMAKE_CXX_COMPILER_ID STREQUAL "GNU") + if (NOT CMAKE_CXX_COMPILER_VERSION VERSION_LESS 4.8) + list_append_cache(GTSAM_COMPILE_OPTIONS_PRIVATE -Wno-unused-local-typedefs) + endif() +endif() + +# As of XCode 7, clang also complains about this +if(CMAKE_CXX_COMPILER_ID STREQUAL "Clang") + if (NOT CMAKE_CXX_COMPILER_VERSION VERSION_LESS 7.0) + list_append_cache(GTSAM_COMPILE_OPTIONS_PRIVATE -Wno-unused-local-typedefs) + endif() +endif() + +if(GTSAM_ENABLE_CONSISTENCY_CHECKS) + # This should be made PUBLIC if GTSAM_EXTRA_CONSISTENCY_CHECKS is someday used in a public .h + list_append_cache(GTSAM_COMPILE_DEFINITIONS_PRIVATE GTSAM_EXTRA_CONSISTENCY_CHECKS) +endif() diff --git a/cmake/handle_mkl.cmake b/cmake/handle_mkl.cmake new file mode 100644 index 000000000..5d7ec365b --- /dev/null +++ b/cmake/handle_mkl.cmake @@ -0,0 +1,17 @@ +############################################################################### +# Find MKL +find_package(MKL) + +if(MKL_FOUND AND GTSAM_WITH_EIGEN_MKL) + set(GTSAM_USE_EIGEN_MKL 1) # This will go into config.h + set(EIGEN_USE_MKL_ALL 1) # This will go into config.h - it makes Eigen use MKL + list(APPEND GTSAM_ADDITIONAL_LIBRARIES ${MKL_LIBRARIES}) + + # --no-as-needed is required with gcc according to the MKL link advisor + if(CMAKE_CXX_COMPILER_ID STREQUAL "GNU") + set(CMAKE_EXE_LINKER_FLAGS "${CMAKE_EXE_LINKER_FLAGS} -Wl,--no-as-needed") + endif() +else() + set(GTSAM_USE_EIGEN_MKL 0) + set(EIGEN_USE_MKL_ALL 0) +endif() diff --git a/cmake/handle_openmp.cmake b/cmake/handle_openmp.cmake new file mode 100644 index 000000000..4f27aa633 --- /dev/null +++ b/cmake/handle_openmp.cmake @@ -0,0 +1,11 @@ + +############################################################################### +# Find OpenMP (if we're also using MKL) +find_package(OpenMP) # do this here to generate correct message if disabled + +if(GTSAM_WITH_EIGEN_MKL AND GTSAM_WITH_EIGEN_MKL_OPENMP AND GTSAM_USE_EIGEN_MKL) + if(OPENMP_FOUND AND GTSAM_USE_EIGEN_MKL AND GTSAM_WITH_EIGEN_MKL_OPENMP) + set(GTSAM_USE_EIGEN_MKL_OPENMP 1) # This will go into config.h + list_append_cache(GTSAM_COMPILE_OPTIONS_PUBLIC ${OpenMP_CXX_FLAGS}) + endif() +endif() diff --git a/cmake/handle_perftools.cmake b/cmake/handle_perftools.cmake new file mode 100644 index 000000000..499caf80a --- /dev/null +++ b/cmake/handle_perftools.cmake @@ -0,0 +1,4 @@ + +############################################################################### +# Find Google perftools +find_package(GooglePerfTools) diff --git a/cmake/handle_print_configuration.cmake b/cmake/handle_print_configuration.cmake new file mode 100644 index 000000000..4ffd00e54 --- /dev/null +++ b/cmake/handle_print_configuration.cmake @@ -0,0 +1,104 @@ +############################################################################### +# Print configuration variables +message(STATUS "===============================================================") +message(STATUS "================ Configuration Options ======================") +print_config("CMAKE_CXX_COMPILER_ID type" "${CMAKE_CXX_COMPILER_ID}") +print_config("CMAKE_CXX_COMPILER_VERSION" "${CMAKE_CXX_COMPILER_VERSION}") +print_config("CMake version" "${CMAKE_VERSION}") +print_config("CMake generator" "${CMAKE_GENERATOR}") +print_config("CMake build tool" "${CMAKE_BUILD_TOOL}") +message(STATUS "Build flags ") +print_enabled_config(${GTSAM_BUILD_TESTS} "Build Tests") +print_enabled_config(${GTSAM_BUILD_EXAMPLES_ALWAYS} "Build examples with 'make all'") +print_enabled_config(${GTSAM_BUILD_TIMING_ALWAYS} "Build timing scripts with 'make all'") +if (DOXYGEN_FOUND) + print_enabled_config(${GTSAM_BUILD_DOCS} "Build Docs") +endif() +print_enabled_config(${BUILD_SHARED_LIBS} "Build shared GTSAM libraries") +print_enabled_config(${GTSAM_BUILD_TYPE_POSTFIXES} "Put build type in library name") +if(GTSAM_UNSTABLE_AVAILABLE) + print_enabled_config(${GTSAM_BUILD_UNSTABLE} "Build libgtsam_unstable ") + print_enabled_config(${GTSAM_UNSTABLE_BUILD_PYTHON} "Build GTSAM unstable Python ") + print_enabled_config(${GTSAM_UNSTABLE_INSTALL_MATLAB_TOOLBOX} "Build MATLAB Toolbox for unstable") +endif() + +if(NOT MSVC AND NOT XCODE_VERSION) + print_enabled_config(${GTSAM_BUILD_WITH_MARCH_NATIVE} "Build for native architecture ") + print_config("Build type" "${CMAKE_BUILD_TYPE}") + print_config("C compilation flags" "${CMAKE_C_FLAGS} ${CMAKE_C_FLAGS_${CMAKE_BUILD_TYPE_UPPER}}") + print_config("C++ compilation flags" "${CMAKE_CXX_FLAGS} ${CMAKE_CXX_FLAGS_${CMAKE_BUILD_TYPE_UPPER}}") +endif() + +print_build_options_for_target(gtsam) + +print_config("Use System Eigen" "${GTSAM_USE_SYSTEM_EIGEN} (Using version: ${GTSAM_EIGEN_VERSION})") + +if(GTSAM_USE_TBB) + print_config("Use Intel TBB" "Yes (Version: ${TBB_VERSION})") +elseif(TBB_FOUND) + print_config("Use Intel TBB" "TBB (Version: ${TBB_VERSION}) found but GTSAM_WITH_TBB is disabled") +else() + print_config("Use Intel TBB" "TBB not found") +endif() +if(GTSAM_USE_EIGEN_MKL) + print_config("Eigen will use MKL" "Yes") +elseif(MKL_FOUND) + print_config("Eigen will use MKL" "MKL found but GTSAM_WITH_EIGEN_MKL is disabled") +else() + print_config("Eigen will use MKL" "MKL not found") +endif() +if(GTSAM_USE_EIGEN_MKL_OPENMP) + print_config("Eigen will use MKL and OpenMP" "Yes") +elseif(OPENMP_FOUND AND NOT GTSAM_WITH_EIGEN_MKL) + print_config("Eigen will use MKL and OpenMP" "OpenMP found but GTSAM_WITH_EIGEN_MKL is disabled") +elseif(OPENMP_FOUND AND NOT MKL_FOUND) + print_config("Eigen will use MKL and OpenMP" "OpenMP found but MKL not found") +elseif(OPENMP_FOUND) + print_config("Eigen will use MKL and OpenMP" "OpenMP found but GTSAM_WITH_EIGEN_MKL_OPENMP is disabled") +else() + print_config("Eigen will use MKL and OpenMP" "OpenMP not found") +endif() +print_config("Default allocator" "${GTSAM_DEFAULT_ALLOCATOR}") + +if(GTSAM_THROW_CHEIRALITY_EXCEPTION) + print_config("Cheirality exceptions enabled" "YES") +else() + print_config("Cheirality exceptions enabled" "NO") +endif() + +if(NOT MSVC AND NOT XCODE_VERSION) + if(CCACHE_FOUND AND GTSAM_BUILD_WITH_CCACHE) + print_config("Build with ccache" "Yes") + elseif(CCACHE_FOUND) + print_config("Build with ccache" "ccache found but GTSAM_BUILD_WITH_CCACHE is disabled") + else() + print_config("Build with ccache" "No") + endif() +endif() + +message(STATUS "Packaging flags") +print_config("CPack Source Generator" "${CPACK_SOURCE_GENERATOR}") +print_config("CPack Generator" "${CPACK_GENERATOR}") + +message(STATUS "GTSAM flags ") +print_enabled_config(${GTSAM_USE_QUATERNIONS} "Quaternions as default Rot3 ") +print_enabled_config(${GTSAM_ENABLE_CONSISTENCY_CHECKS} "Runtime consistency checking ") +print_enabled_config(${GTSAM_ROT3_EXPMAP} "Rot3 retract is full ExpMap ") +print_enabled_config(${GTSAM_POSE3_EXPMAP} "Pose3 retract is full ExpMap ") +print_enabled_config(${GTSAM_ALLOW_DEPRECATED_SINCE_V41} "Allow features deprecated in GTSAM 4.1") +print_enabled_config(${GTSAM_SUPPORT_NESTED_DISSECTION} "Metis-based Nested Dissection ") +print_enabled_config(${GTSAM_TANGENT_PREINTEGRATION} "Use tangent-space preintegration") + +message(STATUS "MATLAB toolbox flags") +print_enabled_config(${GTSAM_INSTALL_MATLAB_TOOLBOX} "Install MATLAB toolbox ") +if (${GTSAM_INSTALL_MATLAB_TOOLBOX}) + print_config("MATLAB root" "${MATLAB_ROOT}") + print_config("MEX binary" "${MEX_COMMAND}") +endif() +message(STATUS "Python toolbox flags ") +print_enabled_config(${GTSAM_BUILD_PYTHON} "Build Python module with pybind ") +if(GTSAM_BUILD_PYTHON) + print_config("Python version" ${GTSAM_PYTHON_VERSION}) +endif() + +message(STATUS "===============================================================") diff --git a/cmake/handle_python.cmake b/cmake/handle_python.cmake new file mode 100644 index 000000000..ac7401906 --- /dev/null +++ b/cmake/handle_python.cmake @@ -0,0 +1,26 @@ +if(GTSAM_BUILD_PYTHON) + if(${GTSAM_PYTHON_VERSION} STREQUAL "Default") + # Get info about the Python3 interpreter + # https://cmake.org/cmake/help/latest/module/FindPython3.html#module:FindPython3 + find_package(Python3 COMPONENTS Interpreter Development) + + if(NOT ${Python3_FOUND}) + message(FATAL_ERROR "Cannot find Python3 interpreter. Please install Python >= 3.6.") + endif() + + set(GTSAM_PYTHON_VERSION "${Python3_VERSION_MAJOR}.${Python3_VERSION_MINOR}" + CACHE + STRING + "The version of Python to build the wrappers against." + FORCE) + endif() + + if(GTSAM_UNSTABLE_BUILD_PYTHON) + if (NOT GTSAM_BUILD_UNSTABLE) + message(WARNING "GTSAM_UNSTABLE_BUILD_PYTHON requires the unstable module to be enabled.") + set(GTSAM_UNSTABLE_BUILD_PYTHON OFF) + endif() + endif() + + set(GTSAM_PY_INSTALL_PATH "${CMAKE_INSTALL_PREFIX}/python") +endif() diff --git a/cmake/handle_tbb.cmake b/cmake/handle_tbb.cmake new file mode 100644 index 000000000..cedee55ea --- /dev/null +++ b/cmake/handle_tbb.cmake @@ -0,0 +1,24 @@ +############################################################################### +# Find TBB +find_package(TBB 4.4 COMPONENTS tbb tbbmalloc) + +# Set up variables if we're using TBB +if(TBB_FOUND AND GTSAM_WITH_TBB) + set(GTSAM_USE_TBB 1) # This will go into config.h + if ((${TBB_VERSION_MAJOR} GREATER 2020) OR (${TBB_VERSION_MAJOR} EQUAL 2020)) + set(TBB_GREATER_EQUAL_2020 1) + else() + set(TBB_GREATER_EQUAL_2020 0) + endif() + # all definitions and link requisites will go via imported targets: + # tbb & tbbmalloc + list(APPEND GTSAM_ADDITIONAL_LIBRARIES tbb tbbmalloc) +else() + set(GTSAM_USE_TBB 0) # This will go into config.h +endif() + +############################################################################### +# Prohibit Timing build mode in combination with TBB +if(GTSAM_USE_TBB AND (CMAKE_BUILD_TYPE STREQUAL "Timing")) + message(FATAL_ERROR "Timing build mode cannot be used together with TBB. Use a sampling profiler such as Instruments or Intel VTune Amplifier instead.") +endif() diff --git a/cmake/handle_uninstall.cmake b/cmake/handle_uninstall.cmake new file mode 100644 index 000000000..1859b0273 --- /dev/null +++ b/cmake/handle_uninstall.cmake @@ -0,0 +1,10 @@ +# ---------------------------------------------------------------------------- +# Uninstall target, for "make uninstall" +# ---------------------------------------------------------------------------- +configure_file( + "${CMAKE_CURRENT_SOURCE_DIR}/cmake/cmake_uninstall.cmake.in" + "${CMAKE_CURRENT_BINARY_DIR}/cmake_uninstall.cmake" + IMMEDIATE @ONLY) + +add_custom_target(uninstall + "${CMAKE_COMMAND}" -P "${CMAKE_CURRENT_BINARY_DIR}/cmake_uninstall.cmake") diff --git a/matlab/CMakeLists.txt b/matlab/CMakeLists.txt index 9abd4e31d..52d56a2b5 100644 --- a/matlab/CMakeLists.txt +++ b/matlab/CMakeLists.txt @@ -2,6 +2,10 @@ include(GtsamMatlabWrap) +# Record the root dir for gtsam - needed during external builds, e.g., ROS +set(GTSAM_SOURCE_ROOT_DIR ${GTSAM_SOURCE_DIR}) +message(STATUS "GTSAM_SOURCE_ROOT_DIR: [${GTSAM_SOURCE_ROOT_DIR}]") + # Tests #message(STATUS "Installing Matlab Toolbox") install_matlab_scripts("${GTSAM_SOURCE_ROOT_DIR}/matlab/" "*.m;*.fig") @@ -21,7 +25,7 @@ install_matlab_scripts("${GTSAM_SOURCE_ROOT_DIR}/matlab/" "README-gtsam-toolbox. file(GLOB matlab_examples_data_graph "${GTSAM_SOURCE_ROOT_DIR}/examples/Data/*.graph") file(GLOB matlab_examples_data_mat "${GTSAM_SOURCE_ROOT_DIR}/examples/Data/*.mat") file(GLOB matlab_examples_data_txt "${GTSAM_SOURCE_ROOT_DIR}/examples/Data/*.txt") -set(matlab_examples_data ${matlab_examples_data_graph} ${matlab_examples_data_mat} ${matlab_examples_data_txt}) +set(matlab_examples_data ${matlab_examples_data_graph} ${matlab_examples_data_mat} ${matlab_examples_data_txt}) if(GTSAM_BUILD_TYPE_POSTFIXES) foreach(build_type ${CMAKE_CONFIGURATION_TYPES}) string(TOUPPER "${build_type}" build_type_upper) @@ -38,4 +42,3 @@ if(GTSAM_BUILD_TYPE_POSTFIXES) else() install(FILES ${matlab_examples_data} DESTINATION ${GTSAM_TOOLBOX_INSTALL_PATH}/gtsam_examples/Data) endif() - From 8b2b7476e1d304ac7a09d5315ee13674fe7b5f40 Mon Sep 17 00:00:00 2001 From: Jose Luis Blanco Claraco Date: Tue, 6 Oct 2020 22:58:21 +0200 Subject: [PATCH 07/44] Remove obsolete comments --- cmake/handle_eigen.cmake | 6 ------ 1 file changed, 6 deletions(-) diff --git a/cmake/handle_eigen.cmake b/cmake/handle_eigen.cmake index 690da6971..4aaf4f2ef 100644 --- a/cmake/handle_eigen.cmake +++ b/cmake/handle_eigen.cmake @@ -1,11 +1,5 @@ ############################################################################### # Option for using system Eigen or GTSAM-bundled Eigen -### These patches only affect usage of MKL. If you want to enable MKL, you *must* -### use our patched version of Eigen -### See: http://eigen.tuxfamily.org/bz/show_bug.cgi?id=704 (Householder QR MKL selection) -### http://eigen.tuxfamily.org/bz/show_bug.cgi?id=705 (Fix MKL LLT return code) -option(GTSAM_USE_SYSTEM_EIGEN "Find and use system-installed Eigen. If 'off', use the one bundled with GTSAM" OFF) -option(GTSAM_WITH_EIGEN_UNSUPPORTED "Install Eigen's unsupported modules" OFF) # Switch for using system Eigen or GTSAM-bundled Eigen if(GTSAM_USE_SYSTEM_EIGEN) From b1c2e0174b5cdc20470354b308ff6c2cd2a883d3 Mon Sep 17 00:00:00 2001 From: Jose Luis Blanco Claraco Date: Tue, 6 Oct 2020 22:58:42 +0200 Subject: [PATCH 08/44] Use system eigen3 only if first quietly found. --- cmake/handle_eigen.cmake | 16 ++++++++++++++++ 1 file changed, 16 insertions(+) diff --git a/cmake/handle_eigen.cmake b/cmake/handle_eigen.cmake index 4aaf4f2ef..69111303d 100644 --- a/cmake/handle_eigen.cmake +++ b/cmake/handle_eigen.cmake @@ -1,6 +1,22 @@ ############################################################################### # Option for using system Eigen or GTSAM-bundled Eigen +# Default: Use system Eigen if it's present: +find_package(Eigen3 QUIET) +if (Eigen3_FOUND) + set(SYS_EIGEN3_DEFAULT_ ON) +else() + set(SYS_EIGEN3_DEFAULT_ OFF) +endif() +option(GTSAM_USE_SYSTEM_EIGEN "Find and use system-installed Eigen. If 'off', use the one bundled with GTSAM" ${SYS_EIGEN3_DEFAULT_}) +unset(SYS_EIGEN3_DEFAULT_) + +if(NOT GTSAM_USE_SYSTEM_EIGEN) + # This option only makes sense if using the embedded copy of Eigen, it is + # used to decide whether to *install* the "unsupported" module: + option(GTSAM_WITH_EIGEN_UNSUPPORTED "Install Eigen's unsupported modules" OFF) +endif() + # Switch for using system Eigen or GTSAM-bundled Eigen if(GTSAM_USE_SYSTEM_EIGEN) find_package(Eigen3 REQUIRED) From f9e7c7d942618c346d96704a7f0b0880e526b0a8 Mon Sep 17 00:00:00 2001 From: Fan Jiang Date: Wed, 7 Oct 2020 01:42:57 -0400 Subject: [PATCH 09/44] Squashed 'wrap/' changes from 5e1373486..2192b194e 2192b194e Merge pull request #8 from borglab/fix/serialization 3a3461a35 Fix test ce3d5c35d Fix serialization git-subtree-dir: wrap git-subtree-split: 2192b194edc35142e529adcf50ed5e6803d48975 --- pybind_wrapper.py | 4 ++-- tests/expected-python/geometry_pybind.cpp | 8 ++++---- 2 files changed, 6 insertions(+), 6 deletions(-) diff --git a/pybind_wrapper.py b/pybind_wrapper.py index 3624d06df..8022a2f77 100755 --- a/pybind_wrapper.py +++ b/pybind_wrapper.py @@ -74,8 +74,8 @@ class PybindWrapper(object): ) .def("deserialize", []({class_inst} self, string serialized){{ - return gtsam::deserialize(serialized, self); - }}) + gtsam::deserialize(serialized, *self); + }}, py::arg("serialized")) '''.format(class_inst=cpp_class + '*')) is_method = isinstance(method, instantiator.InstantiatedMethod) diff --git a/tests/expected-python/geometry_pybind.cpp b/tests/expected-python/geometry_pybind.cpp index 6e18f83d7..2cf104d34 100644 --- a/tests/expected-python/geometry_pybind.cpp +++ b/tests/expected-python/geometry_pybind.cpp @@ -45,8 +45,8 @@ PYBIND11_MODULE(geometry_py, m_) { ) .def("deserialize", [](gtsam::Point2* self, string serialized){ - return gtsam::deserialize(serialized, self); - }) + gtsam::deserialize(serialized, *self); + }, py::arg("serialized")) ; py::class_>(m_gtsam, "Point3") @@ -59,8 +59,8 @@ PYBIND11_MODULE(geometry_py, m_) { ) .def("deserialize", [](gtsam::Point3* self, string serialized){ - return gtsam::deserialize(serialized, self); - }) + gtsam::deserialize(serialized, *self); + }, py::arg("serialized")) .def_static("staticFunction",[](){return gtsam::Point3::staticFunction();}) .def_static("StaticFunctionRet",[]( double z){return gtsam::Point3::StaticFunctionRet(z);}, py::arg("z")); From 82d6b8b66b8a667bde4058b3c8d0a149fcaa1414 Mon Sep 17 00:00:00 2001 From: Fan Jiang Date: Wed, 7 Oct 2020 02:29:11 -0400 Subject: [PATCH 10/44] Resurrect serialization tests --- gtsam/geometry/tests/testSerializationGeometry.cpp | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/gtsam/geometry/tests/testSerializationGeometry.cpp b/gtsam/geometry/tests/testSerializationGeometry.cpp index f7ff881eb..aa111c3ae 100644 --- a/gtsam/geometry/tests/testSerializationGeometry.cpp +++ b/gtsam/geometry/tests/testSerializationGeometry.cpp @@ -57,7 +57,7 @@ static StereoCamera cam2(pose3, cal4ptr); static StereoPoint2 spt(1.0, 2.0, 3.0); /* ************************************************************************* */ -TEST_DISABLED (Serialization, text_geometry) { +TEST (Serialization, text_geometry) { EXPECT(equalsObj(Point2(1.0, 2.0))); EXPECT(equalsObj(Pose2(1.0, 2.0, 0.3))); EXPECT(equalsObj(Rot2::fromDegrees(30.0))); @@ -82,7 +82,7 @@ TEST_DISABLED (Serialization, text_geometry) { } /* ************************************************************************* */ -TEST_DISABLED (Serialization, xml_geometry) { +TEST (Serialization, xml_geometry) { EXPECT(equalsXML(Point2(1.0, 2.0))); EXPECT(equalsXML(Pose2(1.0, 2.0, 0.3))); EXPECT(equalsXML(Rot2::fromDegrees(30.0))); @@ -106,7 +106,7 @@ TEST_DISABLED (Serialization, xml_geometry) { } /* ************************************************************************* */ -TEST_DISABLED (Serialization, binary_geometry) { +TEST (Serialization, binary_geometry) { EXPECT(equalsBinary(Point2(1.0, 2.0))); EXPECT(equalsBinary(Pose2(1.0, 2.0, 0.3))); EXPECT(equalsBinary(Rot2::fromDegrees(30.0))); From 114f069f234445bf0f2904c56be58615f3137da3 Mon Sep 17 00:00:00 2001 From: Fan Jiang Date: Wed, 7 Oct 2020 02:29:29 -0400 Subject: [PATCH 11/44] Add unit test for python serdes --- python/gtsam/tests/test_Pose3.py | 8 ++++++++ 1 file changed, 8 insertions(+) diff --git a/python/gtsam/tests/test_Pose3.py b/python/gtsam/tests/test_Pose3.py index 138f1ff13..e07b904a9 100644 --- a/python/gtsam/tests/test_Pose3.py +++ b/python/gtsam/tests/test_Pose3.py @@ -65,6 +65,14 @@ class TestPose3(GtsamTestCase): actual = Pose3.adjoint_(xi, xi) np.testing.assert_array_equal(actual, expected) + def test_serialization(self): + """Test if serialization is working normally""" + expected = Pose3(Rot3.Ypr(0.0, 1.0, 0.0), Point3(1, 1, 0)) + actual = Pose3() + serialized = expected.serialize() + actual.deserialize(serialized) + self.gtsamAssertEquals(expected, actual, 1e-10) + if __name__ == "__main__": unittest.main() From 16418e2fa6493d8a8983ea2b1aaa2aca86ad2bab Mon Sep 17 00:00:00 2001 From: Fan Jiang Date: Wed, 7 Oct 2020 02:29:41 -0400 Subject: [PATCH 12/44] Squashed 'wrap/' changes from 2192b194e..dfa624e77 dfa624e77 Merge pull request #9 from borglab/fix/serialization 7849665a7 Fix serialization git-subtree-dir: wrap git-subtree-split: dfa624e77e24ce3391d23c614d732fc81b4e6193 --- pybind_wrapper.py | 2 +- tests/expected-python/geometry_pybind.cpp | 4 ++-- 2 files changed, 3 insertions(+), 3 deletions(-) diff --git a/pybind_wrapper.py b/pybind_wrapper.py index 8022a2f77..326d9be52 100755 --- a/pybind_wrapper.py +++ b/pybind_wrapper.py @@ -69,7 +69,7 @@ class PybindWrapper(object): return textwrap.dedent(''' .def("serialize", []({class_inst} self){{ - return gtsam::serialize(self); + return gtsam::serialize(*self); }} ) .def("deserialize", diff --git a/tests/expected-python/geometry_pybind.cpp b/tests/expected-python/geometry_pybind.cpp index 2cf104d34..3eee55bf4 100644 --- a/tests/expected-python/geometry_pybind.cpp +++ b/tests/expected-python/geometry_pybind.cpp @@ -40,7 +40,7 @@ PYBIND11_MODULE(geometry_py, m_) { .def("vectorConfusion",[](gtsam::Point2* self){return self->vectorConfusion();}) .def("serialize", [](gtsam::Point2* self){ - return gtsam::serialize(self); + return gtsam::serialize(*self); } ) .def("deserialize", @@ -54,7 +54,7 @@ PYBIND11_MODULE(geometry_py, m_) { .def("norm",[](gtsam::Point3* self){return self->norm();}) .def("serialize", [](gtsam::Point3* self){ - return gtsam::serialize(self); + return gtsam::serialize(*self); } ) .def("deserialize", From 8cb22624e0520315f402cf2255857301634a9041 Mon Sep 17 00:00:00 2001 From: Jose Luis Blanco Claraco Date: Wed, 7 Oct 2020 17:02:39 +0200 Subject: [PATCH 13/44] Use camel case for cmake files --- CMakeLists.txt | 30 +++++++++---------- ...llocators.cmake => HandleAllocators.cmake} | 0 .../{handle_boost.cmake => HandleBoost.cmake} | 0 ...handle_ccache.cmake => HandleCCache.cmake} | 0 .../{handle_cpack.cmake => HandleCPack.cmake} | 0 .../{handle_eigen.cmake => HandleEigen.cmake} | 0 ...l_checks.cmake => HandleFinalChecks.cmake} | 0 ...tions.cmake => HandleGeneralOptions.cmake} | 0 ...ags.cmake => HandleGlobalBuildFlags.cmake} | 0 cmake/{handle_mkl.cmake => HandleMKL.cmake} | 0 ...handle_openmp.cmake => HandleOpenMP.cmake} | 0 ..._perftools.cmake => HandlePerfTools.cmake} | 0 ...n.cmake => HandlePrintConfiguration.cmake} | 0 ...handle_python.cmake => HandlePython.cmake} | 0 cmake/{handle_tbb.cmake => HandleTBB.cmake} | 0 ..._uninstall.cmake => HandleUninstall.cmake} | 0 16 files changed, 15 insertions(+), 15 deletions(-) rename cmake/{handle_allocators.cmake => HandleAllocators.cmake} (100%) rename cmake/{handle_boost.cmake => HandleBoost.cmake} (100%) rename cmake/{handle_ccache.cmake => HandleCCache.cmake} (100%) rename cmake/{handle_cpack.cmake => HandleCPack.cmake} (100%) rename cmake/{handle_eigen.cmake => HandleEigen.cmake} (100%) rename cmake/{handle_final_checks.cmake => HandleFinalChecks.cmake} (100%) rename cmake/{handle_general_options.cmake => HandleGeneralOptions.cmake} (100%) rename cmake/{handle_global_build_flags.cmake => HandleGlobalBuildFlags.cmake} (100%) rename cmake/{handle_mkl.cmake => HandleMKL.cmake} (100%) rename cmake/{handle_openmp.cmake => HandleOpenMP.cmake} (100%) rename cmake/{handle_perftools.cmake => HandlePerfTools.cmake} (100%) rename cmake/{handle_print_configuration.cmake => HandlePrintConfiguration.cmake} (100%) rename cmake/{handle_python.cmake => HandlePython.cmake} (100%) rename cmake/{handle_tbb.cmake => HandleTBB.cmake} (100%) rename cmake/{handle_uninstall.cmake => HandleUninstall.cmake} (100%) diff --git a/CMakeLists.txt b/CMakeLists.txt index 831ee00f3..35c487fd3 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -38,21 +38,21 @@ if(${CMAKE_SOURCE_DIR} STREQUAL ${CMAKE_BINARY_DIR}) message(FATAL_ERROR "In-source builds not allowed. Please make a new directory (called a build directory) and run CMake from there. You may need to remove CMakeCache.txt. ") endif() -include(cmake/handle_boost.cmake) # Boost -include(cmake/handle_ccache.cmake) # ccache -include(cmake/handle_cpack.cmake) # CPack -include(cmake/handle_eigen.cmake) # Eigen3 -include(cmake/handle_general_options.cmake) # CMake build options -include(cmake/handle_mkl.cmake) # MKL -include(cmake/handle_openmp.cmake) # OpenMP -include(cmake/handle_perftools.cmake) # Google perftools -include(cmake/handle_python.cmake) # Python options and commands -include(cmake/handle_tbb.cmake) # TBB -include(cmake/handle_uninstall.cmake) # for "make uninstall" +include(cmake/HandleBoost.cmake) # Boost +include(cmake/HandleCCache.cmake) # ccache +include(cmake/HandleCPack.cmake) # CPack +include(cmake/HandleEigen.cmake) # Eigen3 +include(cmake/HandleGeneralOptions.cmake) # CMake build options +include(cmake/HandleMKL.cmake) # MKL +include(cmake/HandleOpenMP.cmake) # OpenMP +include(cmake/HandlePerfTools.cmake) # Google perftools +include(cmake/HandlePython.cmake) # Python options and commands +include(cmake/HandleTBB.cmake) # TBB +include(cmake/HandleUninstall.cmake) # for "make uninstall" -include(cmake/handle_allocators.cmake) # Must be after tbb, pertools +include(cmake/HandleAllocators.cmake) # Must be after tbb, pertools -include(cmake/handle_global_build_flags.cmake) # Build flags +include(cmake/HandleGlobalBuildFlags.cmake) # Build flags ############################################################################### # Add components @@ -104,10 +104,10 @@ endif() add_subdirectory(cmake) # Print configuration variables -include(cmake/handle_print_configuration.cmake) +include(cmake/HandlePrintConfiguration.cmake) # Print warnings at the end -include(cmake/handle_final_checks.cmake) +include(cmake/HandleFinalChecks.cmake) # Include CPack *after* all flags include(CPack) diff --git a/cmake/handle_allocators.cmake b/cmake/HandleAllocators.cmake similarity index 100% rename from cmake/handle_allocators.cmake rename to cmake/HandleAllocators.cmake diff --git a/cmake/handle_boost.cmake b/cmake/HandleBoost.cmake similarity index 100% rename from cmake/handle_boost.cmake rename to cmake/HandleBoost.cmake diff --git a/cmake/handle_ccache.cmake b/cmake/HandleCCache.cmake similarity index 100% rename from cmake/handle_ccache.cmake rename to cmake/HandleCCache.cmake diff --git a/cmake/handle_cpack.cmake b/cmake/HandleCPack.cmake similarity index 100% rename from cmake/handle_cpack.cmake rename to cmake/HandleCPack.cmake diff --git a/cmake/handle_eigen.cmake b/cmake/HandleEigen.cmake similarity index 100% rename from cmake/handle_eigen.cmake rename to cmake/HandleEigen.cmake diff --git a/cmake/handle_final_checks.cmake b/cmake/HandleFinalChecks.cmake similarity index 100% rename from cmake/handle_final_checks.cmake rename to cmake/HandleFinalChecks.cmake diff --git a/cmake/handle_general_options.cmake b/cmake/HandleGeneralOptions.cmake similarity index 100% rename from cmake/handle_general_options.cmake rename to cmake/HandleGeneralOptions.cmake diff --git a/cmake/handle_global_build_flags.cmake b/cmake/HandleGlobalBuildFlags.cmake similarity index 100% rename from cmake/handle_global_build_flags.cmake rename to cmake/HandleGlobalBuildFlags.cmake diff --git a/cmake/handle_mkl.cmake b/cmake/HandleMKL.cmake similarity index 100% rename from cmake/handle_mkl.cmake rename to cmake/HandleMKL.cmake diff --git a/cmake/handle_openmp.cmake b/cmake/HandleOpenMP.cmake similarity index 100% rename from cmake/handle_openmp.cmake rename to cmake/HandleOpenMP.cmake diff --git a/cmake/handle_perftools.cmake b/cmake/HandlePerfTools.cmake similarity index 100% rename from cmake/handle_perftools.cmake rename to cmake/HandlePerfTools.cmake diff --git a/cmake/handle_print_configuration.cmake b/cmake/HandlePrintConfiguration.cmake similarity index 100% rename from cmake/handle_print_configuration.cmake rename to cmake/HandlePrintConfiguration.cmake diff --git a/cmake/handle_python.cmake b/cmake/HandlePython.cmake similarity index 100% rename from cmake/handle_python.cmake rename to cmake/HandlePython.cmake diff --git a/cmake/handle_tbb.cmake b/cmake/HandleTBB.cmake similarity index 100% rename from cmake/handle_tbb.cmake rename to cmake/HandleTBB.cmake diff --git a/cmake/handle_uninstall.cmake b/cmake/HandleUninstall.cmake similarity index 100% rename from cmake/handle_uninstall.cmake rename to cmake/HandleUninstall.cmake From 69b2cacbe7d408e92de011a82116007bcf03f590 Mon Sep 17 00:00:00 2001 From: Jose Luis Blanco Claraco Date: Wed, 7 Oct 2020 17:03:20 +0200 Subject: [PATCH 14/44] Revert use system Eigen if found --- cmake/HandleEigen.cmake | 10 +--------- 1 file changed, 1 insertion(+), 9 deletions(-) diff --git a/cmake/HandleEigen.cmake b/cmake/HandleEigen.cmake index 69111303d..fda441907 100644 --- a/cmake/HandleEigen.cmake +++ b/cmake/HandleEigen.cmake @@ -1,15 +1,7 @@ ############################################################################### # Option for using system Eigen or GTSAM-bundled Eigen -# Default: Use system Eigen if it's present: -find_package(Eigen3 QUIET) -if (Eigen3_FOUND) - set(SYS_EIGEN3_DEFAULT_ ON) -else() - set(SYS_EIGEN3_DEFAULT_ OFF) -endif() -option(GTSAM_USE_SYSTEM_EIGEN "Find and use system-installed Eigen. If 'off', use the one bundled with GTSAM" ${SYS_EIGEN3_DEFAULT_}) -unset(SYS_EIGEN3_DEFAULT_) +option(GTSAM_USE_SYSTEM_EIGEN "Find and use system-installed Eigen. If 'off', use the one bundled with GTSAM" OFF) if(NOT GTSAM_USE_SYSTEM_EIGEN) # This option only makes sense if using the embedded copy of Eigen, it is From 93825d0bc72a7d1764e1c9a5f3d8431132c8e63b Mon Sep 17 00:00:00 2001 From: Akshay Krishnan Date: Thu, 8 Oct 2020 07:23:35 +0000 Subject: [PATCH 15/44] Wrapping SfmCamera to be used with GeneralSFMFactor --- gtsam/gtsam.i | 16 ++++++++-------- python/gtsam/examples/SFMExample_bal.py | 9 ++++----- 2 files changed, 12 insertions(+), 13 deletions(-) diff --git a/gtsam/gtsam.i b/gtsam/gtsam.i index 1a239541d..6665a532e 100644 --- a/gtsam/gtsam.i +++ b/gtsam/gtsam.i @@ -1106,8 +1106,7 @@ typedef gtsam::PinholeCamera PinholeCameraCal3_S2; //TODO (Issue 237) due to lack of jacobians of Cal3DS2_Base::calibrate, PinholeCamera does not apply to Cal3DS2/Unified //typedef gtsam::PinholeCamera PinholeCameraCal3DS2; //typedef gtsam::PinholeCamera PinholeCameraCal3Unified; -typedef gtsam::PinholeCamera PinholeCameraCal3Bundler; -//typedef gtsam::PinholeCamera SfmCamera; +typedef gtsam::PinholeCamera SfmCamera; #include class StereoCamera { @@ -2069,7 +2068,7 @@ class NonlinearFactorGraph { gtsam::KeySet keys() const; gtsam::KeyVector keyVector() const; - template + template void addPrior(size_t key, const T& prior, const gtsam::noiseModel::Base* noiseModel); // NonlinearFactorGraph @@ -2163,7 +2162,7 @@ class Values { void insert(size_t j, const gtsam::Cal3Bundler& cal3bundler); void insert(size_t j, const gtsam::EssentialMatrix& essential_matrix); void insert(size_t j, const gtsam::PinholeCameraCal3_S2& simple_camera); - // void insert(size_t j, const gtsam::PinholeCameraCal3Bundler& camera); + void insert(size_t j, const gtsam::SfmCamera& camera); void insert(size_t j, const gtsam::imuBias::ConstantBias& constant_bias); void insert(size_t j, const gtsam::NavState& nav_state); @@ -2181,13 +2180,13 @@ class Values { void update(size_t j, const gtsam::Cal3Bundler& cal3bundler); void update(size_t j, const gtsam::EssentialMatrix& essential_matrix); void update(size_t j, const gtsam::PinholeCameraCal3_S2& simple_camera); - // void update(size_t j, const gtsam::PinholeCameraCal3Bundler& camera); + void update(size_t j, const gtsam::SfmCamera& camera); void update(size_t j, const gtsam::imuBias::ConstantBias& constant_bias); void update(size_t j, const gtsam::NavState& nav_state); void update(size_t j, Vector vector); void update(size_t j, Matrix matrix); - template + template T at(size_t j); /// version for double @@ -2491,7 +2490,8 @@ class ISAM2 { template + gtsam::SimpleCamera, gtsam::PinholeCameraCal3_S2, gtsam::SfmCamera, + Vector, Matrix}> VALUE calculateEstimate(size_t key) const; gtsam::Values calculateBestEstimate() const; Matrix marginalCovariance(size_t key) const; @@ -2674,7 +2674,7 @@ virtual class GeneralSFMFactor : gtsam::NoiseModelFactor { typedef gtsam::GeneralSFMFactor GeneralSFMFactorCal3_S2; //TODO (Issue 237) due to lack of jacobians of Cal3DS2_Base::calibrate, GeneralSFMFactor does not apply to Cal3DS2 //typedef gtsam::GeneralSFMFactor GeneralSFMFactorCal3DS2; -//typedef gtsam::GeneralSFMFactor GeneralSFMFactorCal3Bundler; +typedef gtsam::GeneralSFMFactor GeneralSFMFactorSfmCamera; template diff --git a/python/gtsam/examples/SFMExample_bal.py b/python/gtsam/examples/SFMExample_bal.py index 258ec8917..a5cbcf05f 100644 --- a/python/gtsam/examples/SFMExample_bal.py +++ b/python/gtsam/examples/SFMExample_bal.py @@ -18,8 +18,8 @@ import numpy as np import gtsam from gtsam import ( - #GeneralSFMFactorCal3Bundler, - PinholeCameraCal3Bundler, + GeneralSFMFactorSfmCamera, + SfmCamera, PriorFactorSfmCamera, readBal, symbol_shorthand @@ -31,7 +31,7 @@ P = symbol_shorthand.P import pdb # We will be using a projection factor that ties a SFM_Camera to a 3D point. -# An SFM_Camera is defined in dataset.h as a camera with unknown Cal3Bundler calibration +# An SfmCamera is defined in dataset.h as a pinhole camera with unknown Cal3Bundler calibration # and has a total of 9 free parameters def run(args): @@ -63,7 +63,7 @@ def run(args): # i represents the camera index, and uv is the 2d measurement i, uv = track.measurement(m_idx) # note use of shorthand symbols C and P - #graph.add(GeneralSFMFactorCal3Bundler(uv, noise, C(i), P(j))) + graph.add(GeneralSFMFactorSfmCamera(uv, noise, C(i), P(j))) j += 1 pdb.set_trace() @@ -118,4 +118,3 @@ if __name__ == "__main__": - From c97af55c63534646f2bd026379d40a6155c2dcd6 Mon Sep 17 00:00:00 2001 From: John Lambert Date: Fri, 9 Oct 2020 23:33:53 -0400 Subject: [PATCH 16/44] remove breakpoints --- python/gtsam/examples/SFMExample_bal.py | 9 ++++----- 1 file changed, 4 insertions(+), 5 deletions(-) diff --git a/python/gtsam/examples/SFMExample_bal.py b/python/gtsam/examples/SFMExample_bal.py index a5cbcf05f..169cf9f3c 100644 --- a/python/gtsam/examples/SFMExample_bal.py +++ b/python/gtsam/examples/SFMExample_bal.py @@ -7,11 +7,12 @@ See LICENSE for the license information Solve a structure-from-motion problem from a "Bundle Adjustment in the Large" file - Author: John Lambert + Author: Frank Dellaert (Python: Akshay Krishan, John Lambert) """ import argparse import logging +import sys import matplotlib.pyplot as plt import numpy as np @@ -28,7 +29,8 @@ from gtsam import ( C = symbol_shorthand.C P = symbol_shorthand.P -import pdb + +logging.basicConfig(stream=sys.stdout, level=logging.DEBUG) # We will be using a projection factor that ties a SFM_Camera to a 3D point. # An SfmCamera is defined in dataset.h as a pinhole camera with unknown Cal3Bundler calibration @@ -42,7 +44,6 @@ def run(args): else: input_file = gtsam.findExampleDataFile("dubrovnik-3-7-pre") - pdb.set_trace() # # Load the SfM data from file mydata = readBal(input_file) logging.info(f"read {mydata.number_tracks()} tracks on {mydata.number_cameras()} cameras\n") @@ -55,7 +56,6 @@ def run(args): # Add measurements to the factor graph j = 0 - pdb.set_trace() for t_idx in range(mydata.number_tracks()): track = mydata.track(t_idx) # SfmTrack # retrieve the SfmMeasurement objects @@ -65,7 +65,6 @@ def run(args): # note use of shorthand symbols C and P graph.add(GeneralSFMFactorSfmCamera(uv, noise, C(i), P(j))) j += 1 - pdb.set_trace() # # Add a prior on pose x1. This indirectly specifies where the origin is. # # and a prior on the position of the first landmark to fix the scale From ac9077ff67f5ca36790203ac417982e9e88a52e4 Mon Sep 17 00:00:00 2001 From: Akshay Krishnan Date: Sat, 10 Oct 2020 08:57:09 +0000 Subject: [PATCH 17/44] Renaming SFMCamera to PinholeCameraCal3Bundler --- gtsam/gtsam.i | 17 ++++++++--------- python/gtsam/examples/SFMExample_bal.py | 16 ++++++---------- 2 files changed, 14 insertions(+), 19 deletions(-) diff --git a/gtsam/gtsam.i b/gtsam/gtsam.i index 6665a532e..2a513322d 100644 --- a/gtsam/gtsam.i +++ b/gtsam/gtsam.i @@ -1106,7 +1106,7 @@ typedef gtsam::PinholeCamera PinholeCameraCal3_S2; //TODO (Issue 237) due to lack of jacobians of Cal3DS2_Base::calibrate, PinholeCamera does not apply to Cal3DS2/Unified //typedef gtsam::PinholeCamera PinholeCameraCal3DS2; //typedef gtsam::PinholeCamera PinholeCameraCal3Unified; -typedef gtsam::PinholeCamera SfmCamera; +typedef gtsam::PinholeCamera PinholeCameraCal3Bundler; #include class StereoCamera { @@ -2068,7 +2068,7 @@ class NonlinearFactorGraph { gtsam::KeySet keys() const; gtsam::KeyVector keyVector() const; - template + template, gtsam::imuBias::ConstantBias}> void addPrior(size_t key, const T& prior, const gtsam::noiseModel::Base* noiseModel); // NonlinearFactorGraph @@ -2162,7 +2162,7 @@ class Values { void insert(size_t j, const gtsam::Cal3Bundler& cal3bundler); void insert(size_t j, const gtsam::EssentialMatrix& essential_matrix); void insert(size_t j, const gtsam::PinholeCameraCal3_S2& simple_camera); - void insert(size_t j, const gtsam::SfmCamera& camera); + void insert(size_t j, const gtsam::PinholeCamera& camera); void insert(size_t j, const gtsam::imuBias::ConstantBias& constant_bias); void insert(size_t j, const gtsam::NavState& nav_state); @@ -2180,13 +2180,13 @@ class Values { void update(size_t j, const gtsam::Cal3Bundler& cal3bundler); void update(size_t j, const gtsam::EssentialMatrix& essential_matrix); void update(size_t j, const gtsam::PinholeCameraCal3_S2& simple_camera); - void update(size_t j, const gtsam::SfmCamera& camera); + void update(size_t j, const gtsam::PinholeCamera& camera); void update(size_t j, const gtsam::imuBias::ConstantBias& constant_bias); void update(size_t j, const gtsam::NavState& nav_state); void update(size_t j, Vector vector); void update(size_t j, Matrix matrix); - template + template, gtsam::imuBias::ConstantBias, gtsam::NavState, Vector, Matrix}> T at(size_t j); /// version for double @@ -2490,7 +2490,7 @@ class ISAM2 { template , Vector, Matrix}> VALUE calculateEstimate(size_t key) const; gtsam::Values calculateBestEstimate() const; @@ -2529,7 +2529,7 @@ class NonlinearISAM { #include #include -template +template}> virtual class PriorFactor : gtsam::NoiseModelFactor { PriorFactor(size_t key, const T& prior, const gtsam::noiseModel::Base* noiseModel); T prior() const; @@ -2674,8 +2674,7 @@ virtual class GeneralSFMFactor : gtsam::NoiseModelFactor { typedef gtsam::GeneralSFMFactor GeneralSFMFactorCal3_S2; //TODO (Issue 237) due to lack of jacobians of Cal3DS2_Base::calibrate, GeneralSFMFactor does not apply to Cal3DS2 //typedef gtsam::GeneralSFMFactor GeneralSFMFactorCal3DS2; -typedef gtsam::GeneralSFMFactor GeneralSFMFactorSfmCamera; - +typedef gtsam::GeneralSFMFactor, gtsam::Point3> GeneralSFMFactorCal3Bundler; template virtual class GeneralSFMFactor2 : gtsam::NoiseModelFactor { diff --git a/python/gtsam/examples/SFMExample_bal.py b/python/gtsam/examples/SFMExample_bal.py index 169cf9f3c..a027dac89 100644 --- a/python/gtsam/examples/SFMExample_bal.py +++ b/python/gtsam/examples/SFMExample_bal.py @@ -19,9 +19,9 @@ import numpy as np import gtsam from gtsam import ( - GeneralSFMFactorSfmCamera, - SfmCamera, - PriorFactorSfmCamera, + GeneralSFMFactorCal3Bundler, + PinholeCameraCal3Bundler, + PriorFactorPinholeCameraCal3Bundler, readBal, symbol_shorthand ) @@ -32,10 +32,6 @@ P = symbol_shorthand.P logging.basicConfig(stream=sys.stdout, level=logging.DEBUG) -# We will be using a projection factor that ties a SFM_Camera to a 3D point. -# An SfmCamera is defined in dataset.h as a pinhole camera with unknown Cal3Bundler calibration -# and has a total of 9 free parameters - def run(args): """ Run LM optimization with BAL input data and report resulting error """ # Find default file, but if an argument is given, try loading a file @@ -63,13 +59,13 @@ def run(args): # i represents the camera index, and uv is the 2d measurement i, uv = track.measurement(m_idx) # note use of shorthand symbols C and P - graph.add(GeneralSFMFactorSfmCamera(uv, noise, C(i), P(j))) + graph.add(GeneralSFMFactorCal3Bundler(uv, noise, C(i), P(j))) j += 1 # # Add a prior on pose x1. This indirectly specifies where the origin is. # # and a prior on the position of the first landmark to fix the scale graph.push_back( - gtsam.PriorFactorSfmCamera( + gtsam.PriorFactorPinholeCameraCal3Bundler( C(0), mydata.camera(0), gtsam.noiseModel.Isotropic.Sigma(9, 0.1) ) ) @@ -83,7 +79,7 @@ def run(args): initial = gtsam.Values() i = 0 - # add each SfmCamera + # add each PinholeCameraCal3Bundler for cam_idx in range(mydata.number_cameras()): camera = mydata.camera(cam_idx) initial.insert(C(i), camera) From d4c801bb6bff04f924edccc847f97359b0906217 Mon Sep 17 00:00:00 2001 From: Fan Jiang Date: Sat, 10 Oct 2020 12:39:05 -0400 Subject: [PATCH 18/44] Fix LLVM repo keys --- .github/workflows/build-linux.yml | 2 ++ .github/workflows/build-python.yml | 2 ++ .github/workflows/build-special.yml | 2 ++ 3 files changed, 6 insertions(+) diff --git a/.github/workflows/build-linux.yml b/.github/workflows/build-linux.yml index afe328c3b..7553675c8 100644 --- a/.github/workflows/build-linux.yml +++ b/.github/workflows/build-linux.yml @@ -50,6 +50,8 @@ jobs: run: | # LLVM 9 is not in Bionic's repositories so we add the official LLVM repository. if [ "${{ matrix.compiler }}" = "clang" ] && [ "${{ matrix.version }}" = "9" ]; then + gpg --keyserver pool.sks-keyservers.net --recv-key 15CF4D18AF4F7421 + gpg -a --export 15CF4D18AF4F7421 | sudo apt-key add - sudo add-apt-repository "deb http://apt.llvm.org/bionic/ llvm-toolchain-bionic-9 main" fi sudo apt-get -y update diff --git a/.github/workflows/build-python.yml b/.github/workflows/build-python.yml index b8d6bc311..d4796e2bb 100644 --- a/.github/workflows/build-python.yml +++ b/.github/workflows/build-python.yml @@ -63,6 +63,8 @@ jobs: run: | # LLVM 9 is not in Bionic's repositories so we add the official LLVM repository. if [ "${{ matrix.compiler }}" = "clang" ] && [ "${{ matrix.version }}" = "9" ]; then + gpg --keyserver pool.sks-keyservers.net --recv-key 15CF4D18AF4F7421 + gpg -a --export 15CF4D18AF4F7421 | sudo apt-key add - sudo add-apt-repository "deb http://apt.llvm.org/bionic/ llvm-toolchain-bionic-9 main" fi sudo apt-get -y update diff --git a/.github/workflows/build-special.yml b/.github/workflows/build-special.yml index 648365f24..c314acb16 100644 --- a/.github/workflows/build-special.yml +++ b/.github/workflows/build-special.yml @@ -56,6 +56,8 @@ jobs: run: | # LLVM 9 is not in Bionic's repositories so we add the official LLVM repository. if [ "${{ matrix.compiler }}" = "clang" ] && [ "${{ matrix.version }}" = "9" ]; then + gpg --keyserver pool.sks-keyservers.net --recv-key 15CF4D18AF4F7421 + gpg -a --export 15CF4D18AF4F7421 | sudo apt-key add - sudo add-apt-repository "deb http://apt.llvm.org/bionic/ llvm-toolchain-bionic-9 main" fi sudo apt-get -y update From 22e64ac82d6dee47ba3640b442d3e0c85d4997ee Mon Sep 17 00:00:00 2001 From: Fan Jiang Date: Mon, 12 Oct 2020 11:54:24 -0400 Subject: [PATCH 19/44] Add comments --- .github/workflows/build-linux.yml | 3 ++- .github/workflows/build-python.yml | 3 ++- 2 files changed, 4 insertions(+), 2 deletions(-) diff --git a/.github/workflows/build-linux.yml b/.github/workflows/build-linux.yml index 7553675c8..2195ad05c 100644 --- a/.github/workflows/build-linux.yml +++ b/.github/workflows/build-linux.yml @@ -48,8 +48,9 @@ jobs: - name: Install (Linux) if: runner.os == 'Linux' run: | - # LLVM 9 is not in Bionic's repositories so we add the official LLVM repository. + # LLVM (clang) 9 is not in Bionic's repositories so we add the official LLVM repository. if [ "${{ matrix.compiler }}" = "clang" ] && [ "${{ matrix.version }}" = "9" ]; then + # 15CF4D18AF4F7421 is the GPG key for the LLVM apt repository gpg --keyserver pool.sks-keyservers.net --recv-key 15CF4D18AF4F7421 gpg -a --export 15CF4D18AF4F7421 | sudo apt-key add - sudo add-apt-repository "deb http://apt.llvm.org/bionic/ llvm-toolchain-bionic-9 main" diff --git a/.github/workflows/build-python.yml b/.github/workflows/build-python.yml index d4796e2bb..e348e3125 100644 --- a/.github/workflows/build-python.yml +++ b/.github/workflows/build-python.yml @@ -61,8 +61,9 @@ jobs: - name: Install (Linux) if: runner.os == 'Linux' run: | - # LLVM 9 is not in Bionic's repositories so we add the official LLVM repository. + # LLVM (clang) 9 is not in Bionic's repositories so we add the official LLVM repository. if [ "${{ matrix.compiler }}" = "clang" ] && [ "${{ matrix.version }}" = "9" ]; then + # 15CF4D18AF4F7421 is the GPG key for the LLVM apt repository gpg --keyserver pool.sks-keyservers.net --recv-key 15CF4D18AF4F7421 gpg -a --export 15CF4D18AF4F7421 | sudo apt-key add - sudo add-apt-repository "deb http://apt.llvm.org/bionic/ llvm-toolchain-bionic-9 main" From 8a7ce130ad99bf0054c8786d2f516ebb99a91545 Mon Sep 17 00:00:00 2001 From: Frank dellaert Date: Mon, 12 Oct 2020 14:32:21 -0400 Subject: [PATCH 20/44] Fix warning on clang --- cmake/GtsamBuildTypes.cmake | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/cmake/GtsamBuildTypes.cmake b/cmake/GtsamBuildTypes.cmake index 840d37427..d13e3aa12 100644 --- a/cmake/GtsamBuildTypes.cmake +++ b/cmake/GtsamBuildTypes.cmake @@ -109,7 +109,7 @@ else() ((CMAKE_CXX_COMPILER_ID MATCHES "Clang") AND (NOT CMAKE_CXX_COMPILER_VERSION VERSION_LESS 12.0.0)) OR (CMAKE_CXX_COMPILER_ID MATCHES "GNU") ) - set(flag_override_ -Wsuggest-override) # -Werror=suggest-override: Add again someday + # set(flag_override_ -Wsuggest-override) # -Werror=suggest-override: Add again someday endif() set(GTSAM_COMPILE_OPTIONS_PRIVATE_COMMON From 25d801bd15eeda8244b36ae384eb8c5d318966db Mon Sep 17 00:00:00 2001 From: John Lambert Date: Wed, 14 Oct 2020 15:22:23 -0400 Subject: [PATCH 21/44] use argparse defaults --- python/gtsam/examples/SFMExample_bal.py | 12 ++++-------- 1 file changed, 4 insertions(+), 8 deletions(-) diff --git a/python/gtsam/examples/SFMExample_bal.py b/python/gtsam/examples/SFMExample_bal.py index a027dac89..eda143011 100644 --- a/python/gtsam/examples/SFMExample_bal.py +++ b/python/gtsam/examples/SFMExample_bal.py @@ -34,11 +34,7 @@ logging.basicConfig(stream=sys.stdout, level=logging.DEBUG) def run(args): """ Run LM optimization with BAL input data and report resulting error """ - # Find default file, but if an argument is given, try loading a file - if args.input_file: - input_file = args.input_file - else: - input_file = gtsam.findExampleDataFile("dubrovnik-3-7-pre") + input_file = gtsam.findExampleDataFile(args.input_file) # # Load the SfM data from file mydata = readBal(input_file) @@ -62,13 +58,13 @@ def run(args): graph.add(GeneralSFMFactorCal3Bundler(uv, noise, C(i), P(j))) j += 1 - # # Add a prior on pose x1. This indirectly specifies where the origin is. - # # and a prior on the position of the first landmark to fix the scale + # Add a prior on pose x1. This indirectly specifies where the origin is. graph.push_back( gtsam.PriorFactorPinholeCameraCal3Bundler( C(0), mydata.camera(0), gtsam.noiseModel.Isotropic.Sigma(9, 0.1) ) ) + # Also add a prior on the position of the first landmark to fix the scale graph.push_back( gtsam.PriorFactorPoint3( P(0), mydata.track(0).point3(), gtsam.noiseModel.Isotropic.Sigma(3, 0.1) @@ -107,7 +103,7 @@ def run(args): if __name__ == "__main__": parser = argparse.ArgumentParser() - parser.add_argument('-i', '--input_file', type=str, default="", + parser.add_argument('-i', '--input_file', type=str, default="dubrovnik-3-7-pre", help='Read SFM data from the specified BAL file') run(parser.parse_args()) From c9d719cb1f2992c10d43afa48ebb5c2206e142f0 Mon Sep 17 00:00:00 2001 From: John Lambert Date: Wed, 14 Oct 2020 16:03:14 -0400 Subject: [PATCH 22/44] make a note about how the eror drops --- python/gtsam/examples/SFMExample_bal.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/python/gtsam/examples/SFMExample_bal.py b/python/gtsam/examples/SFMExample_bal.py index eda143011..b5701669e 100644 --- a/python/gtsam/examples/SFMExample_bal.py +++ b/python/gtsam/examples/SFMExample_bal.py @@ -97,7 +97,7 @@ def run(args): except Exception as e: logging.exception("LM Optimization failed") return - + # Error drops from 2764.22 to 0.046 logging.info(f"final error: {graph.error(result)}") From d4bdaf80800487e96c56f59d748833598f1cecff Mon Sep 17 00:00:00 2001 From: Fan Jiang Date: Wed, 14 Oct 2020 16:42:54 -0400 Subject: [PATCH 23/44] Add comments --- .github/workflows/build-linux.yml | 1 + .github/workflows/build-python.yml | 1 + 2 files changed, 2 insertions(+) diff --git a/.github/workflows/build-linux.yml b/.github/workflows/build-linux.yml index 2195ad05c..7aa818d04 100644 --- a/.github/workflows/build-linux.yml +++ b/.github/workflows/build-linux.yml @@ -50,6 +50,7 @@ jobs: run: | # LLVM (clang) 9 is not in Bionic's repositories so we add the official LLVM repository. if [ "${{ matrix.compiler }}" = "clang" ] && [ "${{ matrix.version }}" = "9" ]; then + # pool.sks-keyservers.net is the SKS GPG global keyserver pool # 15CF4D18AF4F7421 is the GPG key for the LLVM apt repository gpg --keyserver pool.sks-keyservers.net --recv-key 15CF4D18AF4F7421 gpg -a --export 15CF4D18AF4F7421 | sudo apt-key add - diff --git a/.github/workflows/build-python.yml b/.github/workflows/build-python.yml index e348e3125..5b9f7418b 100644 --- a/.github/workflows/build-python.yml +++ b/.github/workflows/build-python.yml @@ -63,6 +63,7 @@ jobs: run: | # LLVM (clang) 9 is not in Bionic's repositories so we add the official LLVM repository. if [ "${{ matrix.compiler }}" = "clang" ] && [ "${{ matrix.version }}" = "9" ]; then + # pool.sks-keyservers.net is the SKS GPG global keyserver pool # 15CF4D18AF4F7421 is the GPG key for the LLVM apt repository gpg --keyserver pool.sks-keyservers.net --recv-key 15CF4D18AF4F7421 gpg -a --export 15CF4D18AF4F7421 | sudo apt-key add - From 2b8e9f44fada685d7b73fd47d84c15b35b449785 Mon Sep 17 00:00:00 2001 From: Fan Jiang Date: Wed, 14 Oct 2020 16:44:28 -0400 Subject: [PATCH 24/44] Add comments --- .github/workflows/build-linux.yml | 1 + .github/workflows/build-python.yml | 1 + 2 files changed, 2 insertions(+) diff --git a/.github/workflows/build-linux.yml b/.github/workflows/build-linux.yml index 7aa818d04..d90aad13c 100644 --- a/.github/workflows/build-linux.yml +++ b/.github/workflows/build-linux.yml @@ -52,6 +52,7 @@ jobs: if [ "${{ matrix.compiler }}" = "clang" ] && [ "${{ matrix.version }}" = "9" ]; then # pool.sks-keyservers.net is the SKS GPG global keyserver pool # 15CF4D18AF4F7421 is the GPG key for the LLVM apt repository + # This key is not in the keystore by default for Ubuntu so we need to add it. gpg --keyserver pool.sks-keyservers.net --recv-key 15CF4D18AF4F7421 gpg -a --export 15CF4D18AF4F7421 | sudo apt-key add - sudo add-apt-repository "deb http://apt.llvm.org/bionic/ llvm-toolchain-bionic-9 main" diff --git a/.github/workflows/build-python.yml b/.github/workflows/build-python.yml index 5b9f7418b..724f56dda 100644 --- a/.github/workflows/build-python.yml +++ b/.github/workflows/build-python.yml @@ -65,6 +65,7 @@ jobs: if [ "${{ matrix.compiler }}" = "clang" ] && [ "${{ matrix.version }}" = "9" ]; then # pool.sks-keyservers.net is the SKS GPG global keyserver pool # 15CF4D18AF4F7421 is the GPG key for the LLVM apt repository + # This key is not in the keystore by default for Ubuntu so we need to add it. gpg --keyserver pool.sks-keyservers.net --recv-key 15CF4D18AF4F7421 gpg -a --export 15CF4D18AF4F7421 | sudo apt-key add - sudo add-apt-repository "deb http://apt.llvm.org/bionic/ llvm-toolchain-bionic-9 main" From b4bbad32df891a1f1c8178d2e5af38a3e8b85983 Mon Sep 17 00:00:00 2001 From: John Lambert Date: Wed, 14 Oct 2020 21:33:13 -0400 Subject: [PATCH 25/44] fix typo --- python/gtsam/examples/SFMExample_bal.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/python/gtsam/examples/SFMExample_bal.py b/python/gtsam/examples/SFMExample_bal.py index b5701669e..77d79ca24 100644 --- a/python/gtsam/examples/SFMExample_bal.py +++ b/python/gtsam/examples/SFMExample_bal.py @@ -7,7 +7,7 @@ See LICENSE for the license information Solve a structure-from-motion problem from a "Bundle Adjustment in the Large" file - Author: Frank Dellaert (Python: Akshay Krishan, John Lambert) + Author: Frank Dellaert (Python: Akshay Krishnan, John Lambert) """ import argparse From 4c6b488344b701f0313be108a80a54b571d129e0 Mon Sep 17 00:00:00 2001 From: Fan Jiang Date: Wed, 14 Oct 2020 21:44:07 -0400 Subject: [PATCH 26/44] Fix inteminent sks keyserver failure --- .github/workflows/build-linux.yml | 5 +++-- .github/workflows/build-python.yml | 6 +++--- 2 files changed, 6 insertions(+), 5 deletions(-) diff --git a/.github/workflows/build-linux.yml b/.github/workflows/build-linux.yml index d90aad13c..d0b16d2ee 100644 --- a/.github/workflows/build-linux.yml +++ b/.github/workflows/build-linux.yml @@ -53,8 +53,9 @@ jobs: # pool.sks-keyservers.net is the SKS GPG global keyserver pool # 15CF4D18AF4F7421 is the GPG key for the LLVM apt repository # This key is not in the keystore by default for Ubuntu so we need to add it. - gpg --keyserver pool.sks-keyservers.net --recv-key 15CF4D18AF4F7421 - gpg -a --export 15CF4D18AF4F7421 | sudo apt-key add - + LLVM_KEY=15CF4D18AF4F7421 + gpg --keyserver ipv4.pool.sks-keyservers.net --recv-key $LLVM_KEY || gpg --keyserver ha.pool.sks-keyservers.net --recv-key $LLVM_KEY + gpg -a --export $LLVM_KEY | sudo apt-key add - sudo add-apt-repository "deb http://apt.llvm.org/bionic/ llvm-toolchain-bionic-9 main" fi sudo apt-get -y update diff --git a/.github/workflows/build-python.yml b/.github/workflows/build-python.yml index 724f56dda..1c4953165 100644 --- a/.github/workflows/build-python.yml +++ b/.github/workflows/build-python.yml @@ -61,13 +61,13 @@ jobs: - name: Install (Linux) if: runner.os == 'Linux' run: | - # LLVM (clang) 9 is not in Bionic's repositories so we add the official LLVM repository. if [ "${{ matrix.compiler }}" = "clang" ] && [ "${{ matrix.version }}" = "9" ]; then # pool.sks-keyservers.net is the SKS GPG global keyserver pool # 15CF4D18AF4F7421 is the GPG key for the LLVM apt repository # This key is not in the keystore by default for Ubuntu so we need to add it. - gpg --keyserver pool.sks-keyservers.net --recv-key 15CF4D18AF4F7421 - gpg -a --export 15CF4D18AF4F7421 | sudo apt-key add - + LLVM_KEY=15CF4D18AF4F7421 + gpg --keyserver ipv4.pool.sks-keyservers.net --recv-key $LLVM_KEY || gpg --keyserver ha.pool.sks-keyservers.net --recv-key $LLVM_KEY + gpg -a --export $LLVM_KEY | sudo apt-key add - sudo add-apt-repository "deb http://apt.llvm.org/bionic/ llvm-toolchain-bionic-9 main" fi sudo apt-get -y update From 91e0bb1170ed2f007345878233957f92212e82c6 Mon Sep 17 00:00:00 2001 From: Fan Jiang Date: Thu, 15 Oct 2020 21:14:48 -0400 Subject: [PATCH 27/44] Add notes --- .github/workflows/build-linux.yml | 3 ++- .github/workflows/build-python.yml | 3 ++- 2 files changed, 4 insertions(+), 2 deletions(-) diff --git a/.github/workflows/build-linux.yml b/.github/workflows/build-linux.yml index d0b16d2ee..87a0430f8 100644 --- a/.github/workflows/build-linux.yml +++ b/.github/workflows/build-linux.yml @@ -50,7 +50,8 @@ jobs: run: | # LLVM (clang) 9 is not in Bionic's repositories so we add the official LLVM repository. if [ "${{ matrix.compiler }}" = "clang" ] && [ "${{ matrix.version }}" = "9" ]; then - # pool.sks-keyservers.net is the SKS GPG global keyserver pool + # (ipv4|ha).pool.sks-keyservers.net is the SKS GPG global keyserver pool + # ipv4 avoids potential timeouts because of crappy IPv6 infrastructure # 15CF4D18AF4F7421 is the GPG key for the LLVM apt repository # This key is not in the keystore by default for Ubuntu so we need to add it. LLVM_KEY=15CF4D18AF4F7421 diff --git a/.github/workflows/build-python.yml b/.github/workflows/build-python.yml index 1c4953165..fbec491f2 100644 --- a/.github/workflows/build-python.yml +++ b/.github/workflows/build-python.yml @@ -62,7 +62,8 @@ jobs: if: runner.os == 'Linux' run: | if [ "${{ matrix.compiler }}" = "clang" ] && [ "${{ matrix.version }}" = "9" ]; then - # pool.sks-keyservers.net is the SKS GPG global keyserver pool + # (ipv4|ha).pool.sks-keyservers.net is the SKS GPG global keyserver pool + # ipv4 avoids potential timeouts because of crappy IPv6 infrastructure # 15CF4D18AF4F7421 is the GPG key for the LLVM apt repository # This key is not in the keystore by default for Ubuntu so we need to add it. LLVM_KEY=15CF4D18AF4F7421 From b1c53000f7a1466100086c230529b327f742017d Mon Sep 17 00:00:00 2001 From: John Lambert Date: Sat, 17 Oct 2020 12:47:57 -0400 Subject: [PATCH 28/44] clean up comments --- python/gtsam/examples/SFMExample_bal.py | 12 +++++------- 1 file changed, 5 insertions(+), 7 deletions(-) diff --git a/python/gtsam/examples/SFMExample_bal.py b/python/gtsam/examples/SFMExample_bal.py index 77d79ca24..3ce465f6f 100644 --- a/python/gtsam/examples/SFMExample_bal.py +++ b/python/gtsam/examples/SFMExample_bal.py @@ -36,14 +36,14 @@ def run(args): """ Run LM optimization with BAL input data and report resulting error """ input_file = gtsam.findExampleDataFile(args.input_file) - # # Load the SfM data from file + # Load the SfM data from file mydata = readBal(input_file) logging.info(f"read {mydata.number_tracks()} tracks on {mydata.number_cameras()} cameras\n") - # # Create a factor graph + # Create a factor graph graph = gtsam.NonlinearFactorGraph() - # # We share *one* noiseModel between all projection factors + # We share *one* noiseModel between all projection factors noise = gtsam.noiseModel.Isotropic.Sigma(2, 1.0) # one pixel in u and v # Add measurements to the factor graph @@ -71,7 +71,7 @@ def run(args): ) ) - # # Create initial estimate + # Create initial estimate initial = gtsam.Values() i = 0 @@ -97,7 +97,7 @@ def run(args): except Exception as e: logging.exception("LM Optimization failed") return - # Error drops from 2764.22 to 0.046 + # Error drops from ~2764.22 to ~0.046 logging.info(f"final error: {graph.error(result)}") @@ -107,5 +107,3 @@ if __name__ == "__main__": help='Read SFM data from the specified BAL file') run(parser.parse_args()) - - From 0d88438a2a47d2af2bc7914b662f8623ad8294dd Mon Sep 17 00:00:00 2001 From: John Lambert Date: Mon, 19 Oct 2020 09:08:54 -0400 Subject: [PATCH 29/44] renamed myData to scene_data, and explained BAL parameterization --- python/gtsam/examples/SFMExample_bal.py | 33 ++++++++++++++++--------- 1 file changed, 21 insertions(+), 12 deletions(-) diff --git a/python/gtsam/examples/SFMExample_bal.py b/python/gtsam/examples/SFMExample_bal.py index 77d79ca24..34696700c 100644 --- a/python/gtsam/examples/SFMExample_bal.py +++ b/python/gtsam/examples/SFMExample_bal.py @@ -37,8 +37,8 @@ def run(args): input_file = gtsam.findExampleDataFile(args.input_file) # # Load the SfM data from file - mydata = readBal(input_file) - logging.info(f"read {mydata.number_tracks()} tracks on {mydata.number_cameras()} cameras\n") + scene_data = readBal(input_file) + logging.info(f"read {scene_data.number_tracks()} tracks on {scene_data.number_cameras()} cameras\n") # # Create a factor graph graph = gtsam.NonlinearFactorGraph() @@ -48,8 +48,8 @@ def run(args): # Add measurements to the factor graph j = 0 - for t_idx in range(mydata.number_tracks()): - track = mydata.track(t_idx) # SfmTrack + for t_idx in range(scene_data.number_tracks()): + track = scene_data.track(t_idx) # SfmTrack # retrieve the SfmMeasurement objects for m_idx in range(track.number_measurements()): # i represents the camera index, and uv is the 2d measurement @@ -61,13 +61,13 @@ def run(args): # Add a prior on pose x1. This indirectly specifies where the origin is. graph.push_back( gtsam.PriorFactorPinholeCameraCal3Bundler( - C(0), mydata.camera(0), gtsam.noiseModel.Isotropic.Sigma(9, 0.1) + C(0), scene_data.camera(0), gtsam.noiseModel.Isotropic.Sigma(9, 0.1) ) ) # Also add a prior on the position of the first landmark to fix the scale graph.push_back( gtsam.PriorFactorPoint3( - P(0), mydata.track(0).point3(), gtsam.noiseModel.Isotropic.Sigma(3, 0.1) + P(0), scene_data.track(0).point3(), gtsam.noiseModel.Isotropic.Sigma(3, 0.1) ) ) @@ -76,15 +76,15 @@ def run(args): i = 0 # add each PinholeCameraCal3Bundler - for cam_idx in range(mydata.number_cameras()): - camera = mydata.camera(cam_idx) + for cam_idx in range(scene_data.number_cameras()): + camera = scene_data.camera(cam_idx) initial.insert(C(i), camera) i += 1 j = 0 # add each SfmTrack - for t_idx in range(mydata.number_tracks()): - track = mydata.track(t_idx) + for t_idx in range(scene_data.number_tracks()): + track = scene_data.track(t_idx) initial.insert(P(j), track.point3()) j += 1 @@ -103,8 +103,17 @@ def run(args): if __name__ == "__main__": parser = argparse.ArgumentParser() - parser.add_argument('-i', '--input_file', type=str, default="dubrovnik-3-7-pre", - help='Read SFM data from the specified BAL file') + parser.add_argument( + '-i', + '--input_file', + type=str, + default="dubrovnik-3-7-pre", + help='Read SFM data from the specified BAL file' + 'The data format is described here: https://grail.cs.washington.edu/projects/bal/.' + 'BAL files contain (nrPoses, nrPoints, nrObservations), followed by (i,j,u,v) tuples, ' + 'then (wx,wy,wz,tx,ty,tz,f,k1,k1) as Bundler camera calibrations w/ Rodrigues vector' + 'and (x,y,z) 3d point initializations.' + ) run(parser.parse_args()) From 5be4571d5d06b18a64b2f18bcb80a0c188f6b477 Mon Sep 17 00:00:00 2001 From: John Lambert Date: Mon, 19 Oct 2020 14:32:36 -0400 Subject: [PATCH 30/44] update list of C++ examples that have been ported to Python --- python/gtsam/examples/README.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/python/gtsam/examples/README.md b/python/gtsam/examples/README.md index e05a0c7e1..2a2c9f2ef 100644 --- a/python/gtsam/examples/README.md +++ b/python/gtsam/examples/README.md @@ -39,7 +39,7 @@ | SelfCalibrationExample | | | SFMdata | | | SFMExample_bal_COLAMD_METIS | | -| SFMExample_bal | | +| SFMExample_bal | :heavy_check_mark: | | SFMExample | :heavy_check_mark: | | SFMExampleExpressions_bal | | | SFMExampleExpressions | | From 7aab3796b0f5cee7b6cd97ff9fbd40df1bea5f3d Mon Sep 17 00:00:00 2001 From: Jose Luis Blanco-Claraco Date: Fri, 23 Oct 2020 12:50:38 +0200 Subject: [PATCH 31/44] Add alternativeName() --- gtsam/inference/Symbol.h | 6 ++++++ gtsam/inference/tests/testKey.cpp | 19 +++++++++++++++++++ 2 files changed, 25 insertions(+) diff --git a/gtsam/inference/Symbol.h b/gtsam/inference/Symbol.h index 5be195db3..000a026c2 100644 --- a/gtsam/inference/Symbol.h +++ b/gtsam/inference/Symbol.h @@ -162,6 +162,12 @@ inline Key W(std::uint64_t j) { return Symbol('w', j); } inline Key X(std::uint64_t j) { return Symbol('x', j); } inline Key Y(std::uint64_t j) { return Symbol('y', j); } inline Key Z(std::uint64_t j) { return Symbol('z', j); } + +/** Generates symbol shorthands with alternative names different than the + * one-letter predefined ones. */ +inline std::function alternativeName(const char c) { + return [c](std::uint64_t j) { return gtsam::Symbol(c, j); }; +} } /// traits diff --git a/gtsam/inference/tests/testKey.cpp b/gtsam/inference/tests/testKey.cpp index a60258581..f34b77c14 100644 --- a/gtsam/inference/tests/testKey.cpp +++ b/gtsam/inference/tests/testKey.cpp @@ -40,6 +40,25 @@ TEST(Key, KeySymbolConversion) { EXPECT(assert_equal(original, actual)) } +/* ************************************************************************* */ +TEST(Key, SymbolAlternativeNames) { + const auto x1 = gtsam::symbol_shorthand::X(1); + const auto v1 = gtsam::symbol_shorthand::V(1); + const auto a1 = gtsam::symbol_shorthand::A(1); + + const auto Z = gtsam::symbol_shorthand::alternativeName('x'); + const auto DZ = gtsam::symbol_shorthand::alternativeName('v'); + const auto DDZ = gtsam::symbol_shorthand::alternativeName('a'); + + const auto z1 = Z(1); + const auto dz1 = DZ(1); + const auto ddz1 = DDZ(1); + + EXPECT(assert_equal(x1, z1)); + EXPECT(assert_equal(v1, dz1)); + EXPECT(assert_equal(a1, ddz1)); +} + /* ************************************************************************* */ template Key KeyTestValue(); From e3a28767edb7f86c39e0369a1910c488fa5aca8c Mon Sep 17 00:00:00 2001 From: Jose Luis Blanco Claraco Date: Sat, 24 Oct 2020 08:41:00 +0200 Subject: [PATCH 32/44] replaced lambda with class plus functor --- gtsam/inference/Symbol.h | 10 ++++++---- gtsam/inference/tests/testKey.cpp | 9 ++++----- 2 files changed, 10 insertions(+), 9 deletions(-) diff --git a/gtsam/inference/Symbol.h b/gtsam/inference/Symbol.h index 000a026c2..6dbb306db 100644 --- a/gtsam/inference/Symbol.h +++ b/gtsam/inference/Symbol.h @@ -165,13 +165,15 @@ inline Key Z(std::uint64_t j) { return Symbol('z', j); } /** Generates symbol shorthands with alternative names different than the * one-letter predefined ones. */ -inline std::function alternativeName(const char c) { - return [c](std::uint64_t j) { return gtsam::Symbol(c, j); }; -} +class SymbolGenerator { + const char c_; +public: + SymbolGenerator(const char c) : c_(c) {} + Symbol operator()(const std::uint64_t j) const { return Symbol(c_, j); } +}; } /// traits template<> struct traits : public Testable {}; } // \ namespace gtsam - diff --git a/gtsam/inference/tests/testKey.cpp b/gtsam/inference/tests/testKey.cpp index f34b77c14..124ba7652 100644 --- a/gtsam/inference/tests/testKey.cpp +++ b/gtsam/inference/tests/testKey.cpp @@ -41,14 +41,14 @@ TEST(Key, KeySymbolConversion) { } /* ************************************************************************* */ -TEST(Key, SymbolAlternativeNames) { +TEST(Key, SymbolGenerator) { const auto x1 = gtsam::symbol_shorthand::X(1); const auto v1 = gtsam::symbol_shorthand::V(1); const auto a1 = gtsam::symbol_shorthand::A(1); - const auto Z = gtsam::symbol_shorthand::alternativeName('x'); - const auto DZ = gtsam::symbol_shorthand::alternativeName('v'); - const auto DDZ = gtsam::symbol_shorthand::alternativeName('a'); + const auto Z = gtsam::symbol_shorthand::SymbolGenerator('x'); + const auto DZ = gtsam::symbol_shorthand::SymbolGenerator('v'); + const auto DDZ = gtsam::symbol_shorthand::SymbolGenerator('a'); const auto z1 = Z(1); const auto dz1 = DZ(1); @@ -125,4 +125,3 @@ int main() { return TestRegistry::runAllTests(tr); } /* ************************************************************************* */ - From 672635aad46ab69c4e7aaba8a223b7732359a0f8 Mon Sep 17 00:00:00 2001 From: Jose Luis Blanco Claraco Date: Sat, 24 Oct 2020 08:44:31 +0200 Subject: [PATCH 33/44] less verbose name path for SymbolGenerator --- gtsam/inference/Symbol.h | 2 +- gtsam/inference/tests/testKey.cpp | 6 +++--- 2 files changed, 4 insertions(+), 4 deletions(-) diff --git a/gtsam/inference/Symbol.h b/gtsam/inference/Symbol.h index 6dbb306db..469082f16 100644 --- a/gtsam/inference/Symbol.h +++ b/gtsam/inference/Symbol.h @@ -162,6 +162,7 @@ inline Key W(std::uint64_t j) { return Symbol('w', j); } inline Key X(std::uint64_t j) { return Symbol('x', j); } inline Key Y(std::uint64_t j) { return Symbol('y', j); } inline Key Z(std::uint64_t j) { return Symbol('z', j); } +} /** Generates symbol shorthands with alternative names different than the * one-letter predefined ones. */ @@ -171,7 +172,6 @@ public: SymbolGenerator(const char c) : c_(c) {} Symbol operator()(const std::uint64_t j) const { return Symbol(c_, j); } }; -} /// traits template<> struct traits : public Testable {}; diff --git a/gtsam/inference/tests/testKey.cpp b/gtsam/inference/tests/testKey.cpp index 124ba7652..64674c36f 100644 --- a/gtsam/inference/tests/testKey.cpp +++ b/gtsam/inference/tests/testKey.cpp @@ -46,9 +46,9 @@ TEST(Key, SymbolGenerator) { const auto v1 = gtsam::symbol_shorthand::V(1); const auto a1 = gtsam::symbol_shorthand::A(1); - const auto Z = gtsam::symbol_shorthand::SymbolGenerator('x'); - const auto DZ = gtsam::symbol_shorthand::SymbolGenerator('v'); - const auto DDZ = gtsam::symbol_shorthand::SymbolGenerator('a'); + const auto Z = gtsam::SymbolGenerator('x'); + const auto DZ = gtsam::SymbolGenerator('v'); + const auto DDZ = gtsam::SymbolGenerator('a'); const auto z1 = Z(1); const auto dz1 = DZ(1); From 1da968afd3d9122ed8d97dec96a2b4b8183a6cfe Mon Sep 17 00:00:00 2001 From: Jose Luis Blanco-Claraco Date: Wed, 28 Oct 2020 07:43:16 +0100 Subject: [PATCH 34/44] Automatic detection of correct suggest-override flag --- cmake/GtsamBuildTypes.cmake | 15 ++++++++++----- 1 file changed, 10 insertions(+), 5 deletions(-) diff --git a/cmake/GtsamBuildTypes.cmake b/cmake/GtsamBuildTypes.cmake index d13e3aa12..3155161be 100644 --- a/cmake/GtsamBuildTypes.cmake +++ b/cmake/GtsamBuildTypes.cmake @@ -1,3 +1,5 @@ +include(CheckCXXCompilerFlag) # for check_cxx_compiler_flag() + # Set cmake policy to recognize the AppleClang compiler # independently from the Clang compiler. if(POLICY CMP0025) @@ -105,11 +107,14 @@ if(MSVC) else() # Common to all configurations, next for each configuration: - if ( - ((CMAKE_CXX_COMPILER_ID MATCHES "Clang") AND (NOT CMAKE_CXX_COMPILER_VERSION VERSION_LESS 12.0.0)) OR - (CMAKE_CXX_COMPILER_ID MATCHES "GNU") - ) - # set(flag_override_ -Wsuggest-override) # -Werror=suggest-override: Add again someday + if (NOT MSVC) + check_cxx_compiler_flag(-Wsuggest-override COMPILER_HAS_WSUGGEST_OVERRIDE) + check_cxx_compiler_flag(-Wmissing COMPILER_HAS_WMISSING_OVERRIDE) + if (COMPILER_HAS_WSUGGEST_OVERRIDE) + set(flag_override_ -Wsuggest-override) # -Werror=suggest-override: Add again someday + elseif(COMPILER_HAS_WMISSING_OVERRIDE) + set(flag_override_ -Wmissing-override) # -Werror=missing-override: Add again someday + endif() endif() set(GTSAM_COMPILE_OPTIONS_PRIVATE_COMMON From 405771397ba3938f094f7d023e75ccbb9a8e3ea3 Mon Sep 17 00:00:00 2001 From: Tim McGrath Date: Sat, 31 Oct 2020 13:40:05 -0400 Subject: [PATCH 35/44] adding additional Unit3 support in the wrapper: PriorFactorUnit3, Values::insert/update/at(Unit3) --- gtsam/gtsam.i | 6 ++++-- 1 file changed, 4 insertions(+), 2 deletions(-) diff --git a/gtsam/gtsam.i b/gtsam/gtsam.i index 575a216d6..b578d134d 100644 --- a/gtsam/gtsam.i +++ b/gtsam/gtsam.i @@ -2157,6 +2157,7 @@ class Values { void insert(size_t j, const gtsam::SOn& P); void insert(size_t j, const gtsam::Rot3& rot3); void insert(size_t j, const gtsam::Pose3& pose3); + void insert(size_t j, const gtsam::Unit3& unit3); void insert(size_t j, const gtsam::Cal3_S2& cal3_s2); void insert(size_t j, const gtsam::Cal3DS2& cal3ds2); void insert(size_t j, const gtsam::Cal3Bundler& cal3bundler); @@ -2175,6 +2176,7 @@ class Values { void update(size_t j, const gtsam::SOn& P); void update(size_t j, const gtsam::Rot3& rot3); void update(size_t j, const gtsam::Pose3& pose3); + void update(size_t j, const gtsam::Unit3& unit3); void update(size_t j, const gtsam::Cal3_S2& cal3_s2); void update(size_t j, const gtsam::Cal3DS2& cal3ds2); void update(size_t j, const gtsam::Cal3Bundler& cal3bundler); @@ -2186,7 +2188,7 @@ class Values { void update(size_t j, Vector vector); void update(size_t j, Matrix matrix); - template, gtsam::imuBias::ConstantBias, gtsam::NavState, Vector, Matrix}> + template, gtsam::imuBias::ConstantBias, gtsam::NavState, Vector, Matrix}> T at(size_t j); /// version for double @@ -2529,7 +2531,7 @@ class NonlinearISAM { #include #include -template}> +template}> virtual class PriorFactor : gtsam::NoiseModelFactor { PriorFactor(size_t key, const T& prior, const gtsam::noiseModel::Base* noiseModel); T prior() const; From 63ca1c1f5eec82cc04737611469f3ad69b486f16 Mon Sep 17 00:00:00 2001 From: Fan Jiang Date: Mon, 2 Nov 2020 10:46:36 -0500 Subject: [PATCH 36/44] Attempt to fix spooky boost in Homebrew --- .github/workflows/build-macos.yml | 4 ++-- .github/workflows/build-python.yml | 4 ++-- 2 files changed, 4 insertions(+), 4 deletions(-) diff --git a/.github/workflows/build-macos.yml b/.github/workflows/build-macos.yml index 363cd690f..b2b71ea7d 100644 --- a/.github/workflows/build-macos.yml +++ b/.github/workflows/build-macos.yml @@ -35,7 +35,7 @@ jobs: - name: Install (macOS) if: runner.os == 'macOS' run: | - brew install cmake ninja boost + brew install cmake ninja boost@1.60 if [ "${{ matrix.compiler }}" = "gcc" ]; then brew install gcc@${{ matrix.version }} echo "::set-env name=CC::gcc-${{ matrix.version }}" @@ -48,4 +48,4 @@ jobs: - name: Build and Test (macOS) if: runner.os == 'macOS' run: | - bash .github/scripts/unix.sh -t \ No newline at end of file + bash .github/scripts/unix.sh -t diff --git a/.github/workflows/build-python.yml b/.github/workflows/build-python.yml index fbec491f2..6c90b8bf7 100644 --- a/.github/workflows/build-python.yml +++ b/.github/workflows/build-python.yml @@ -87,7 +87,7 @@ jobs: - name: Install (macOS) if: runner.os == 'macOS' run: | - brew install cmake ninja boost + brew install cmake ninja boost@1.60 if [ "${{ matrix.compiler }}" = "gcc" ]; then brew install gcc@${{ matrix.version }} echo "::set-env name=CC::gcc-${{ matrix.version }}" @@ -109,4 +109,4 @@ jobs: - name: Build (macOS) if: runner.os == 'macOS' run: | - bash .github/scripts/python.sh \ No newline at end of file + bash .github/scripts/python.sh From d8089c71322ad1c75f92f0b2de4d2fb286ac27a7 Mon Sep 17 00:00:00 2001 From: Fan Jiang Date: Mon, 2 Nov 2020 11:01:43 -0500 Subject: [PATCH 37/44] Use my tap --- .github/workflows/build-macos.yml | 3 ++- .github/workflows/build-python.yml | 3 ++- 2 files changed, 4 insertions(+), 2 deletions(-) diff --git a/.github/workflows/build-macos.yml b/.github/workflows/build-macos.yml index b2b71ea7d..fd6fb8d0b 100644 --- a/.github/workflows/build-macos.yml +++ b/.github/workflows/build-macos.yml @@ -35,7 +35,8 @@ jobs: - name: Install (macOS) if: runner.os == 'macOS' run: | - brew install cmake ninja boost@1.60 + brew tap ProfFan/robotics + brew install cmake ninja boost@1.68 if [ "${{ matrix.compiler }}" = "gcc" ]; then brew install gcc@${{ matrix.version }} echo "::set-env name=CC::gcc-${{ matrix.version }}" diff --git a/.github/workflows/build-python.yml b/.github/workflows/build-python.yml index 6c90b8bf7..5f79ae90d 100644 --- a/.github/workflows/build-python.yml +++ b/.github/workflows/build-python.yml @@ -87,7 +87,8 @@ jobs: - name: Install (macOS) if: runner.os == 'macOS' run: | - brew install cmake ninja boost@1.60 + brew tap ProfFan/robotics + brew install cmake ninja boost@1.68 if [ "${{ matrix.compiler }}" = "gcc" ]; then brew install gcc@${{ matrix.version }} echo "::set-env name=CC::gcc-${{ matrix.version }}" From 1ee5650fc774157f824267741852a0b2ec43f919 Mon Sep 17 00:00:00 2001 From: Fan Jiang Date: Mon, 2 Nov 2020 11:12:52 -0500 Subject: [PATCH 38/44] Use my tap --- .github/workflows/build-macos.yml | 4 ++-- .github/workflows/build-python.yml | 4 ++-- 2 files changed, 4 insertions(+), 4 deletions(-) diff --git a/.github/workflows/build-macos.yml b/.github/workflows/build-macos.yml index fd6fb8d0b..9dca41b84 100644 --- a/.github/workflows/build-macos.yml +++ b/.github/workflows/build-macos.yml @@ -35,8 +35,8 @@ jobs: - name: Install (macOS) if: runner.os == 'macOS' run: | - brew tap ProfFan/robotics - brew install cmake ninja boost@1.68 + brew tap ProfFan/my + brew install cmake ninja boost@1.59 if [ "${{ matrix.compiler }}" = "gcc" ]; then brew install gcc@${{ matrix.version }} echo "::set-env name=CC::gcc-${{ matrix.version }}" diff --git a/.github/workflows/build-python.yml b/.github/workflows/build-python.yml index 5f79ae90d..ef7c30a62 100644 --- a/.github/workflows/build-python.yml +++ b/.github/workflows/build-python.yml @@ -87,8 +87,8 @@ jobs: - name: Install (macOS) if: runner.os == 'macOS' run: | - brew tap ProfFan/robotics - brew install cmake ninja boost@1.68 + brew tap ProfFan/my + brew install cmake ninja boost@1.59 if [ "${{ matrix.compiler }}" = "gcc" ]; then brew install gcc@${{ matrix.version }} echo "::set-env name=CC::gcc-${{ matrix.version }}" From dddc97c487c2abe91254ac19a4cc759278d7a349 Mon Sep 17 00:00:00 2001 From: Fan Jiang Date: Mon, 2 Nov 2020 11:20:48 -0500 Subject: [PATCH 39/44] Use explict tap name --- .github/workflows/build-macos.yml | 2 +- .github/workflows/build-python.yml | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/.github/workflows/build-macos.yml b/.github/workflows/build-macos.yml index 9dca41b84..c9ccfbfc3 100644 --- a/.github/workflows/build-macos.yml +++ b/.github/workflows/build-macos.yml @@ -36,7 +36,7 @@ jobs: if: runner.os == 'macOS' run: | brew tap ProfFan/my - brew install cmake ninja boost@1.59 + brew install cmake ninja ProfFan/my/boost@1.59 if [ "${{ matrix.compiler }}" = "gcc" ]; then brew install gcc@${{ matrix.version }} echo "::set-env name=CC::gcc-${{ matrix.version }}" diff --git a/.github/workflows/build-python.yml b/.github/workflows/build-python.yml index ef7c30a62..f75701215 100644 --- a/.github/workflows/build-python.yml +++ b/.github/workflows/build-python.yml @@ -88,7 +88,7 @@ jobs: if: runner.os == 'macOS' run: | brew tap ProfFan/my - brew install cmake ninja boost@1.59 + brew install cmake ninja ProfFan/my/boost@1.59 if [ "${{ matrix.compiler }}" = "gcc" ]; then brew install gcc@${{ matrix.version }} echo "::set-env name=CC::gcc-${{ matrix.version }}" From 315380db03f25eec0d05ad6eabeecef0b541e920 Mon Sep 17 00:00:00 2001 From: Fan Jiang Date: Mon, 2 Nov 2020 11:28:49 -0500 Subject: [PATCH 40/44] Last resort: use the explict 1.73 formula --- .github/workflows/build-macos.yml | 4 ++-- .github/workflows/build-python.yml | 4 ++-- 2 files changed, 4 insertions(+), 4 deletions(-) diff --git a/.github/workflows/build-macos.yml b/.github/workflows/build-macos.yml index c9ccfbfc3..212924cc7 100644 --- a/.github/workflows/build-macos.yml +++ b/.github/workflows/build-macos.yml @@ -35,8 +35,8 @@ jobs: - name: Install (macOS) if: runner.os == 'macOS' run: | - brew tap ProfFan/my - brew install cmake ninja ProfFan/my/boost@1.59 + brew install cmake ninja + brew install https://github.com/Homebrew/homebrew-core/raw/0687baaf14e7b16c383d101fcc3b954cfb05ffe8/Formula/boost.rb if [ "${{ matrix.compiler }}" = "gcc" ]; then brew install gcc@${{ matrix.version }} echo "::set-env name=CC::gcc-${{ matrix.version }}" diff --git a/.github/workflows/build-python.yml b/.github/workflows/build-python.yml index f75701215..f6930a8c4 100644 --- a/.github/workflows/build-python.yml +++ b/.github/workflows/build-python.yml @@ -87,8 +87,8 @@ jobs: - name: Install (macOS) if: runner.os == 'macOS' run: | - brew tap ProfFan/my - brew install cmake ninja ProfFan/my/boost@1.59 + brew install cmake ninja + brew install https://github.com/Homebrew/homebrew-core/raw/0687baaf14e7b16c383d101fcc3b954cfb05ffe8/Formula/boost.rb if [ "${{ matrix.compiler }}" = "gcc" ]; then brew install gcc@${{ matrix.version }} echo "::set-env name=CC::gcc-${{ matrix.version }}" From 325b868e8b55f186567de398d85c61b2400cfa80 Mon Sep 17 00:00:00 2001 From: Fan Jiang Date: Mon, 2 Nov 2020 14:42:21 -0500 Subject: [PATCH 41/44] Use my tap --- .github/workflows/build-macos.yml | 3 ++- .github/workflows/build-python.yml | 3 ++- 2 files changed, 4 insertions(+), 2 deletions(-) diff --git a/.github/workflows/build-macos.yml b/.github/workflows/build-macos.yml index 212924cc7..3ce98055a 100644 --- a/.github/workflows/build-macos.yml +++ b/.github/workflows/build-macos.yml @@ -35,8 +35,9 @@ jobs: - name: Install (macOS) if: runner.os == 'macOS' run: | + brew tap ProfFan/robotics brew install cmake ninja - brew install https://github.com/Homebrew/homebrew-core/raw/0687baaf14e7b16c383d101fcc3b954cfb05ffe8/Formula/boost.rb + brew install ProfFan/robotics/boost if [ "${{ matrix.compiler }}" = "gcc" ]; then brew install gcc@${{ matrix.version }} echo "::set-env name=CC::gcc-${{ matrix.version }}" diff --git a/.github/workflows/build-python.yml b/.github/workflows/build-python.yml index f6930a8c4..8255fb8ab 100644 --- a/.github/workflows/build-python.yml +++ b/.github/workflows/build-python.yml @@ -87,8 +87,9 @@ jobs: - name: Install (macOS) if: runner.os == 'macOS' run: | + brew tap ProfFan/robotics brew install cmake ninja - brew install https://github.com/Homebrew/homebrew-core/raw/0687baaf14e7b16c383d101fcc3b954cfb05ffe8/Formula/boost.rb + brew install ProfFan/robotics/boost if [ "${{ matrix.compiler }}" = "gcc" ]; then brew install gcc@${{ matrix.version }} echo "::set-env name=CC::gcc-${{ matrix.version }}" From 6c6cb965d88318623653454aac28b572aeef776b Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Wed, 4 Nov 2020 12:12:10 -0500 Subject: [PATCH 42/44] Consistent interface for pixel center (#579) * defined u0 and v0 in all camera models for consistent interface * deprecate u0/v0 and use px/py everywhere * Use deprecation macro * fix various issues --- gtsam/geometry/Cal3Bundler.h | 12 ++++++++++++ gtsam/gtsam.i | 14 ++++++++++++-- gtsam/nonlinear/tests/testAdaptAutoDiff.cpp | 2 +- gtsam/slam/dataset.cpp | 4 ++-- 4 files changed, 27 insertions(+), 5 deletions(-) diff --git a/gtsam/geometry/Cal3Bundler.h b/gtsam/geometry/Cal3Bundler.h index 96765f899..2e3fab002 100644 --- a/gtsam/geometry/Cal3Bundler.h +++ b/gtsam/geometry/Cal3Bundler.h @@ -98,6 +98,17 @@ public: return k2_; } + /// image center in x + inline double px() const { + return u0_; + } + + /// image center in y + inline double py() const { + return v0_; + } + +#ifdef GTSAM_ALLOW_DEPRECATED_SINCE_V41 /// get parameter u0 inline double u0() const { return u0_; @@ -107,6 +118,7 @@ public: inline double v0() const { return v0_; } +#endif /** diff --git a/gtsam/gtsam.i b/gtsam/gtsam.i index 575a216d6..8ed93868f 100644 --- a/gtsam/gtsam.i +++ b/gtsam/gtsam.i @@ -597,6 +597,7 @@ class Rot3 { Rot3(double R11, double R12, double R13, double R21, double R22, double R23, double R31, double R32, double R33); + Rot3(double w, double x, double y, double z); static gtsam::Rot3 Rx(double t); static gtsam::Rot3 Ry(double t); @@ -980,8 +981,8 @@ class Cal3Bundler { double fy() const; double k1() const; double k2() const; - double u0() const; - double v0() const; + double px() const; + double py() const; Vector vector() const; Vector k() const; Matrix K() const; @@ -2761,7 +2762,16 @@ virtual class EssentialMatrixFactor : gtsam::NoiseModelFactor { }; #include + class SfmTrack { + SfmTrack(); + + double r; + double g; + double b; + // TODO Need to close wrap#10 to allow this to work. + // std::vector> measurements; + Point3 point3() const; size_t number_measurements() const; pair measurement(size_t idx) const; diff --git a/gtsam/nonlinear/tests/testAdaptAutoDiff.cpp b/gtsam/nonlinear/tests/testAdaptAutoDiff.cpp index 2f4f21286..1423b473e 100644 --- a/gtsam/nonlinear/tests/testAdaptAutoDiff.cpp +++ b/gtsam/nonlinear/tests/testAdaptAutoDiff.cpp @@ -41,7 +41,7 @@ struct Cal3Bundler0 : public Cal3Bundler { double v0 = 0) : Cal3Bundler(f, k1, k2, u0, v0) {} Cal3Bundler0 retract(const Vector& d) const { - return Cal3Bundler0(fx() + d(0), k1() + d(1), k2() + d(2), u0(), v0()); + return Cal3Bundler0(fx() + d(0), k1() + d(1), k2() + d(2), px(), py()); } Vector3 localCoordinates(const Cal3Bundler0& T2) const { return T2.vector() - vector(); diff --git a/gtsam/slam/dataset.cpp b/gtsam/slam/dataset.cpp index 270dbeb95..74e074c9e 100644 --- a/gtsam/slam/dataset.cpp +++ b/gtsam/slam/dataset.cpp @@ -1164,8 +1164,8 @@ bool writeBAL(const string &filename, SfmData &data) { for (size_t k = 0; k < track.number_measurements(); k++) { // for each observation of the 3D point j size_t i = track.measurements[k].first; // camera id - double u0 = data.cameras[i].calibration().u0(); - double v0 = data.cameras[i].calibration().v0(); + double u0 = data.cameras[i].calibration().px(); + double v0 = data.cameras[i].calibration().py(); if (u0 != 0 || v0 != 0) { cout << "writeBAL has not been tested for calibration with nonzero " From acd6fff5623e33ddd2a086ec6074c737097693c7 Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Sat, 7 Nov 2020 17:28:50 -0500 Subject: [PATCH 43/44] minor typo fixes --- gtsam/geometry/Rot3.h | 2 +- wrap/cmake/PybindWrap.cmake | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/gtsam/geometry/Rot3.h b/gtsam/geometry/Rot3.h index 2334312f6..abd74e063 100644 --- a/gtsam/geometry/Rot3.h +++ b/gtsam/geometry/Rot3.h @@ -526,7 +526,7 @@ namespace gtsam { /** * @brief Spherical Linear intERPolation between *this and other - * @param s a value between 0 and 1 + * @param t a value between 0 and 1 * @param other final point of iterpolation geodesic on manifold */ Rot3 slerp(double t, const Rot3& other) const; diff --git a/wrap/cmake/PybindWrap.cmake b/wrap/cmake/PybindWrap.cmake index 85f956d50..ff69b5aed 100644 --- a/wrap/cmake/PybindWrap.cmake +++ b/wrap/cmake/PybindWrap.cmake @@ -146,7 +146,7 @@ function(install_python_scripts else() set(build_type_tag "") endif() - # Split up filename to strip trailing '/' in WRAP_CYTHON_INSTALL_PATH if + # Split up filename to strip trailing '/' in GTSAM_PY_INSTALL_PATH if # there is one get_filename_component(location "${dest_directory}" PATH) get_filename_component(name "${dest_directory}" NAME) From c5c54da588f4cb8150437e417c3141c64e714cd8 Mon Sep 17 00:00:00 2001 From: Jose Luis Blanco-Claraco Date: Sun, 8 Nov 2020 11:07:50 +0100 Subject: [PATCH 44/44] Avoid redundant calls to error() --- gtsam/nonlinear/NonlinearOptimizer.cpp | 10 +++++++--- 1 file changed, 7 insertions(+), 3 deletions(-) diff --git a/gtsam/nonlinear/NonlinearOptimizer.cpp b/gtsam/nonlinear/NonlinearOptimizer.cpp index 9a9c487b6..fd9961742 100644 --- a/gtsam/nonlinear/NonlinearOptimizer.cpp +++ b/gtsam/nonlinear/NonlinearOptimizer.cpp @@ -88,20 +88,24 @@ void NonlinearOptimizer::defaultOptimize() { } // Iterative loop + double newError = currentError; // used to avoid repeated calls to error() do { // Do next iteration - currentError = error(); // TODO(frank): don't do this twice at first !? Computed above! + currentError = newError; iterate(); tictoc_finishedIteration(); + // Update newError for either printouts or conditional-end checks: + newError = error(); + // Maybe show output if (params.verbosity >= NonlinearOptimizerParams::VALUES) values().print("newValues"); if (params.verbosity >= NonlinearOptimizerParams::ERROR) - cout << "newError: " << error() << endl; + cout << "newError: " << newError << endl; } while (iterations() < params.maxIterations && !checkConvergence(params.relativeErrorTol, params.absoluteErrorTol, params.errorTol, - currentError, error(), params.verbosity) && std::isfinite(currentError)); + currentError, newError, params.verbosity) && std::isfinite(currentError)); // Printing if verbose if (params.verbosity >= NonlinearOptimizerParams::TERMINATION) {