Skip to content

Commit

Permalink
Style changes in voxelization and preprocessing utilities (#364)
Browse files Browse the repository at this point in the history
* Unify Voxel functionalities, now everything comes from VoxelHashMap

* This looks like an even better unification

* Modernize VoxelDownsample

* VoxelUtils is born, now everthing is liteally in one place, and we have
some side effect code reduction

* Macos does not like my include

* Local style include

* With move

* As of benchmark

* For each for the win

* Remove unnecessary include

* Const correcteness

* Refresh changes

* Add style changes for a separate PR

* Add missing headers

* Remove more raw for loops

* Move Voxeldownsample into VoxelUtils

* Cmake needs to know

* Miss cpp

* Remove duplicate

* cmake-format

* Format

* We never used noexcept anywhere, why adding it now?

* We always use frame, if we want to move point_cloud, let's do it in a
seprate PR

* put back whitespaces

* reduce diff

---------

Co-authored-by: tizianoGuadagnino <[email protected]>
Co-authored-by: Luca Lobefaro <[email protected]>
Co-authored-by: Benedikt Mersch <[email protected]>
  • Loading branch information
4 people authored Jul 22, 2024
1 parent a9f527d commit 1c28d17
Show file tree
Hide file tree
Showing 7 changed files with 40 additions and 35 deletions.
3 changes: 2 additions & 1 deletion cpp/kiss_icp/core/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -21,6 +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 Preprocessing.cpp Threshold.cpp)
target_sources(kiss_icp_core PRIVATE Registration.cpp Deskew.cpp VoxelHashMap.cpp VoxelUtils.cpp Preprocessing.cpp
Threshold.cpp)
target_link_libraries(kiss_icp_core PUBLIC Eigen3::Eigen tsl::robin_map TBB::tbb Sophus::Sophus)
set_global_target_properties(kiss_icp_core)
18 changes: 0 additions & 18 deletions cpp/kiss_icp/core/Preprocessing.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -34,24 +34,6 @@
#include "VoxelUtils.hpp"

namespace kiss_icp {
std::vector<Eigen::Vector3d> VoxelDownsample(const std::vector<Eigen::Vector3d> &frame,
double voxel_size) {
tsl::robin_map<Voxel, Eigen::Vector3d, VoxelHash> grid;
grid.reserve(frame.size());
for (const auto &point : frame) {
const auto voxel = PointToVoxel(point, voxel_size);
if (grid.contains(voxel)) continue;
grid.insert({voxel, point});
}
std::vector<Eigen::Vector3d> frame_dowsampled;
frame_dowsampled.reserve(grid.size());
for (const auto &[voxel, point] : grid) {
(void)voxel;
frame_dowsampled.emplace_back(point);
}
return frame_dowsampled;
}

std::vector<Eigen::Vector3d> Preprocess(const std::vector<Eigen::Vector3d> &frame,
double max_range,
double min_range) {
Expand Down
3 changes: 0 additions & 3 deletions cpp/kiss_icp/core/Preprocessing.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -37,7 +37,4 @@ std::vector<Eigen::Vector3d> Preprocess(const std::vector<Eigen::Vector3d> &fram
/// Originally introduced the calibration factor)
std::vector<Eigen::Vector3d> CorrectKITTIScan(const std::vector<Eigen::Vector3d> &frame);

/// Voxelize point cloud keeping the original coordinates
std::vector<Eigen::Vector3d> VoxelDownsample(const std::vector<Eigen::Vector3d> &frame,
double voxel_size);
} // namespace kiss_icp
12 changes: 4 additions & 8 deletions cpp/kiss_icp/core/VoxelHashMap.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -37,9 +37,8 @@ std::vector<Eigen::Vector3d> VoxelHashMap::GetPoints(const std::vector<Voxel> &q
std::for_each(query_voxels.cbegin(), query_voxels.cend(), [&](const auto &query) {
auto search = map_.find(query);
if (search != map_.end()) {
for (const auto &point : search->second.points) {
points.emplace_back(point);
}
const auto &voxel_points = search->second.points;
points.insert(points.end(), voxel_points.cbegin(), voxel_points.cend());
}
});
points.shrink_to_fit();
Expand All @@ -50,11 +49,8 @@ std::vector<Eigen::Vector3d> VoxelHashMap::Pointcloud() const {
std::vector<Eigen::Vector3d> points;
points.reserve(map_.size() * static_cast<size_t>(max_points_per_voxel_));
std::for_each(map_.cbegin(), map_.cend(), [&](const auto &map_element) {
const auto &[voxel, voxel_block] = map_element;
(void)voxel;
for (const auto &point : voxel_block.points) {
points.emplace_back(point);
}
const auto &voxel_points = map_element.second.points;
points.insert(points.end(), voxel_points.cbegin(), voxel_points.cend());
});
points.shrink_to_fit();
return points;
Expand Down
2 changes: 1 addition & 1 deletion cpp/kiss_icp/core/VoxelHashMap.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -62,6 +62,6 @@ struct VoxelHashMap {
double voxel_size_;
double max_distance_;
int max_points_per_voxel_;
tsl::robin_map<Voxel, VoxelBlock, VoxelHash> map_;
tsl::robin_map<Voxel, VoxelBlock> map_;
};
} // namespace kiss_icp
23 changes: 23 additions & 0 deletions cpp/kiss_icp/core/VoxelUtils.cpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,23 @@
#include "VoxelUtils.hpp"

#include <tsl/robin_map.h>

namespace kiss_icp {

std::vector<Eigen::Vector3d> VoxelDownsample(const std::vector<Eigen::Vector3d> &frame,
const double voxel_size) {
tsl::robin_map<Voxel, Eigen::Vector3d> grid;
grid.reserve(frame.size());
std::for_each(frame.cbegin(), frame.cend(), [&](const auto &point) {
const auto voxel = PointToVoxel(point, voxel_size);
if (!grid.contains(voxel)) grid.insert({voxel, point});
});
std::vector<Eigen::Vector3d> frame_dowsampled;
frame_dowsampled.reserve(grid.size());
std::for_each(grid.cbegin(), grid.cend(), [&](const auto &voxel_and_point) {
frame_dowsampled.emplace_back(voxel_and_point.second);
});
return frame_dowsampled;
}

} // namespace kiss_icp
14 changes: 10 additions & 4 deletions cpp/kiss_icp/core/VoxelUtils.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -25,21 +25,27 @@

#include <Eigen/Core>
#include <cmath>
#include <vector>

namespace kiss_icp {

using Voxel = Eigen::Vector3i;

inline Voxel PointToVoxel(const Eigen::Vector3d &point, const double voxel_size) {
return Voxel(static_cast<int>(std::floor(point.x() / voxel_size)),
static_cast<int>(std::floor(point.y() / voxel_size)),
static_cast<int>(std::floor(point.z() / voxel_size)));
}

struct VoxelHash {
size_t operator()(const Voxel &voxel) const {
/// Voxelize a point cloud keeping the original coordinates
std::vector<Eigen::Vector3d> VoxelDownsample(const std::vector<Eigen::Vector3d> &frame,
const double voxel_size);

} // namespace kiss_icp

template <>
struct std::hash<kiss_icp::Voxel> {
std::size_t operator()(const kiss_icp::Voxel &voxel) const {
const uint32_t *vec = reinterpret_cast<const uint32_t *>(voxel.data());
return (vec[0] * 73856093 ^ vec[1] * 19349669 ^ vec[2] * 83492791);
}
};
} // namespace kiss_icp

0 comments on commit 1c28d17

Please sign in to comment.