diff --git a/include/gtsam_points/factors/impl/integrated_ct_gicp_factor_impl.hpp b/include/gtsam_points/factors/impl/integrated_ct_gicp_factor_impl.hpp index 09574ee..d451343 100644 --- a/include/gtsam_points/factors/impl/integrated_ct_gicp_factor_impl.hpp +++ b/include/gtsam_points/factors/impl/integrated_ct_gicp_factor_impl.hpp @@ -77,7 +77,7 @@ double IntegratedCT_GICPFactor_::error(const gtsam::Va return error; }; - if (is_omp_default() || num_threads == 1) { + if (is_omp_default() || this->num_threads == 1) { return scan_matching_reduce_omp(perpoint_task, frame::size(*this->source), this->num_threads, nullptr, nullptr, nullptr, nullptr, nullptr); } else { return scan_matching_reduce_tbb(perpoint_task, frame::size(*this->source), nullptr, nullptr, nullptr, nullptr, nullptr); @@ -142,7 +142,7 @@ boost::shared_ptr IntegratedCT_GICPFactor_num_threads == 1) { error = scan_matching_reduce_omp(perpoint_task, frame::size(*this->source), this->num_threads, &H_00, &H_11, &H_01, &b_0, &b_1); } else { error = scan_matching_reduce_tbb(perpoint_task, frame::size(*this->source), &H_00, &H_11, &H_01, &b_0, &b_1); @@ -184,7 +184,7 @@ void IntegratedCT_GICPFactor_::update_correspondences( } }; - if (is_omp_default() || num_threads == 1) { + if (is_omp_default() || this->num_threads == 1) { #pragma omp parallel for num_threads(this->num_threads) schedule(guided, 8) for (int i = 0; i < frame::size(*this->source); i++) { perpoint_task(i); diff --git a/src/gtsam_points/util/covariance_estimation.cpp b/src/gtsam_points/util/covariance_estimation.cpp index 468ba49..0a1210e 100644 --- a/src/gtsam_points/util/covariance_estimation.cpp +++ b/src/gtsam_points/util/covariance_estimation.cpp @@ -54,7 +54,7 @@ std::vector estimate_covariances(const Eigen::Vector4d* points, } }; - if (is_omp_default() || num_threads == 1) { + if (is_omp_default() || params.num_threads == 1) { #pragma omp parallel for num_threads(params.num_threads) schedule(guided, 8) for (int i = 0; i < num_points; i++) { perpoint_task(i); diff --git a/src/test/test_colored_gicp.cpp b/src/test/test_colored_gicp.cpp index 5cc8168..1cc13f6 100644 --- a/src/test/test_colored_gicp.cpp +++ b/src/test/test_colored_gicp.cpp @@ -117,7 +117,7 @@ TEST_P(ColoredGICPTest, AlignmentTest) { const auto param = GetParam(); const std::string method = std::get<0>(param); const std::string parallelism = std::get<1>(param); - const int num_threads = parallelism == "OMP" ? 2 : 1; + const int num_threads = parallelism == "NONE" ? 1 : 2; if (parallelism == "TBB") { gtsam_points::set_tbb_as_default(); diff --git a/src/test/test_continuous_time.cpp b/src/test/test_continuous_time.cpp index f3c1801..f821325 100644 --- a/src/test/test_continuous_time.cpp +++ b/src/test/test_continuous_time.cpp @@ -83,7 +83,7 @@ TEST_P(ContinuousTimeFactorTest, AlignmentTest) { const auto param = GetParam(); const std::string method = std::get<0>(param); const std::string parallelism = std::get<1>(param); - const int num_threads = parallelism == "OMP" ? 2 : 1; + const int num_threads = parallelism == "NONE" ? 1 : 2; if (parallelism == "TBB") { gtsam_points::set_tbb_as_default(); diff --git a/src/test/test_loam_factors.cpp b/src/test/test_loam_factors.cpp index 47b0d5e..e7074e2 100644 --- a/src/test/test_loam_factors.cpp +++ b/src/test/test_loam_factors.cpp @@ -80,7 +80,7 @@ class LOAMFactorTest : public LOAMTestBase, public testing::WithParamInterface(param); const std::string parallelism = std::get<1>(param); - const int num_threads = parallelism == "OMP" ? 2 : 1; + const int num_threads = parallelism == "NONE" ? 1 : 2; gtsam::NonlinearFactor::shared_ptr factor; if (method == "LOAM") {