Skip to content

Commit

Permalink
auto type conversion
Browse files Browse the repository at this point in the history
  • Loading branch information
koide3 committed Aug 28, 2024
1 parent 7f932ab commit 091ba05
Showing 1 changed file with 14 additions and 0 deletions.
14 changes: 14 additions & 0 deletions include/gtsam_points/types/gaussian_voxelmap.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -131,6 +131,20 @@ std::enable_if_t<!std::is_same_v<VoxelMapPtr, GaussianVoxelMap::ConstPtr>, doubl
return overlap_gpu(targets_, source, Ts_target_source, stream);
}

/// @brief Calculate the fraction of points fell in targets' voxels on GPU
template <typename VoxelMapPtr, typename PointCloudPtr>
std::
enable_if_t<!std::is_same_v<VoxelMapPtr, GaussianVoxelMap::ConstPtr> || !std::is_same_v<PointCloudPtr, PointCloud::ConstPtr>, std::vector<double>>
overlap_gpu(
const std::vector<VoxelMapPtr>& targets,
const std::vector<PointCloudPtr>& sources,
const std::vector<Eigen::Isometry3d>& Ts_target_source,
CUstream_st* stream = 0) {
const std::vector<GaussianVoxelMap::ConstPtr> targets_(targets.begin(), targets.end());
const std::vector<PointCloud::ConstPtr> sources_(sources.begin(), sources.end());
return overlap_gpu(targets_, sources_, Ts_target_source, stream);
}

// Automatically select CPU or GPU method
double overlap_auto(const GaussianVoxelMap::ConstPtr& target, const PointCloud::ConstPtr& source, const Eigen::Isometry3d& T_target_source);

Expand Down

0 comments on commit 091ba05

Please sign in to comment.