Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Adds in a class for performing parallel operations with n threads #400

Open
wants to merge 1 commit into
base: main
Choose a base branch
from
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
4 changes: 2 additions & 2 deletions cpp/kiss_icp/core/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -21,7 +21,7 @@
# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE
# SOFTWARE.
add_library(kiss_icp_core STATIC)
target_sources(kiss_icp_core PRIVATE Registration.cpp Deskew.cpp VoxelHashMap.cpp VoxelUtils.cpp Preprocessing.cpp
Threshold.cpp)
target_sources(kiss_icp_core PUBLIC Registration.cpp Deskew.cpp VoxelHashMap.cpp VoxelUtils.cpp Preprocessing.cpp
Threshold.cpp Parallel.cpp)
target_link_libraries(kiss_icp_core PUBLIC Eigen3::Eigen tsl::robin_map TBB::tbb Sophus::Sophus)
set_global_target_properties(kiss_icp_core)
13 changes: 8 additions & 5 deletions cpp/kiss_icp/core/Deskew.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -21,8 +21,7 @@
// OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE
// SOFTWARE.
#include "Deskew.hpp"

#include <tbb/parallel_for.h>
#include "Parallel.hpp"

#include <Eigen/Core>
#include <sophus/se3.hpp>
Expand All @@ -36,11 +35,15 @@ constexpr double mid_pose_timestamp{0.5};
namespace kiss_icp {
std::vector<Eigen::Vector3d> DeSkewScan(const std::vector<Eigen::Vector3d> &frame,
const std::vector<double> &timestamps,
const Sophus::SE3d &delta) {
const Sophus::SE3d &delta,
int max_n_threads) {
// We trust this will not change as the config will not change over the duration of the run.
static parallel::NParallel n_parallel(max_n_threads);

const auto delta_pose = delta.log();
std::vector<Eigen::Vector3d> 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) {

n_parallel.n_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];
});
Expand Down
3 changes: 2 additions & 1 deletion cpp/kiss_icp/core/Deskew.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -31,6 +31,7 @@ namespace kiss_icp {
/// Compensate the frame by interpolating the delta pose
std::vector<Eigen::Vector3d> DeSkewScan(const std::vector<Eigen::Vector3d> &frame,
const std::vector<double> &timestamps,
const Sophus::SE3d &delta);
const Sophus::SE3d &delta,
int max_n_threads);

} // namespace kiss_icp
10 changes: 10 additions & 0 deletions cpp/kiss_icp/core/Parallel.cpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,10 @@
#include "Parallel.hpp"

namespace kiss_icp::parallel {
NParallel::NParallel(int num_threads) : number_of_threads_(num_threads), arena_(number_of_threads_) {}

auto NParallel::get_max_threads() -> int {
return number_of_threads_;
}

}
27 changes: 27 additions & 0 deletions cpp/kiss_icp/core/Parallel.hpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,27 @@
#include <tbb/parallel_for.h>
#include <tbb/parallel_reduce.h>
#include <tbb/task_arena.h>

namespace kiss_icp::parallel {

class NParallel{
public:
NParallel(int n);
auto get_max_threads() -> int;

template <typename Index, typename Function>
void n_for(Index begin, Index end, const Function& func);

private:
int number_of_threads_;
tbb::task_arena arena_;
};

template <typename Index, typename Function>
void NParallel::n_for(Index begin, Index end, const Function& func) {
arena_.execute([&]() {
tbb::parallel_for(begin, end, func);
});
}

} // namespace kiss_icp::parallel
2 changes: 1 addition & 1 deletion cpp/kiss_icp/pipeline/KissICP.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -37,7 +37,7 @@ KissICP::Vector3dVectorTuple KissICP::RegisterFrame(const std::vector<Eigen::Vec
const std::vector<double> &timestamps) {
const auto &deskew_frame = [&]() -> std::vector<Eigen::Vector3d> {
if (!config_.deskew || timestamps.empty()) return frame;
return DeSkewScan(frame, timestamps, last_delta_);
return DeSkewScan(frame, timestamps, last_delta_, config_.max_num_threads);
}();
return RegisterFrame(deskew_frame);
}
Expand Down
Loading