From 0959bfef5c7e206a78e38ded84c4397940ea80ac Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Mon, 20 Jan 2025 02:27:31 -0500 Subject: [PATCH 01/10] replace #ifdef with #if --- gtsam/constrained/NonlinearConstraint.h | 4 ++-- gtsam/constrained/NonlinearEqualityConstraint.h | 8 ++++---- gtsam/constrained/NonlinearInequalityConstraint.h | 6 +++--- 3 files changed, 9 insertions(+), 9 deletions(-) diff --git a/gtsam/constrained/NonlinearConstraint.h b/gtsam/constrained/NonlinearConstraint.h index a01430bf3..f64e8bfc1 100644 --- a/gtsam/constrained/NonlinearConstraint.h +++ b/gtsam/constrained/NonlinearConstraint.h @@ -21,7 +21,7 @@ #include #include #include -#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION +#if GTSAM_ENABLE_BOOST_SERIALIZATION #include #endif @@ -77,7 +77,7 @@ class GTSAM_EXPORT NonlinearConstraint : public NoiseModelFactor { } private: -#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION +#if GTSAM_ENABLE_BOOST_SERIALIZATION /** Serialization function */ friend class boost::serialization::access; template diff --git a/gtsam/constrained/NonlinearEqualityConstraint.h b/gtsam/constrained/NonlinearEqualityConstraint.h index 017ca1607..f8b0205a1 100644 --- a/gtsam/constrained/NonlinearEqualityConstraint.h +++ b/gtsam/constrained/NonlinearEqualityConstraint.h @@ -39,7 +39,7 @@ class GTSAM_EXPORT NonlinearEqualityConstraint : public NonlinearConstraint { virtual ~NonlinearEqualityConstraint() {} private: -#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION +#if GTSAM_ENABLE_BOOST_SERIALIZATION /** Serialization function */ friend class boost::serialization::access; template @@ -85,7 +85,7 @@ class ExpressionEqualityConstraint : public NonlinearEqualityConstraint { } private: -#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION +#if GTSAM_ENABLE_BOOST_SERIALIZATION /** Serialization function */ friend class boost::serialization::access; template @@ -131,7 +131,7 @@ class GTSAM_EXPORT ZeroCostConstraint : public NonlinearEqualityConstraint { } private: -#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION +#if GTSAM_ENABLE_BOOST_SERIALIZATION /** Serialization function */ friend class boost::serialization::access; template @@ -166,7 +166,7 @@ class GTSAM_EXPORT NonlinearEqualityConstraints : public FactorGraph diff --git a/gtsam/constrained/NonlinearInequalityConstraint.h b/gtsam/constrained/NonlinearInequalityConstraint.h index 9dbf1f008..edc2b90e9 100644 --- a/gtsam/constrained/NonlinearInequalityConstraint.h +++ b/gtsam/constrained/NonlinearInequalityConstraint.h @@ -61,7 +61,7 @@ class GTSAM_EXPORT NonlinearInequalityConstraint : public NonlinearConstraint { virtual NoiseModelFactor::shared_ptr penaltyFactorEquality(const double mu = 1.0) const; private: -#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION +#if GTSAM_ENABLE_BOOST_SERIALIZATION /** Serialization function */ friend class boost::serialization::access; template @@ -129,7 +129,7 @@ class GTSAM_EXPORT ScalarExpressionInequalityConstraint : public NonlinearInequa } private: -#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION +#if GTSAM_ENABLE_BOOST_SERIALIZATION /** Serialization function */ friend class boost::serialization::access; template @@ -169,7 +169,7 @@ class GTSAM_EXPORT NonlinearInequalityConstraints const double mu = 1.0) const; private: -#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION +#if GTSAM_ENABLE_BOOST_SERIALIZATION /** Serialization function */ friend class boost::serialization::access; template From a00335ff4a36200af81f57bbcfcac824bc2a0a83 Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Mon, 20 Jan 2025 02:32:17 -0500 Subject: [PATCH 02/10] fully declare struct U --- gtsam/base/std_optional_serialization.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/gtsam/base/std_optional_serialization.h b/gtsam/base/std_optional_serialization.h index 93a5c8dba..265ef1620 100644 --- a/gtsam/base/std_optional_serialization.h +++ b/gtsam/base/std_optional_serialization.h @@ -48,7 +48,7 @@ */ #ifdef __GNUC__ #if __GNUC__ >= 7 && __cplusplus >= 201703L -namespace boost { namespace serialization { struct U; } } +namespace boost { namespace serialization { struct U{}; } } namespace std { template<> struct is_trivially_default_constructible : std::false_type {}; } namespace std { template<> struct is_trivially_copy_constructible : std::false_type {}; } namespace std { template<> struct is_trivially_move_constructible : std::false_type {}; } From aa91159fcbc797730501bcc5861ca969566fbb4c Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Mon, 20 Jan 2025 02:35:20 -0500 Subject: [PATCH 03/10] add Ubuntu 24.04 to the CI --- .github/workflows/build-linux.yml | 29 +++++++++++++++++++++-------- 1 file changed, 21 insertions(+), 8 deletions(-) diff --git a/.github/workflows/build-linux.yml b/.github/workflows/build-linux.yml index 3c1275a55..317b82dfd 100644 --- a/.github/workflows/build-linux.yml +++ b/.github/workflows/build-linux.yml @@ -2,8 +2,8 @@ name: Linux CI on: [pull_request] -# Every time you make a push to your PR, it cancel immediately the previous checks, -# and start a new one. The other runner will be available more quickly to your PR. +# Every time you make a push to your PR, it cancel immediately the previous checks, +# and start a new one. The other runner will be available more quickly to your PR. concurrency: group: ${{ github.workflow }}-${{ github.head_ref || github.run_id }} cancel-in-progress: true @@ -24,12 +24,15 @@ jobs: matrix: # Github Actions requires a single row to be added to the build matrix. # See https://help.github.com/en/articles/workflow-syntax-for-github-actions. - name: [ - ubuntu-20.04-gcc-9, - ubuntu-20.04-clang-9, - ubuntu-22.04-gcc-12, - ubuntu-22.04-clang-14, - ] + name: + [ + ubuntu-20.04-gcc-9, + ubuntu-20.04-clang-9, + ubuntu-22.04-gcc-12, + ubuntu-22.04-clang-14, + ubuntu-24.04-gcc-13, + ubuntu-24.04-clang-16, + ] build_type: [Debug, Release] build_unstable: [ON] @@ -54,6 +57,16 @@ jobs: compiler: clang version: "14" + - name: ubuntu-24.04-gcc-13 + os: ubuntu-24.04 + compiler: gcc + version: "13" + + - name: ubuntu-24.04-clang-16 + os: ubuntu-24.04 + compiler: clang + version: "16" + steps: - name: Checkout uses: actions/checkout@v4 From 3d116d7fdf6eac746a629953cc4d44dea17b6c6b Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Mon, 20 Jan 2025 10:04:06 -0500 Subject: [PATCH 04/10] pass in this to lambda expression explicitly --- .../constrained/InequalityPenaltyFunction.cpp | 26 ++++++++++++------- 1 file changed, 16 insertions(+), 10 deletions(-) diff --git a/gtsam/constrained/InequalityPenaltyFunction.cpp b/gtsam/constrained/InequalityPenaltyFunction.cpp index 2e331292c..238733c97 100644 --- a/gtsam/constrained/InequalityPenaltyFunction.cpp +++ b/gtsam/constrained/InequalityPenaltyFunction.cpp @@ -20,12 +20,15 @@ namespace gtsam { -/* ********************************************************************************************* */ -InequalityPenaltyFunction::UnaryScalarFunc InequalityPenaltyFunction::function() const { - return [=](const double& x, OptionalJacobian<1, 1> H = {}) -> double { return (*this)(x, H); }; +/* ************************************************************************* */ +InequalityPenaltyFunction::UnaryScalarFunc InequalityPenaltyFunction::function() + const { + return [this](const double& x, OptionalJacobian<1, 1> H = {}) { + return this->operator()(x, H); + }; } -/* ********************************************************************************************* */ +/* ************************************************************************* */ double RampFunction::Ramp(const double x, OptionalJacobian<1, 1> H) { if (x < 0) { if (H) { @@ -40,8 +43,9 @@ double RampFunction::Ramp(const double x, OptionalJacobian<1, 1> H) { } } -/* ********************************************************************************************* */ -double SmoothRampPoly2::operator()(const double& x, OptionalJacobian<1, 1> H) const { +/* ************************************************************************* */ +double SmoothRampPoly2::operator()(const double& x, + OptionalJacobian<1, 1> H) const { if (x <= 0) { if (H) { H->setZero(); @@ -60,8 +64,9 @@ double SmoothRampPoly2::operator()(const double& x, OptionalJacobian<1, 1> H) co } } -/* ********************************************************************************************* */ -double SmoothRampPoly3::operator()(const double& x, OptionalJacobian<1, 1> H) const { +/* ************************************************************************* */ +double SmoothRampPoly3::operator()(const double& x, + OptionalJacobian<1, 1> H) const { if (x <= 0) { if (H) { H->setZero(); @@ -80,8 +85,9 @@ double SmoothRampPoly3::operator()(const double& x, OptionalJacobian<1, 1> H) co } } -/* ********************************************************************************************* */ -double SoftPlusFunction::operator()(const double& x, OptionalJacobian<1, 1> H) const { +/* ************************************************************************* */ +double SoftPlusFunction::operator()(const double& x, + OptionalJacobian<1, 1> H) const { if (H) { H->setConstant(1 / (1 + std::exp(-k_ * x))); } From 7eb5ad67e3e9b06fc4b9173623dce33c222d6855 Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Mon, 20 Jan 2025 10:20:01 -0500 Subject: [PATCH 05/10] use reference capture instead of copy capture --- gtsam/geometry/tests/testSO3.cpp | 12 ++++++------ gtsam/navigation/tests/testCombinedImuFactor.cpp | 2 +- gtsam/navigation/tests/testImuFactor.cpp | 4 ++-- .../navigation/tests/testManifoldPreintegration.cpp | 6 +++--- gtsam/navigation/tests/testTangentPreintegration.cpp | 4 ++-- 5 files changed, 14 insertions(+), 14 deletions(-) diff --git a/gtsam/geometry/tests/testSO3.cpp b/gtsam/geometry/tests/testSO3.cpp index 41777ae3a..17b27daea 100644 --- a/gtsam/geometry/tests/testSO3.cpp +++ b/gtsam/geometry/tests/testSO3.cpp @@ -333,7 +333,7 @@ TEST(SO3, CrossB) { Matrix aH1; for (bool nearZero : {true, false}) { std::function f = - [=](const Vector3& omega, const Vector3& v) { + [nearZero](const Vector3& omega, const Vector3& v) { return so3::DexpFunctor(omega, nearZero).crossB(v); }; for (const Vector3& omega : test_cases::omegas(nearZero)) { @@ -351,7 +351,7 @@ TEST(SO3, DoubleCrossC) { Matrix aH1; for (bool nearZero : {true, false}) { std::function f = - [=](const Vector3& omega, const Vector3& v) { + [nearZero](const Vector3& omega, const Vector3& v) { return so3::DexpFunctor(omega, nearZero).doubleCrossC(v); }; for (const Vector3& omega : test_cases::omegas(nearZero)) { @@ -369,7 +369,7 @@ TEST(SO3, ApplyDexp) { Matrix aH1, aH2; for (bool nearZero : {true, false}) { std::function f = - [=](const Vector3& omega, const Vector3& v) { + [nearZero](const Vector3& omega, const Vector3& v) { return so3::DexpFunctor(omega, nearZero).applyDexp(v); }; for (const Vector3& omega : test_cases::omegas(nearZero)) { @@ -390,7 +390,7 @@ TEST(SO3, ApplyInvDexp) { Matrix aH1, aH2; for (bool nearZero : {true, false}) { std::function f = - [=](const Vector3& omega, const Vector3& v) { + [nearZero](const Vector3& omega, const Vector3& v) { return so3::DexpFunctor(omega, nearZero).applyInvDexp(v); }; for (const Vector3& omega : test_cases::omegas(nearZero)) { @@ -412,7 +412,7 @@ TEST(SO3, ApplyLeftJacobian) { Matrix aH1, aH2; for (bool nearZero : {true, false}) { std::function f = - [=](const Vector3& omega, const Vector3& v) { + [nearZero](const Vector3& omega, const Vector3& v) { return so3::DexpFunctor(omega, nearZero).applyLeftJacobian(v); }; for (const Vector3& omega : test_cases::omegas(nearZero)) { @@ -433,7 +433,7 @@ TEST(SO3, ApplyLeftJacobianInverse) { Matrix aH1, aH2; for (bool nearZero : {true, false}) { std::function f = - [=](const Vector3& omega, const Vector3& v) { + [nearZero](const Vector3& omega, const Vector3& v) { return so3::DexpFunctor(omega, nearZero).applyLeftJacobianInverse(v); }; for (const Vector3& omega : test_cases::omegas(nearZero)) { diff --git a/gtsam/navigation/tests/testCombinedImuFactor.cpp b/gtsam/navigation/tests/testCombinedImuFactor.cpp index c4fefb8ff..80a7b0298 100644 --- a/gtsam/navigation/tests/testCombinedImuFactor.cpp +++ b/gtsam/navigation/tests/testCombinedImuFactor.cpp @@ -144,7 +144,7 @@ TEST(CombinedImuFactor, FirstOrderPreIntegratedMeasurements) { auto p = testing::Params(); testing::SomeMeasurements measurements; - auto preintegrated = [=](const Vector3& a, const Vector3& w) { + auto preintegrated = [&](const Vector3& a, const Vector3& w) { PreintegratedImuMeasurements pim(p, Bias(a, w)); testing::integrateMeasurements(measurements, &pim); return pim.preintegrated(); diff --git a/gtsam/navigation/tests/testImuFactor.cpp b/gtsam/navigation/tests/testImuFactor.cpp index d4bc763ee..2e1528ae8 100644 --- a/gtsam/navigation/tests/testImuFactor.cpp +++ b/gtsam/navigation/tests/testImuFactor.cpp @@ -399,7 +399,7 @@ TEST(ImuFactor, PartialDerivative_wrt_Bias) { Vector3 measuredOmega(0.1, 0, 0); double deltaT = 0.5; - auto evaluateRotation = [=](const Vector3 biasOmega) { + auto evaluateRotation = [&measuredOmega, &deltaT](const Vector3 biasOmega) { return Rot3::Expmap((measuredOmega - biasOmega) * deltaT); }; @@ -424,7 +424,7 @@ TEST(ImuFactor, PartialDerivativeLogmap) { // Measurements Vector3 deltaTheta(0, 0, 0); - auto evaluateLogRotation = [=](const Vector3 delta) { + auto evaluateLogRotation = [&thetaHat](const Vector3 delta) { return Rot3::Logmap( Rot3::Expmap(thetaHat).compose(Rot3::Expmap(delta))); }; diff --git a/gtsam/navigation/tests/testManifoldPreintegration.cpp b/gtsam/navigation/tests/testManifoldPreintegration.cpp index 82f9876fb..f9c6ebacb 100644 --- a/gtsam/navigation/tests/testManifoldPreintegration.cpp +++ b/gtsam/navigation/tests/testManifoldPreintegration.cpp @@ -43,21 +43,21 @@ TEST(ManifoldPreintegration, BiasCorrectionJacobians) { testing::SomeMeasurements measurements; std::function deltaRij = - [=](const Vector3& a, const Vector3& w) { + [&](const Vector3& a, const Vector3& w) { ManifoldPreintegration pim(testing::Params(), Bias(a, w)); testing::integrateMeasurements(measurements, &pim); return pim.deltaRij(); }; std::function deltaPij = - [=](const Vector3& a, const Vector3& w) { + [&](const Vector3& a, const Vector3& w) { ManifoldPreintegration pim(testing::Params(), Bias(a, w)); testing::integrateMeasurements(measurements, &pim); return pim.deltaPij(); }; std::function deltaVij = - [=](const Vector3& a, const Vector3& w) { + [&](const Vector3& a, const Vector3& w) { ManifoldPreintegration pim(testing::Params(), Bias(a, w)); testing::integrateMeasurements(measurements, &pim); return pim.deltaVij(); diff --git a/gtsam/navigation/tests/testTangentPreintegration.cpp b/gtsam/navigation/tests/testTangentPreintegration.cpp index af91f4f2c..73cea9f71 100644 --- a/gtsam/navigation/tests/testTangentPreintegration.cpp +++ b/gtsam/navigation/tests/testTangentPreintegration.cpp @@ -78,7 +78,7 @@ TEST(ImuFactor, BiasCorrectionJacobians) { testing::SomeMeasurements measurements; std::function preintegrated = - [=](const Vector3& a, const Vector3& w) { + [&](const Vector3& a, const Vector3& w) { TangentPreintegration pim(testing::Params(), Bias(a, w)); testing::integrateMeasurements(measurements, &pim); return pim.preintegrated(); @@ -149,7 +149,7 @@ TEST(TangentPreintegration, Compose) { TEST(TangentPreintegration, MergedBiasDerivatives) { testing::SomeMeasurements measurements; - auto f = [=](const Vector3& a, const Vector3& w) { + auto f = [&](const Vector3& a, const Vector3& w) { TangentPreintegration pim02(testing::Params(), Bias(a, w)); testing::integrateMeasurements(measurements, &pim02); testing::integrateMeasurements(measurements, &pim02); From 36758a818fb8e0a1da384eb44e90edb86be10a16 Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Mon, 20 Jan 2025 10:20:21 -0500 Subject: [PATCH 06/10] add comment and remove unnecessary copy-constructor --- gtsam/base/std_optional_serialization.h | 1 + gtsam/base/tests/testStdOptionalSerialization.cpp | 2 -- 2 files changed, 1 insertion(+), 2 deletions(-) diff --git a/gtsam/base/std_optional_serialization.h b/gtsam/base/std_optional_serialization.h index 265ef1620..db5e994e9 100644 --- a/gtsam/base/std_optional_serialization.h +++ b/gtsam/base/std_optional_serialization.h @@ -48,6 +48,7 @@ */ #ifdef __GNUC__ #if __GNUC__ >= 7 && __cplusplus >= 201703L +// Based on https://github.com/borglab/gtsam/issues/1738, we define U as a complete type. namespace boost { namespace serialization { struct U{}; } } namespace std { template<> struct is_trivially_default_constructible : std::false_type {}; } namespace std { template<> struct is_trivially_copy_constructible : std::false_type {}; } diff --git a/gtsam/base/tests/testStdOptionalSerialization.cpp b/gtsam/base/tests/testStdOptionalSerialization.cpp index d9bd1da4a..3c1310aa6 100644 --- a/gtsam/base/tests/testStdOptionalSerialization.cpp +++ b/gtsam/base/tests/testStdOptionalSerialization.cpp @@ -60,8 +60,6 @@ public: TestOptionalStruct() = default; TestOptionalStruct(const int& opt) : opt(opt) {} - // A copy constructor is needed for serialization - TestOptionalStruct(const TestOptionalStruct& other) = default; bool operator==(const TestOptionalStruct& other) const { // check the values are equal return *opt == *other.opt; From c2ee7ff12263699bcb5492b59ff74d86934d5227 Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Mon, 20 Jan 2025 10:24:57 -0500 Subject: [PATCH 07/10] bracket clang and GCC --- .github/workflows/build-linux.yml | 22 +++++----------------- 1 file changed, 5 insertions(+), 17 deletions(-) diff --git a/.github/workflows/build-linux.yml b/.github/workflows/build-linux.yml index 317b82dfd..b4b391df3 100644 --- a/.github/workflows/build-linux.yml +++ b/.github/workflows/build-linux.yml @@ -24,13 +24,11 @@ jobs: matrix: # Github Actions requires a single row to be added to the build matrix. # See https://help.github.com/en/articles/workflow-syntax-for-github-actions. - name: - [ + name: [ + # "Bracket" the versions from GCC [9-14] and Clang [9-16] ubuntu-20.04-gcc-9, ubuntu-20.04-clang-9, - ubuntu-22.04-gcc-12, - ubuntu-22.04-clang-14, - ubuntu-24.04-gcc-13, + ubuntu-24.04-gcc-14, ubuntu-24.04-clang-16, ] @@ -47,20 +45,10 @@ jobs: compiler: clang version: "9" - - name: ubuntu-22.04-gcc-12 - os: ubuntu-22.04 - compiler: gcc - version: "11" - - - name: ubuntu-22.04-clang-14 - os: ubuntu-22.04 - compiler: clang - version: "14" - - - name: ubuntu-24.04-gcc-13 + - name: ubuntu-24.04-gcc-14 os: ubuntu-24.04 compiler: gcc - version: "13" + version: "14" - name: ubuntu-24.04-clang-16 os: ubuntu-24.04 From 5ce332764c0f466ceddacb18559ecfa5455d1a5d Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Mon, 20 Jan 2025 10:27:11 -0500 Subject: [PATCH 08/10] don't install boost if no_boost flag is set --- .github/workflows/build-special.yml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/.github/workflows/build-special.yml b/.github/workflows/build-special.yml index 3a7dd974d..eb1d96fdc 100644 --- a/.github/workflows/build-special.yml +++ b/.github/workflows/build-special.yml @@ -116,7 +116,7 @@ jobs: fi - name: Install Boost - if: runner.os == 'Linux' + if: runner.os == 'Linux' && matrix.flag != 'no_boost' run: | sudo apt-get -y install libboost-all-dev From cdb761c603c848088395d5af52f5b92562cbb122 Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Mon, 20 Jan 2025 10:43:36 -0500 Subject: [PATCH 09/10] update unix.sh to set Boost flags from env variable correctly --- .github/scripts/unix.sh | 2 ++ 1 file changed, 2 insertions(+) diff --git a/.github/scripts/unix.sh b/.github/scripts/unix.sh index 09fcd788b..b2e960fc1 100644 --- a/.github/scripts/unix.sh +++ b/.github/scripts/unix.sh @@ -52,6 +52,8 @@ function configure() -DGTSAM_POSE3_EXPMAP=${GTSAM_POSE3_EXPMAP:-ON} \ -DGTSAM_USE_SYSTEM_EIGEN=${GTSAM_USE_SYSTEM_EIGEN:-OFF} \ -DGTSAM_USE_SYSTEM_METIS=${GTSAM_USE_SYSTEM_METIS:-OFF} \ + -DGTSAM_USE_BOOST_FEATURES=${GTSAM_USE_BOOST_FEATURES:-ON} \ + -DGTSAM_ENABLE_BOOST_SERIALIZATION=${GTSAM_ENABLE_BOOST_SERIALIZATION:-ON} \ -DGTSAM_BUILD_WITH_MARCH_NATIVE=OFF \ -DGTSAM_SINGLE_TEST_EXE=OFF } From 08fc4885f7d198b2fb4efdd387e8cdd71a2a3b5c Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Mon, 20 Jan 2025 10:45:04 -0500 Subject: [PATCH 10/10] check for boost all in one step --- .github/workflows/build-special.yml | 22 +++++++++++++--------- 1 file changed, 13 insertions(+), 9 deletions(-) diff --git a/.github/workflows/build-special.yml b/.github/workflows/build-special.yml index eb1d96fdc..d0a182975 100644 --- a/.github/workflows/build-special.yml +++ b/.github/workflows/build-special.yml @@ -2,8 +2,8 @@ name: Special Cases CI on: [pull_request] -# Every time you make a push to your PR, it cancel immediately the previous checks, -# and start a new one. The other runner will be available more quickly to your PR. +# Every time you make a push to your PR, it cancel immediately the previous checks, +# and start a new one. The other runner will be available more quickly to your PR. concurrency: group: ${{ github.workflow }}-${{ github.head_ref || github.run_id }} cancel-in-progress: true @@ -115,19 +115,24 @@ jobs: echo "CXX=clang++-${{ matrix.version }}" >> $GITHUB_ENV fi - - name: Install Boost - if: runner.os == 'Linux' && matrix.flag != 'no_boost' - run: | - sudo apt-get -y install libboost-all-dev - - name: Install (macOS) if: runner.os == 'macOS' run: | - brew install cmake ninja boost + brew install cmake ninja sudo xcode-select -switch /Applications/Xcode_${{ matrix.version }}.app echo "CC=clang" >> $GITHUB_ENV echo "CXX=clang++" >> $GITHUB_ENV + - name: Install Boost + run: | + if [ ${{matrix.flag}} != 'no_boost' ]; then + if [ ${{runner.os}} == 'Linux' ]; then + sudo apt-get -y install libboost-all-dev + elif [ ${{runner.os}} == 'macOS' ]; then + brew install boost + fi + fi + - name: Set Allow Deprecated Flag if: matrix.flag == 'deprecated' run: | @@ -181,7 +186,6 @@ jobs: with: swap-size-gb: 12 - - name: Build & Test run: | bash .github/scripts/unix.sh -t