Skip to content

Commit daadbf9

Browse files
authored
Merge pull request #129 from neka-nat/develop
build on cuda 12.6
2 parents dd9df0f + 7e5c760 commit daadbf9

20 files changed

+56
-39
lines changed

src/cupoch/geometry/down_sample.cu

+19-10
Original file line numberDiff line numberDiff line change
@@ -75,14 +75,14 @@ struct compute_key_functor {
7575
};
7676

7777
template <int Index, class... Args>
78-
struct normalize_and_devide_tuple_functor
78+
struct normalize_and_divide_tuple_functor
7979
: public thrust::binary_function<const thrust::tuple<Args...>,
8080
const int,
8181
thrust::tuple<Args...>> {
8282
__host__ __device__ thrust::tuple<Args...> operator()(
8383
const thrust::tuple<Args...> &x, const int &y) const {
8484
thrust::tuple<Args...> ans = x;
85-
devide_tuple_impl(ans, y,
85+
divide_tuple_impl(ans, y,
8686
thrust::make_index_sequence<sizeof...(Args)>{});
8787
thrust::get<Index>(ans).normalize();
8888
return ans;
@@ -211,8 +211,17 @@ std::shared_ptr<PointCloud> PointCloud::VoxelDownSample(
211211
};
212212
if (!has_normals && !has_colors) {
213213
auto begin = make_tuple_begin(output->points_, counts);
214-
int n_out = runs(begin, sorted_points);
215-
devide_tuple_functor<Eigen::Vector3f> dv_func;
214+
thrust::sort_by_key(
215+
utility::exec_policy(0), keys.begin(), keys.end(),
216+
sorted_points.begin());
217+
add_tuple_functor<Eigen::Vector3f, int> add_func;
218+
auto end = thrust::reduce_by_key(
219+
utility::exec_policy(0), keys.begin(), keys.end(),
220+
make_tuple_iterator(sorted_points.begin(),
221+
thrust::make_constant_iterator(1)),
222+
thrust::make_discard_iterator(), begin, binary_pred, add_func);
223+
int n_out = thrust::distance(begin, end.second);
224+
divide_tuple_functor<Eigen::Vector3f> dv_func;
216225
auto output_begins = make_tuple_begin(output->points_);
217226
thrust::transform(output_begins, output_begins + n_out, counts.begin(),
218227
output_begins, dv_func);
@@ -223,7 +232,7 @@ std::shared_ptr<PointCloud> PointCloud::VoxelDownSample(
223232
auto begin =
224233
make_tuple_begin(output->points_, output->normals_, counts);
225234
int n_out = runs(begin, sorted_points, sorted_normals);
226-
normalize_and_devide_tuple_functor<1, Eigen::Vector3f, Eigen::Vector3f>
235+
normalize_and_divide_tuple_functor<1, Eigen::Vector3f, Eigen::Vector3f>
227236
dv_func;
228237
auto output_begins =
229238
make_tuple_begin(output->points_, output->normals_);
@@ -235,7 +244,7 @@ std::shared_ptr<PointCloud> PointCloud::VoxelDownSample(
235244
resize_all(n, output->colors_);
236245
auto begin = make_tuple_begin(output->points_, output->colors_, counts);
237246
int n_out = runs(begin, sorted_points, sorted_colors);
238-
devide_tuple_functor<Eigen::Vector3f, Eigen::Vector3f> dv_func;
247+
divide_tuple_functor<Eigen::Vector3f, Eigen::Vector3f> dv_func;
239248
auto output_begins = make_tuple_begin(output->points_, output->colors_);
240249
thrust::transform(output_begins, output_begins + n_out, counts.begin(),
241250
output_begins, dv_func);
@@ -247,7 +256,7 @@ std::shared_ptr<PointCloud> PointCloud::VoxelDownSample(
247256
auto begin = make_tuple_begin(output->points_, output->normals_,
248257
output->colors_, counts);
249258
int n_out = runs(begin, sorted_points, sorted_normals, sorted_colors);
250-
normalize_and_devide_tuple_functor<1, Eigen::Vector3f, Eigen::Vector3f,
259+
normalize_and_divide_tuple_functor<1, Eigen::Vector3f, Eigen::Vector3f,
251260
Eigen::Vector3f>
252261
dv_func;
253262
auto output_begins = make_tuple_begin(output->points_, output->normals_,
@@ -397,7 +406,7 @@ PointCloud::RemoveStatisticalOutliers(size_t nb_neighbors,
397406
auto mean_and_count = thrust::transform_reduce(
398407
utility::exec_policy(0), avg_distances.begin(),
399408
avg_distances.end(),
400-
[] __device__(float const &x) {
409+
[] __device__(float const &x) -> thrust::tuple<float, size_t> {
401410
return thrust::make_tuple(max(x, 0.0f), (size_t)(x >= 0.0));
402411
},
403412
thrust::make_tuple(0.0f, size_t(0)),
@@ -412,8 +421,8 @@ PointCloud::RemoveStatisticalOutliers(size_t nb_neighbors,
412421
const float sq_sum = thrust::transform_reduce(
413422
utility::exec_policy(0), avg_distances.begin(),
414423
avg_distances.end(),
415-
[cloud_mean] __device__(const float x) {
416-
return (x > 0) ? (x - cloud_mean) * (x - cloud_mean) : 0;
424+
[cloud_mean] __device__(const float x) -> float {
425+
return (x > 0) ? (x - cloud_mean) * (x - cloud_mean) : 0.0f;
417426
},
418427
0.0, thrust::plus<float>());
419428
// Bessel's correction

src/cupoch/geometry/lineset.cu

+1-1
Original file line numberDiff line numberDiff line change
@@ -225,7 +225,7 @@ float LineSet<Dim>::GetMaxLineLength() const {
225225
element_get_functor<Eigen::Vector2i, 1>()))),
226226
[] __device__(
227227
const thrust::tuple<Eigen::Matrix<float, Dim, 1>,
228-
Eigen::Matrix<float, Dim, 1>> &ppair) {
228+
Eigen::Matrix<float, Dim, 1>> &ppair) -> float {
229229
return (thrust::get<0>(ppair) - thrust::get<1>(ppair)).norm();
230230
},
231231
0.0f, thrust::maximum<float>());

src/cupoch/geometry/pointcloud.cu

+1-1
Original file line numberDiff line numberDiff line change
@@ -327,7 +327,7 @@ std::shared_ptr<PointCloud> PointCloud::FarthestPointDownSample(
327327
thrust::make_counting_iterator<size_t>(0),
328328
thrust::make_counting_iterator<size_t>(num_points),
329329
func,
330-
thrust::make_tuple<size_t, float>(farthest_index, 0.0f),
330+
thrust::make_tuple<size_t, float>(static_cast<size_t>(farthest_index), 0.0f),
331331
[] __host__ __device__(const thrust::tuple<size_t, float> &a,
332332
const thrust::tuple<size_t, float> &b) -> thrust::tuple<size_t, float> {
333333
return thrust::get<1>(a) > thrust::get<1>(b) ? a : b;

src/cupoch/geometry/segmentation.cu

+1-1
Original file line numberDiff line numberDiff line change
@@ -147,7 +147,7 @@ Eigen::Vector4f GetPlaneFromPoints(
147147
utility::exec_policy(0),
148148
thrust::make_permutation_iterator(points.begin(), inliers.begin()),
149149
thrust::make_permutation_iterator(points.begin(), inliers.end()),
150-
[centroid] __device__(const Eigen::Vector3f &pt) {
150+
[centroid] __device__(const Eigen::Vector3f &pt) -> Eigen::Vector6f {
151151
Eigen::Vector3f r = pt - centroid;
152152
Eigen::Vector6f ans;
153153
ans << r(0) * r(0), r(0) * r(1), r(0) * r(2), r(1) * r(1),

src/cupoch/geometry/trianglemesh.cu

+5-3
Original file line numberDiff line numberDiff line change
@@ -929,12 +929,14 @@ TriangleMesh &TriangleMesh::RemoveDuplicatedVertices() {
929929
if (has_vert_normal && has_vert_color) {
930930
k = runs(vertex_normals_, vertex_colors_);
931931
} else if (has_vert_normal) {
932-
k = runs(vertex_normals_);
932+
thrust::discard_iterable dummy;
933+
k = runs(vertex_normals_, dummy);
933934
} else if (has_vert_color) {
934-
k = runs(vertex_colors_);
935+
thrust::discard_iterable dummy;
936+
k = runs(vertex_colors_, dummy);
935937
} else {
936938
thrust::discard_iterable dummy;
937-
k = runs(dummy);
939+
k = runs(dummy, dummy);
938940
}
939941
vertices_.resize(k);
940942
if (has_vert_normal) vertex_normals_.resize(k);

src/cupoch/geometry/voxelgrid.cu

+1-1
Original file line numberDiff line numberDiff line change
@@ -274,7 +274,7 @@ VoxelGrid &VoxelGrid::operator+=(const VoxelGrid &voxelgrid) {
274274
thrust::swap(voxels_keys_, new_keys);
275275
thrust::transform(voxels_values_.begin(), voxels_values_.end(),
276276
counts.begin(), voxels_values_.begin(),
277-
devide_voxel_color_functor());
277+
divide_voxel_color_functor());
278278
} else {
279279
this->AddVoxels(voxelgrid.voxels_values_);
280280
}

src/cupoch/geometry/voxelgrid.h

+1-1
Original file line numberDiff line numberDiff line change
@@ -72,7 +72,7 @@ struct add_voxel_color_functor {
7272
}
7373
};
7474

75-
struct devide_voxel_color_functor {
75+
struct divide_voxel_color_functor {
7676
__device__ Voxel operator()(const Voxel &x, int y) const {
7777
Voxel ans;
7878
ans.grid_index_ = x.grid_index_;

src/cupoch/geometry/voxelgrid_factory.cu

+1-1
Original file line numberDiff line numberDiff line change
@@ -210,7 +210,7 @@ std::shared_ptr<VoxelGrid> VoxelGrid::CreateFromPointCloudWithinBounds(
210210
thrust::transform(output->voxels_values_.begin(),
211211
output->voxels_values_.end(), counts.begin(),
212212
output->voxels_values_.begin(),
213-
devide_voxel_color_functor());
213+
divide_voxel_color_functor());
214214
utility::LogDebug(
215215
"Pointcloud is voxelized from {:d} points to {:d} voxels.",
216216
(int)input.points_.size(), (int)output->voxels_keys_.size());

src/cupoch/registration/fast_global_registration.cu

+1-1
Original file line numberDiff line numberDiff line change
@@ -234,7 +234,7 @@ std::tuple<std::vector<Eigen::Vector3f>, float, float> NormalizePointCloud(
234234
utility::exec_policy(0),
235235
point_cloud_vec[i].points_.begin(),
236236
point_cloud_vec[i].points_.end(),
237-
[] __device__(const Eigen::Vector3f& pt) { return pt.norm(); },
237+
[] __device__(const Eigen::Vector3f& pt) -> float { return pt.norm(); },
238238
scale, thrust::maximum<float>());
239239
}
240240

src/cupoch/registration/feature.h

+6
Original file line numberDiff line numberDiff line change
@@ -23,6 +23,7 @@
2323
#include <Eigen/Core>
2424
#include <memory>
2525

26+
#include "cupoch/registration/transformation_estimation.h"
2627
#include "cupoch/knn/kdtree_search_param.h"
2728
#include "cupoch/utility/device_vector.h"
2829

@@ -65,5 +66,10 @@ std::shared_ptr<Feature<352>> ComputeSHOTFeature(
6566
const knn::KDTreeSearchParam& search_param =
6667
knn::KDTreeSearchParamKNN());
6768

69+
CorrespondenceSet CorrespondencesFromFeatures(const Feature<33> &source_features,
70+
const Feature<33> &target_features,
71+
bool mutual_filter = false,
72+
float mutual_consistency_ratio = 0.1);
73+
6874
} // namespace registration
6975
} // namespace cupoch

src/cupoch/registration/kabsch.cu

+4-4
Original file line numberDiff line numberDiff line change
@@ -146,14 +146,14 @@ Eigen::Matrix4f_u cupoch::registration::KabschWeighted(
146146
Eigen::Vector3f model_center = thrust::transform_reduce(
147147
utility::exec_policy(0), make_tuple_begin(model, weight),
148148
make_tuple_end(model, weight),
149-
[] __device__(const thrust::tuple<Eigen::Vector3f, float> &x) {
149+
[] __device__(const thrust::tuple<Eigen::Vector3f, float> &x) -> Eigen::Vector3f {
150150
return thrust::get<0>(x) * thrust::get<1>(x);
151151
},
152152
Eigen::Vector3f(0.0, 0.0, 0.0), thrust::plus<Eigen::Vector3f>());
153153
Eigen::Vector3f target_center = thrust::transform_reduce(
154154
utility::exec_policy(0), make_tuple_begin(target, weight),
155155
make_tuple_end(target, weight),
156-
[] __device__(const thrust::tuple<Eigen::Vector3f, float> &x) {
156+
[] __device__(const thrust::tuple<Eigen::Vector3f, float> &x) -> Eigen::Vector3f {
157157
return thrust::get<0>(x) * thrust::get<1>(x);
158158
},
159159
Eigen::Vector3f(0.0, 0.0, 0.0), thrust::plus<Eigen::Vector3f>());
@@ -166,7 +166,7 @@ Eigen::Matrix4f_u cupoch::registration::KabschWeighted(
166166
// Compute the H matrix
167167
const float h_weight = thrust::transform_reduce(
168168
utility::exec_policy(0), weight.begin(), weight.end(),
169-
[] __device__(float x) { return x * x; }, 0.0f,
169+
[] __device__(float x) -> float { return x * x; }, 0.0f,
170170
thrust::plus<float>());
171171
const Eigen::Matrix3f init = Eigen::Matrix3f::Zero();
172172
Eigen::Matrix3f hh = thrust::transform_reduce(
@@ -175,7 +175,7 @@ Eigen::Matrix4f_u cupoch::registration::KabschWeighted(
175175
make_tuple_end(model, target, weight),
176176
[model_center, target_center] __device__(
177177
const thrust::tuple<Eigen::Vector3f, Eigen::Vector3f, float>
178-
&x) {
178+
&x) -> Eigen::Matrix3f {
179179
const Eigen::Vector3f centralized_x =
180180
thrust::get<0>(x) - model_center;
181181
const Eigen::Vector3f centralized_y =

src/cupoch/registration/registration.cu

+1-1
Original file line numberDiff line numberDiff line change
@@ -49,7 +49,7 @@ RegistrationResult GetRegistrationResultAndCorrespondences(
4949
result.correspondence_set_.resize(n_pt);
5050
const float error2 = thrust::transform_reduce(
5151
utility::exec_policy(0), dists.begin(), dists.end(),
52-
[] __device__(float d) { return (isinf(d)) ? 0.0 : d; }, 0.0f,
52+
[] __device__(float d) -> float { return (isinf(d)) ? 0.0f : d; }, 0.0f,
5353
thrust::plus<float>());
5454
thrust::transform(enumerate_begin(indices), enumerate_end(indices),
5555
result.correspondence_set_.begin(),

src/cupoch/registration/transformation_estimation.cu

+2-2
Original file line numberDiff line numberDiff line change
@@ -183,7 +183,7 @@ float TransformationEstimationPointToPlane::ComputeRMSE(
183183
element_get_functor<Eigen::Vector2i,
184184
1>()))),
185185
[] __device__(const thrust::tuple<Eigen::Vector3f, Eigen::Vector3f,
186-
Eigen::Vector3f> &x) {
186+
Eigen::Vector3f> &x) -> float {
187187
float r = (thrust::get<0>(x) - thrust::get<1>(x))
188188
.dot(thrust::get<2>(x));
189189
return r * r;
@@ -275,7 +275,7 @@ float TransformationEstimationSymmetricMethod::ComputeRMSE(
275275
1>()))),
276276
[] __device__(
277277
const thrust::tuple<Eigen::Vector3f, Eigen::Vector3f,
278-
Eigen::Vector3f, Eigen::Vector3f> &x) {
278+
Eigen::Vector3f, Eigen::Vector3f> &x) -> float{
279279
// Compute error using both source and target normals
280280
float r = ComputeErrorUsingNormals(
281281
thrust::get<0>(x), thrust::get<1>(x), thrust::get<2>(x),

src/cupoch/utility/console.h

+1-1
Original file line numberDiff line numberDiff line change
@@ -117,7 +117,7 @@ class ConsoleProgressBar {
117117
private:
118118
const size_t resolution_ = 40;
119119
size_t expected_count_;
120-
size_t current_count_;
120+
int current_count_;
121121
std::string progress_info_;
122122
size_t progress_pixel_;
123123
bool active_;

src/cupoch/utility/eigen.inl

+1-1
Original file line numberDiff line numberDiff line change
@@ -177,7 +177,7 @@ thrust::tuple<MatType, VecType, float, float> ComputeWeightedJTJandJTr(
177177
make_tuple_begin(JTJs, JTrs, r2s, ws),
178178
make_tuple_end(JTJs, JTrs, r2s, ws),
179179
[] __device__(
180-
const thrust::tuple<MatType, VecType, float, float> &x) {
180+
const thrust::tuple<MatType, VecType, float, float> &x) -> thrust::tuple<MatType, VecType, float> {
181181
float w = thrust::get<3>(x);
182182
return thrust::make_tuple(thrust::get<0>(x) * w,
183183
thrust::get<1>(x) * w,

src/cupoch/utility/helper.h

+7-8
Original file line numberDiff line numberDiff line change
@@ -51,7 +51,6 @@ struct equal_to<Eigen::Matrix<int, Dim, 1>> {
5151
typedef Eigen::Matrix<int, Dim, 1> second_argument_type;
5252
typedef bool result_type;
5353
// clang-format off
54-
__thrust_exec_check_disable__
5554
__host__ __device__ bool operator()(
5655
const Eigen::Matrix<int, Dim, 1> &lhs,
5756
const Eigen::Matrix<int, Dim, 1> &rhs) const {
@@ -207,7 +206,7 @@ __host__ __device__ void add_fn(T &x, const T &y) {
207206
template <typename T, std::size_t... Is>
208207
__host__ __device__ void add_tuple_impl(T &t,
209208
const T &y,
210-
std::index_sequence<Is...>) {
209+
thrust::integer_sequence<std::size_t, Is...>) {
211210
std::initializer_list<int>{
212211
((void)add_fn(thrust::get<Is>(t), thrust::get<Is>(y)), 0)...};
213212
}
@@ -227,26 +226,26 @@ struct add_tuple_functor
227226
};
228227

229228
template <typename T>
230-
__host__ __device__ void devide_fn(T &x, const int &y) {
229+
__host__ __device__ void divide_fn(T &x, const int &y) {
231230
x /= static_cast<float>(y);
232231
}
233232

234233
template <typename T, std::size_t... Is>
235-
__host__ __device__ void devide_tuple_impl(T &t,
234+
__host__ __device__ void divide_tuple_impl(T &t,
236235
const int &y,
237-
std::index_sequence<Is...>) {
238-
std::initializer_list<int>{((void)devide_fn(thrust::get<Is>(t), y), 0)...};
236+
thrust::integer_sequence<std::size_t, Is...>) {
237+
std::initializer_list<int>{((void)divide_fn(thrust::get<Is>(t), y), 0)...};
239238
}
240239

241240
template <class... Args>
242-
struct devide_tuple_functor
241+
struct divide_tuple_functor
243242
: public thrust::binary_function<const thrust::tuple<Args...>,
244243
const int,
245244
thrust::tuple<Args...>> {
246245
__host__ __device__ thrust::tuple<Args...> operator()(
247246
const thrust::tuple<Args...> &x, const int &y) const {
248247
thrust::tuple<Args...> ans = x;
249-
devide_tuple_impl(ans, y,
248+
divide_tuple_impl(ans, y,
250249
thrust::make_index_sequence<sizeof...(Args)>{});
251250
return ans;
252251
}

src/cupoch/utility/pinned_allocator.h

-1
Original file line numberDiff line numberDiff line change
@@ -21,7 +21,6 @@
2121
#pragma once
2222

2323
#include <thrust/detail/config.h>
24-
#include <thrust/system/cuda/detail/guarded_cuda_runtime_api.h>
2524
#include <stdexcept>
2625
#include <limits>
2726
#include <string>

src/python/pyproject.toml

+1
Original file line numberDiff line numberDiff line change
@@ -22,6 +22,7 @@ rosmaster = {version = "^1.15.11", optional = true}
2222
rosbag = {version = "^1.15.11", optional = true}
2323
transformations = {version = "^2022.9.26", optional = true}
2424

25+
setuptools = "^72.2.0"
2526
[tool.poetry.dev-dependencies]
2627
twine = "^3.2.0"
2728
wheel = "^0.36.2"

src/tests/test_utility/raw.h

+1
Original file line numberDiff line numberDiff line change
@@ -20,6 +20,7 @@
2020
**/
2121
#pragma once
2222

23+
#include <stdint.h>
2324
#include <iostream>
2425
#include <string>
2526
#include <vector>

0 commit comments

Comments
 (0)