Skip to content

Commit da104ce

Browse files
Merge branch 'main' into tiziano/bonxai_minimal
2 parents 9b84286 + 18536b9 commit da104ce

File tree

8 files changed

+31
-39
lines changed

8 files changed

+31
-39
lines changed

Makefile

Lines changed: 5 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,5 @@
1+
.PHONY: cpp
2+
3+
cpp:
4+
@cmake -Bbuild cpp/kinematic_icp/
5+
@cmake --build build -j$(nproc --all)

cpp/kinematic_icp/3rdparty/kiss_icp/kiss-icp.cmake

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -26,6 +26,6 @@ if(CMAKE_VERSION VERSION_GREATER 3.24)
2626
endif()
2727

2828
include(FetchContent)
29-
FetchContent_Declare(kiss_icp URL https://github.com/PRBonn/kiss-icp/archive/refs/tags/v1.1.0.tar.gz SOURCE_SUBDIR
29+
FetchContent_Declare(kiss_icp URL https://github.com/PRBonn/kiss-icp/archive/refs/tags/v1.2.0.tar.gz SOURCE_SUBDIR
3030
cpp/kiss_icp)
3131
FetchContent_MakeAvailable(kiss_icp)

cpp/kinematic_icp/CMakeLists.txt

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -21,7 +21,7 @@
2121
# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE
2222
# SOFTWARE.
2323
cmake_minimum_required(VERSION 3.16...3.26)
24-
project(kinematic_icp_cpp VERSION 0.0.1 LANGUAGES CXX)
24+
project(kinematic_icp_cpp VERSION 0.1.1 LANGUAGES CXX)
2525

2626
# Setup build options for the underlying kiss dependency
2727
option(USE_CCACHE "Build using Ccache if found on the path" ON)

cpp/kinematic_icp/pipeline/KinematicICP.cpp

Lines changed: 9 additions & 12 deletions
Original file line numberDiff line numberDiff line change
@@ -23,7 +23,6 @@
2323
#include "KinematicICP.hpp"
2424

2525
#include <Eigen/Core>
26-
#include <kiss_icp/core/Deskew.hpp>
2726
#include <kiss_icp/core/Preprocessing.hpp>
2827
#include <kiss_icp/core/VoxelUtils.hpp>
2928
#include <vector>
@@ -51,18 +50,16 @@ KinematicICP::Vector3dVectorTuple KinematicICP::RegisterFrame(
5150
const std::vector<double> &timestamps,
5251
const Sophus::SE3d &lidar_to_base,
5352
const Sophus::SE3d &relative_odometry) {
54-
const auto &deskew_frame = [&]() -> std::vector<Eigen::Vector3d> {
55-
if (!config_.deskew || timestamps.empty()) return frame;
56-
return kiss_icp::DeSkewScan(frame, timestamps,
57-
lidar_to_base.inverse() * relative_odometry * lidar_to_base);
58-
}();
59-
const auto &deskew_frame_in_base = transform_points(deskew_frame, lidar_to_base);
60-
// Preprocess the input cloud
61-
const auto &cropped_frame =
62-
kiss_icp::Preprocess(deskew_frame_in_base, config_.max_range, config_.min_range);
63-
53+
// Need to deskew in lidar frame
54+
const Sophus::SE3d &relative_odometry_in_lidar =
55+
lidar_to_base.inverse() * relative_odometry * lidar_to_base;
56+
const auto &preprocessed_frame =
57+
preprocessor_.Preprocess(frame, timestamps, relative_odometry_in_lidar);
58+
// Give the frame in base frame
59+
const auto &preprocessed_frame_in_base = transform_points(preprocessed_frame, lidar_to_base);
6460
// Voxelize
65-
const auto &[source, frame_downsample] = Voxelize(cropped_frame, config_.voxel_size);
61+
const auto &[source, frame_downsample] =
62+
Voxelize(preprocessed_frame_in_base, config_.voxel_size);
6663

6764
// Get adaptive_threshold
6865
const double tau = correspondence_threshold_.ComputeThreshold();

cpp/kinematic_icp/pipeline/KinematicICP.hpp

Lines changed: 4 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -89,8 +89,8 @@ class KinematicICP {
8989

9090
std::vector<Eigen::Vector3d> LocalMap() const { return local_map_.Pointcloud(); };
9191

92-
const SparseVoxelGrid &VoxelMap() const { return local_map_; };
93-
SparseVoxelGrid &VoxelMap() { return local_map_; };
92+
const kiss_icp::VoxelHashMap &VoxelMap() const { return local_map_; };
93+
kiss_icp::VoxelHashMap &VoxelMap() { return local_map_; };
9494

9595
const Sophus::SE3d &pose() const { return last_pose_; }
9696
Sophus::SE3d &pose() { return last_pose_; }
@@ -101,7 +101,8 @@ class KinematicICP {
101101
KinematicRegistration registration_;
102102
CorrespondenceThreshold correspondence_threshold_;
103103
Config config_;
104-
SparseVoxelGrid local_map_;
104+
// KISS-ICP pipeline modules
105+
kiss_icp::VoxelHashMap local_map_;
105106
};
106107

107108
} // namespace kinematic_icp::pipeline

cpp/kinematic_icp/registration/Registration.cpp

Lines changed: 9 additions & 20 deletions
Original file line numberDiff line numberDiff line change
@@ -23,8 +23,10 @@
2323
#include "Registration.hpp"
2424

2525
#include <tbb/blocked_range.h>
26+
#include <tbb/concurrent_vector.h>
2627
#include <tbb/global_control.h>
2728
#include <tbb/info.h>
29+
#include <tbb/parallel_for.h>
2830
#include <tbb/parallel_reduce.h>
2931
#include <tbb/task_arena.h>
3032

@@ -37,7 +39,7 @@
3739
#include <tuple>
3840

3941
using LinearSystem = std::pair<Eigen::Matrix2d, Eigen::Vector2d>;
40-
using Correspondences = std::vector<std::pair<Eigen::Vector3d, Eigen::Vector3d>>;
42+
using Correspondences = tbb::concurrent_vector<std::pair<Eigen::Vector3d, Eigen::Vector3d>>;
4143

4244
namespace {
4345
constexpr double epsilon = std::numeric_limits<double>::min();
@@ -61,33 +63,20 @@ Correspondences DataAssociation(const std::vector<Eigen::Vector3d> &points,
6163
const Sophus::SE3d &T,
6264
const double max_correspondance_distance) {
6365
using points_iterator = std::vector<Eigen::Vector3d>::const_iterator;
64-
Correspondences associations;
65-
associations.reserve(points.size());
66-
associations = tbb::parallel_reduce(
66+
Correspondences correspondences;
67+
correspondences.reserve(points.size());
68+
tbb::parallel_for(
6769
// Range
6870
tbb::blocked_range<points_iterator>{points.cbegin(), points.cend()},
69-
// Identity
70-
associations,
71-
// 1st lambda: Parallel computation
72-
[&](const tbb::blocked_range<points_iterator> &r, Correspondences res) -> Correspondences {
73-
res.reserve(r.size());
71+
[&](const tbb::blocked_range<points_iterator> &r) {
7472
std::for_each(r.begin(), r.end(), [&](const auto &point) {
7573
const auto &[closest_neighbor, distance] = voxel_map.GetClosestNeighbor(T * point);
7674
if (distance < max_correspondance_distance) {
77-
res.emplace_back(point, closest_neighbor);
75+
correspondences.emplace_back(point, closest_neighbor);
7876
}
7977
});
80-
return res;
81-
},
82-
// 2nd lambda: Parallel reduction
83-
[](Correspondences a, const Correspondences &b) -> Correspondences {
84-
a.insert(a.end(), //
85-
std::make_move_iterator(b.cbegin()), //
86-
std::make_move_iterator(b.cend()));
87-
return a;
8878
});
89-
90-
return associations;
79+
return correspondences;
9180
}
9281

9382
Eigen::Vector2d ComputePerturbation(const Correspondences &correspondences,

ros/CMakeLists.txt

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -21,7 +21,7 @@
2121
# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE
2222
# SOFTWARE.
2323
cmake_minimum_required(VERSION 3.16...3.26)
24-
project(kinematic_icp VERSION 0.0.1 LANGUAGES CXX)
24+
project(kinematic_icp VERSION 0.1.1 LANGUAGES CXX)
2525

2626
set(CMAKE_BUILD_TYPE Release)
2727

ros/package.xml

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -25,7 +25,7 @@ SOFTWARE.
2525
-->
2626
<package format="3">
2727
<name>kinematic_icp</name>
28-
<version>0.0.1</version>
28+
<version>0.1.1</version>
2929
<description>ROS 2 Wrapper</description>
3030
<maintainer email="tiziano.guadagnino93@gmail.com">frevo137</maintainer>
3131
<license>MIT</license>

0 commit comments

Comments
 (0)