From b7b48ba5302a7045bd9677f957d0977790542ddd Mon Sep 17 00:00:00 2001 From: Matt Date: Sun, 29 Dec 2024 11:06:22 -0800 Subject: [PATCH 1/4] Fix lingering boost flags --- gtsam/base/concepts.h | 2 +- gtsam/base/tests/testMatrix.cpp | 4 ++-- gtsam/base/tests/testVector.cpp | 2 +- gtsam/base/timing.cpp | 22 +++++++++---------- gtsam/base/timing.h | 8 +++---- .../nonlinear/LevenbergMarquardtOptimizer.cpp | 6 ++--- 6 files changed, 22 insertions(+), 22 deletions(-) diff --git a/gtsam/base/concepts.h b/gtsam/base/concepts.h index c9f76ca9f..6ff1a44d4 100644 --- a/gtsam/base/concepts.h +++ b/gtsam/base/concepts.h @@ -8,7 +8,7 @@ #pragma once -#ifdef GTSAM_USE_BOOST_FEATURES +#if GTSAM_USE_BOOST_FEATURES #include #include #include diff --git a/gtsam/base/tests/testMatrix.cpp b/gtsam/base/tests/testMatrix.cpp index 3fbf11746..4c8808722 100644 --- a/gtsam/base/tests/testMatrix.cpp +++ b/gtsam/base/tests/testMatrix.cpp @@ -1151,7 +1151,7 @@ TEST(Matrix, Matrix24IsVectorSpace) { } TEST(Matrix, RowMajorIsVectorSpace) { -#ifdef GTSAM_USE_BOOST_FEATURES +#if GTSAM_USE_BOOST_FEATURES typedef Eigen::Matrix RowMajor; GTSAM_CONCEPT_ASSERT(IsVectorSpace); #endif @@ -1166,7 +1166,7 @@ TEST(Matrix, VectorIsVectorSpace) { } TEST(Matrix, RowVectorIsVectorSpace) { -#ifdef GTSAM_USE_BOOST_FEATURES +#if GTSAM_USE_BOOST_FEATURES typedef Eigen::Matrix RowVector; GTSAM_CONCEPT_ASSERT(IsVectorSpace); GTSAM_CONCEPT_ASSERT(IsVectorSpace); diff --git a/gtsam/base/tests/testVector.cpp b/gtsam/base/tests/testVector.cpp index d95b14292..46d44bb80 100644 --- a/gtsam/base/tests/testVector.cpp +++ b/gtsam/base/tests/testVector.cpp @@ -272,7 +272,7 @@ TEST(Vector, VectorIsVectorSpace) { } TEST(Vector, RowVectorIsVectorSpace) { -#ifdef GTSAM_USE_BOOST_FEATURES +#if GTSAM_USE_BOOST_FEATURES typedef Eigen::Matrix RowVector; GTSAM_CONCEPT_ASSERT(IsVectorSpace); #endif diff --git a/gtsam/base/timing.cpp b/gtsam/base/timing.cpp index b43595066..07fb7b61b 100644 --- a/gtsam/base/timing.cpp +++ b/gtsam/base/timing.cpp @@ -57,7 +57,7 @@ void TimingOutline::add(size_t usecs, size_t usecsWall) { TimingOutline::TimingOutline(const std::string& label, size_t id) : id_(id), t_(0), tWall_(0), t2_(0.0), tIt_(0), tMax_(0), tMin_(0), n_(0), myOrder_( 0), lastChildOrder_(0), label_(label) { -#ifdef GTSAM_USE_BOOST_FEATURES +#if GTSAM_USE_BOOST_FEATURES #ifdef GTSAM_USING_NEW_BOOST_TIMERS timer_.stop(); #endif @@ -66,7 +66,7 @@ TimingOutline::TimingOutline(const std::string& label, size_t id) : /* ************************************************************************* */ size_t TimingOutline::time() const { -#ifdef GTSAM_USE_BOOST_FEATURES +#if GTSAM_USE_BOOST_FEATURES size_t time = 0; bool hasChildren = false; for(const ChildMap::value_type& child: children_) { @@ -84,7 +84,7 @@ size_t TimingOutline::time() const { /* ************************************************************************* */ void TimingOutline::print(const std::string& outline) const { -#ifdef GTSAM_USE_BOOST_FEATURES +#if GTSAM_USE_BOOST_FEATURES std::string formattedLabel = label_; std::replace(formattedLabel.begin(), formattedLabel.end(), '_', ' '); std::cout << outline << "-" << formattedLabel << ": " << self() << " CPU (" @@ -108,7 +108,7 @@ void TimingOutline::print(const std::string& outline) const { void TimingOutline::print2(const std::string& outline, const double parentTotal) const { -#ifdef GTSAM_USE_BOOST_FEATURES +#if GTSAM_USE_BOOST_FEATURES const int w1 = 24, w2 = 2, w3 = 6, w4 = 8, precision = 2; const double selfTotal = self(), selfMean = selfTotal / double(n_); const double childTotal = secs(); @@ -153,7 +153,7 @@ void TimingOutline::print2(const std::string& outline, /* ************************************************************************* */ const std::shared_ptr& TimingOutline::child(size_t child, const std::string& label, const std::weak_ptr& thisPtr) { -#ifdef GTSAM_USE_BOOST_FEATURES +#if GTSAM_USE_BOOST_FEATURES assert(thisPtr.lock().get() == this); std::shared_ptr& result = children_[child]; if (!result) { @@ -172,7 +172,7 @@ const std::shared_ptr& TimingOutline::child(size_t child, /* ************************************************************************* */ void TimingOutline::tic() { // Disable this entire function if we are not using boost -#ifdef GTSAM_USE_BOOST_FEATURES +#if GTSAM_USE_BOOST_FEATURES #ifdef GTSAM_USING_NEW_BOOST_TIMERS assert(timer_.is_stopped()); timer_.start(); @@ -191,7 +191,7 @@ void TimingOutline::tic() { /* ************************************************************************* */ void TimingOutline::toc() { // Disable this entire function if we are not using boost -#ifdef GTSAM_USE_BOOST_FEATURES +#if GTSAM_USE_BOOST_FEATURES #ifdef GTSAM_USING_NEW_BOOST_TIMERS @@ -225,7 +225,7 @@ void TimingOutline::toc() { /* ************************************************************************* */ void TimingOutline::finishedIteration() { -#ifdef GTSAM_USE_BOOST_FEATURES +#if GTSAM_USE_BOOST_FEATURES if (tIt_ > tMax_) tMax_ = tIt_; if (tMin_ == 0 || tIt_ < tMin_) @@ -240,7 +240,7 @@ void TimingOutline::finishedIteration() { /* ************************************************************************* */ size_t getTicTocID(const char *descriptionC) { // disable anything which refers to TimingOutline as well, for good measure -#ifdef GTSAM_USE_BOOST_FEATURES +#if GTSAM_USE_BOOST_FEATURES const std::string description(descriptionC); // Global (static) map from strings to ID numbers and current next ID number static size_t nextId = 0; @@ -263,7 +263,7 @@ size_t getTicTocID(const char *descriptionC) { /* ************************************************************************* */ void tic(size_t id, const char *labelC) { // disable anything which refers to TimingOutline as well, for good measure -#ifdef GTSAM_USE_BOOST_FEATURES +#if GTSAM_USE_BOOST_FEATURES const std::string label(labelC); std::shared_ptr node = // gCurrentTimer.lock()->child(id, label, gCurrentTimer); @@ -275,7 +275,7 @@ void tic(size_t id, const char *labelC) { /* ************************************************************************* */ void toc(size_t id, const char *labelC) { // disable anything which refers to TimingOutline as well, for good measure -#ifdef GTSAM_USE_BOOST_FEATURES +#if GTSAM_USE_BOOST_FEATURES const std::string label(labelC); std::shared_ptr current(gCurrentTimer.lock()); if (id != current->id_) { diff --git a/gtsam/base/timing.h b/gtsam/base/timing.h index 99c55a3d7..cc38f32b8 100644 --- a/gtsam/base/timing.h +++ b/gtsam/base/timing.h @@ -21,7 +21,7 @@ #include #include // for GTSAM_USE_TBB -#ifdef GTSAM_USE_BOOST_FEATURES +#if GTSAM_USE_BOOST_FEATURES #include #endif @@ -107,7 +107,7 @@ // have matching gttic/gttoc statments. You may want to consider reorganizing your timing // outline to match the scope of your code. -#ifdef GTSAM_USE_BOOST_FEATURES +#if GTSAM_USE_BOOST_FEATURES // Automatically use the new Boost timers if version is recent enough. #if BOOST_VERSION >= 104800 # ifndef GTSAM_DISABLE_NEW_TIMERS @@ -165,7 +165,7 @@ namespace gtsam { ChildMap children_; ///< subtrees // disable all timers if not using boost -#ifdef GTSAM_USE_BOOST_FEATURES +#if GTSAM_USE_BOOST_FEATURES #ifdef GTSAM_USING_NEW_BOOST_TIMERS boost::timer::cpu_timer timer_; #else @@ -183,7 +183,7 @@ namespace gtsam { GTSAM_EXPORT TimingOutline(const std::string& label, size_t myId); GTSAM_EXPORT size_t time() const; ///< time taken, including children double secs() const { return double(time()) / 1000000.0;} ///< time taken, in seconds, including children -#ifdef GTSAM_USE_BOOST_FEATURES +#if GTSAM_USE_BOOST_FEATURES double self() const { return double(t_) / 1000000.0;} ///< self time only, in seconds double wall() const { return double(tWall_) / 1000000.0;} ///< wall time, in seconds double min() const { return double(tMin_) / 1000000.0;} ///< min time, in seconds diff --git a/gtsam/nonlinear/LevenbergMarquardtOptimizer.cpp b/gtsam/nonlinear/LevenbergMarquardtOptimizer.cpp index 99682fb77..f6711f0f0 100644 --- a/gtsam/nonlinear/LevenbergMarquardtOptimizer.cpp +++ b/gtsam/nonlinear/LevenbergMarquardtOptimizer.cpp @@ -26,7 +26,7 @@ #include #include #include -#ifdef GTSAM_USE_BOOST_FEATURES +#if GTSAM_USE_BOOST_FEATURES #include #endif @@ -123,7 +123,7 @@ bool LevenbergMarquardtOptimizer::tryLambda(const GaussianFactorGraph& linear, auto currentState = static_cast(state_.get()); bool verbose = (params_.verbosityLM >= LevenbergMarquardtParams::TRYLAMBDA); -#ifdef GTSAM_USE_BOOST_FEATURES +#if GTSAM_USE_BOOST_FEATURES #ifdef GTSAM_USING_NEW_BOOST_TIMERS boost::timer::cpu_timer lamda_iteration_timer; lamda_iteration_timer.start(); @@ -222,7 +222,7 @@ bool LevenbergMarquardtOptimizer::tryLambda(const GaussianFactorGraph& linear, } // if (systemSolvedSuccessfully) if (params_.verbosityLM == LevenbergMarquardtParams::SUMMARY) { -#ifdef GTSAM_USE_BOOST_FEATURES +#if GTSAM_USE_BOOST_FEATURES // do timing #ifdef GTSAM_USING_NEW_BOOST_TIMERS double iterationTime = 1e-9 * lamda_iteration_timer.elapsed().wall; From cd27b7f2ac1f4423064a723a03eb490412d6f1ec Mon Sep 17 00:00:00 2001 From: Gold856 <117957790+Gold856@users.noreply.github.com> Date: Wed, 25 Dec 2024 00:56:12 -0500 Subject: [PATCH 2/4] Add BUILD_SHARED_LIBS as a configurable option Update build logic to match and also prevent conflicting options --- cmake/HandleGeneralOptions.cmake | 10 ++++++---- 1 file changed, 6 insertions(+), 4 deletions(-) diff --git a/cmake/HandleGeneralOptions.cmake b/cmake/HandleGeneralOptions.cmake index 8c56ae242..3282ea682 100644 --- a/cmake/HandleGeneralOptions.cmake +++ b/cmake/HandleGeneralOptions.cmake @@ -21,12 +21,13 @@ if (NOT MSVC) endif() # Configurable Options +option(BUILD_SHARED_LIBS "Build shared libraries" ON) 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(GTSAM_FORCE_SHARED_LIB "Force gtsam to be a shared library, overriding BUILD_SHARED_LIBS" ON) +option(GTSAM_FORCE_SHARED_LIB "Force gtsam to be a shared library, overriding BUILD_SHARED_LIBS" OFF) option(GTSAM_FORCE_STATIC_LIB "Force gtsam to be a static library, overriding BUILD_SHARED_LIBS" OFF) 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) @@ -46,7 +47,9 @@ option(GTSAM_TANGENT_PREINTEGRATION "Use new ImuFactor with integration option(GTSAM_SLOW_BUT_CORRECT_BETWEENFACTOR "Use the slower but correct version of BetweenFactor" OFF) option(GTSAM_SLOW_BUT_CORRECT_EXPMAP "Use slower but correct expmap for Pose2" OFF) -if (GTSAM_FORCE_SHARED_LIB) +if (GTSAM_FORCE_SHARED_LIB AND GTSAM_FORCE_STATIC_LIB) + message(FATAL_ERROR "GTSAM_FORCE_SHARED_LIB and GTSAM_FORCE_STATIC_LIB are both true. Please, to unambiguously select the desired library type to use to build GTSAM, set one of GTSAM_FORCE_SHARED_LIB=ON, GTSAM_FORCE_STATIC_LIB=ON, or BUILD_SHARED_LIBS={ON/OFF}") +elseif (GTSAM_FORCE_SHARED_LIB) message(STATUS "GTSAM is a shared library due to GTSAM_FORCE_SHARED_LIB") set(GTSAM_LIBRARY_TYPE SHARED CACHE STRING "" FORCE) set(GTSAM_SHARED_LIB 1 CACHE BOOL "" FORCE) @@ -55,10 +58,9 @@ elseif (GTSAM_FORCE_STATIC_LIB) set(GTSAM_LIBRARY_TYPE STATIC CACHE STRING "" FORCE) set(GTSAM_SHARED_LIB 0 CACHE BOOL "" FORCE) elseif (BUILD_SHARED_LIBS) - message(STATUS "GTSAM is a shared library due to BUILD_SHARED_LIBS is ON") set(GTSAM_LIBRARY_TYPE SHARED CACHE STRING "" FORCE) set(GTSAM_SHARED_LIB 1 CACHE BOOL "" FORCE) -elseif((DEFINED BUILD_SHARED_LIBS) AND (NOT BUILD_SHARED_LIBS)) +elseif(NOT BUILD_SHARED_LIBS) message(STATUS "GTSAM is a static library due to BUILD_SHARED_LIBS is OFF") set(GTSAM_LIBRARY_TYPE STATIC CACHE STRING "" FORCE) set(GTSAM_SHARED_LIB 0 CACHE BOOL "" FORCE) From 7b9b14e03e2da46f41b788be5df3f0df6b653971 Mon Sep 17 00:00:00 2001 From: Gold856 <117957790+Gold856@users.noreply.github.com> Date: Wed, 1 Jan 2025 00:45:04 -0500 Subject: [PATCH 3/4] Fix building with a shared metis --- gtsam/3rdparty/metis/libmetis/CMakeLists.txt | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/gtsam/3rdparty/metis/libmetis/CMakeLists.txt b/gtsam/3rdparty/metis/libmetis/CMakeLists.txt index 92f931b98..f3b8694f4 100644 --- a/gtsam/3rdparty/metis/libmetis/CMakeLists.txt +++ b/gtsam/3rdparty/metis/libmetis/CMakeLists.txt @@ -13,7 +13,8 @@ if(WIN32) set_target_properties(metis-gtsam PROPERTIES PREFIX "" COMPILE_FLAGS /w - RUNTIME_OUTPUT_DIRECTORY "${PROJECT_BINARY_DIR}/../../../bin") + RUNTIME_OUTPUT_DIRECTORY "${PROJECT_BINARY_DIR}/../../../bin" + WINDOWS_EXPORT_ALL_SYMBOLS ON) endif() if (APPLE) From ebd523eea4ded155412050ba9e164d23b96ff56e Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Wed, 1 Jan 2025 19:23:12 -0500 Subject: [PATCH 4/4] fix naming --- gtsam/discrete/DiscreteFactorGraph.cpp | 13 ++++++------- 1 file changed, 6 insertions(+), 7 deletions(-) diff --git a/gtsam/discrete/DiscreteFactorGraph.cpp b/gtsam/discrete/DiscreteFactorGraph.cpp index 169259a36..227bb4da3 100644 --- a/gtsam/discrete/DiscreteFactorGraph.cpp +++ b/gtsam/discrete/DiscreteFactorGraph.cpp @@ -112,13 +112,12 @@ namespace gtsam { // } /** - * @brief Multiply all the `factors` and normalize the - * product to prevent underflow. + * @brief Multiply all the `factors`. * * @param factors The factors to multiply as a DiscreteFactorGraph. * @return DecisionTreeFactor */ - static DecisionTreeFactor ProductAndNormalize( + static DecisionTreeFactor DiscreteProduct( const DiscreteFactorGraph& factors) { // PRODUCT: multiply all factors gttic(product); @@ -126,10 +125,10 @@ namespace gtsam { gttoc(product); // Max over all the potentials by pretending all keys are frontal: - auto normalizer = product.max(product.size()); + auto denominator = product.max(product.size()); // Normalize the product factor to prevent underflow. - product = product / (*normalizer); + product = product / (*denominator); return product; } @@ -139,7 +138,7 @@ namespace gtsam { std::pair // EliminateForMPE(const DiscreteFactorGraph& factors, const Ordering& frontalKeys) { - DecisionTreeFactor product = ProductAndNormalize(factors); + DecisionTreeFactor product = DiscreteProduct(factors); // max out frontals, this is the factor on the separator gttic(max); @@ -217,7 +216,7 @@ namespace gtsam { std::pair // EliminateDiscrete(const DiscreteFactorGraph& factors, const Ordering& frontalKeys) { - DecisionTreeFactor product = ProductAndNormalize(factors); + DecisionTreeFactor product = DiscreteProduct(factors); // sum out frontals, this is the factor on the separator gttic(sum);