diff --git a/.github/workflows/cpp.yml b/.github/workflows/cpp.yml index 131dda9e..bbb8ef8a 100644 --- a/.github/workflows/cpp.yml +++ b/.github/workflows/cpp.yml @@ -25,3 +25,32 @@ jobs: run: cmake -B ${{github.workspace}}/build -DCMAKE_BUILD_TYPE=${{env.BUILD_TYPE}} ${{github.workspace}}/cpp/kiss_icp - name: Build run: cmake --build ${{github.workspace}}/build --config ${{env.BUILD_TYPE}} + + # As the previous job will always install the dependencies from cmake, and this is guaranteed to + # work, we also want to support dev sandboxes where the main dependencies are already + # pre-installed in the system. For now, we only support dev machines under a GNU/Linux + # environmnets. If you are reading this and need the same functionallity in Windows/macOS please + # open a ticket. + cpp_api_dev: + runs-on: ${{ matrix.os }} + strategy: + matrix: + os: [ubuntu-22.04, ubuntu-20.04] + + steps: + - uses: actions/checkout@v3 + - name: Cache dependencies + uses: actions/cache@v2 + with: + path: ~/.apt/cache + key: ${{ runner.os }}-apt-${{ hashFiles('**/ubuntu_dependencies.yml') }} + restore-keys: | + ${{ runner.os }}-apt- + - name: Install dependencies + run: | + sudo apt-get update + sudo apt-get install -y build-essential cmake git libeigen3-dev libtbb-dev + - name: Configure CMake + run: cmake -B ${{github.workspace}}/build -DCMAKE_BUILD_TYPE=${{env.BUILD_TYPE}} ${{github.workspace}}/cpp/kiss_icp + - name: Build + run: cmake --build ${{github.workspace}}/build --config ${{env.BUILD_TYPE}} diff --git a/cpp/kiss_icp/core/Deskew.cpp b/cpp/kiss_icp/core/Deskew.cpp index 9b721fe2..fe20b77e 100644 --- a/cpp/kiss_icp/core/Deskew.cpp +++ b/cpp/kiss_icp/core/Deskew.cpp @@ -39,6 +39,7 @@ std::vector DeSkewScan(const std::vector &fram const Sophus::SE3d &delta) { const auto delta_pose = delta.log(); std::vector corrected_frame(frame.size()); + // TODO(All): This tbb execution is ignoring the max_n_threads config value tbb::parallel_for(size_t(0), frame.size(), [&](size_t i) { const auto motion = Sophus::SE3d::exp((timestamps[i] - mid_pose_timestamp) * delta_pose); corrected_frame[i] = motion * frame[i]; diff --git a/cpp/kiss_icp/core/Registration.cpp b/cpp/kiss_icp/core/Registration.cpp index d7adb4df..137fa50c 100644 --- a/cpp/kiss_icp/core/Registration.cpp +++ b/cpp/kiss_icp/core/Registration.cpp @@ -26,6 +26,7 @@ #include #include #include +#include #include #include @@ -171,7 +172,8 @@ Registration::Registration(int max_num_iteration, double convergence_criterion, : max_num_iterations_(max_num_iteration), convergence_criterion_(convergence_criterion), // Only manipulate the number of threads if the user specifies something greater than 0 - max_num_threads_(max_num_threads > 0 ? max_num_threads : tbb::info::default_concurrency()) { + max_num_threads_(max_num_threads > 0 ? max_num_threads + : tbb::this_task_arena::max_concurrency()) { // This global variable requires static duration storage to be able to manipulate the max // concurrency from TBB across the entire class static const auto tbb_control_settings = tbb::global_control(