Skip to content

Commit

Permalink
bug fix
Browse files Browse the repository at this point in the history
  • Loading branch information
neka-nat committed Oct 5, 2020
1 parent ad550de commit ac5ca36
Show file tree
Hide file tree
Showing 14 changed files with 56 additions and 39 deletions.
2 changes: 1 addition & 1 deletion .github/workflows/windows.yml
Original file line number Diff line number Diff line change
Expand Up @@ -95,7 +95,7 @@ jobs:
python -m pip install -U pip wheel setuptools
cmake --build . --config ${{ env.config }} --target pip-package --verbose
- name: Publish package
if: github.event_name == 'push' && startsWith(github.ref, 'refs/tags')
if: github.event_name == 'push' && startsWith(github.ref, 'refs/tags') && matrix.cuda == '10.2.89'
working-directory: ${{ env.build_dir }}/lib/python_package
env:
PYPI_USERNAME: ${{ secrets.pypi_username }}
Expand Down
10 changes: 5 additions & 5 deletions src/cupoch/geometry/down_sample.cu
Original file line number Diff line number Diff line change
Expand Up @@ -81,7 +81,7 @@ __host__ int CalcAverageByKey(utility::device_vector<Eigen::Vector3i> &keys,
OutputIterator buf_begins,
OutputIterator output_begins) {
const size_t n = keys.size();
thrust::sort_by_key(utility::exec_policy(utility::GetStream(0))->on(utility::GetStream(0)),
thrust::sort_by_key(utility::exec_policy(0)->on(0),
keys.begin(), keys.end(), buf_begins);

utility::device_vector<int> counts(n);
Expand Down Expand Up @@ -122,7 +122,7 @@ std::shared_ptr<PointCloud> PointCloud::SelectByIndex(
if (invert) {
size_t n_out = points_.size() - indices.size();
utility::device_vector<size_t> sorted_indices = indices;
thrust::sort(utility::exec_policy(utility::GetStream(0))->on(utility::GetStream(0)),
thrust::sort(utility::exec_policy(0)->on(0),
sorted_indices.begin(), sorted_indices.end());
utility::device_vector<size_t> inv_indices(n_out);
thrust::set_difference(thrust::make_counting_iterator<size_t>(0),
Expand Down Expand Up @@ -269,7 +269,7 @@ std::shared_ptr<PointCloud> PointCloud::UniformDownSample(
}

std::tuple<std::shared_ptr<PointCloud>, utility::device_vector<size_t>>
PointCloud::RemoveRadiusOutliers(size_t nb_points, float search_radius, int max_search_points) const {
PointCloud::RemoveRadiusOutliers(size_t nb_points, float search_radius) const {
if (nb_points < 1 || search_radius <= 0) {
utility::LogError(
"[RemoveRadiusOutliers] Illegal input parameters,"
Expand All @@ -279,12 +279,12 @@ PointCloud::RemoveRadiusOutliers(size_t nb_points, float search_radius, int max_
kdtree.SetGeometry(*this);
utility::device_vector<int> tmp_indices;
utility::device_vector<float> dist;
kdtree.SearchRadius(points_, search_radius, max_search_points, tmp_indices, dist);
kdtree.SearchRadius(points_, search_radius, nb_points + 1, tmp_indices, dist);
const size_t n_pt = points_.size();
utility::device_vector<size_t> counts(n_pt);
utility::device_vector<size_t> indices(n_pt);
thrust::repeated_range<thrust::counting_iterator<size_t>> range(thrust::make_counting_iterator<size_t>(0),
thrust::make_counting_iterator(n_pt), NUM_MAX_NN);
thrust::make_counting_iterator(n_pt), nb_points + 1);
thrust::reduce_by_key(range.begin(), range.end(),
thrust::make_transform_iterator(tmp_indices.begin(),
[] __device__ (int idx) { return (int)(idx >= 0); }),
Expand Down
18 changes: 9 additions & 9 deletions src/cupoch/geometry/graph.cu
Original file line number Diff line number Diff line change
Expand Up @@ -213,19 +213,19 @@ Graph<Dim> &Graph<Dim>::ConstructGraph(bool set_edge_weights_from_distance) {
bool has_colors = this->HasColors();
bool has_weights = this->HasWeights();
if (has_colors && has_weights) {
thrust::sort_by_key(utility::exec_policy(utility::GetStream(0))->on(utility::GetStream(0)),
thrust::sort_by_key(utility::exec_policy(0)->on(0),
this->lines_.begin(), this->lines_.end(),
make_tuple_begin(edge_weights_, this->colors_));
} else if (!has_colors && has_weights) {
thrust::sort_by_key(utility::exec_policy(utility::GetStream(0))->on(utility::GetStream(0)),
thrust::sort_by_key(utility::exec_policy(0)->on(0),
this->lines_.begin(), this->lines_.end(),
edge_weights_.begin());
} else if (has_colors && !has_weights) {
thrust::sort_by_key(utility::exec_policy(utility::GetStream(0))->on(utility::GetStream(0)),
thrust::sort_by_key(utility::exec_policy(0)->on(0),
this->lines_.begin(), this->lines_.end(),
this->colors_.begin());
} else {
thrust::sort(utility::exec_policy(utility::GetStream(0))->on(utility::GetStream(0)),
thrust::sort(utility::exec_policy(0)->on(0),
this->lines_.begin(), this->lines_.end());
edge_weights_.resize(this->lines_.size(), 1.0);
}
Expand Down Expand Up @@ -274,7 +274,7 @@ Graph<Dim> &Graph<Dim>::ConnectToNearestNeighbors(float max_edge_distance,
return thrust::get<0>(x)[0] < 0;
};
remove_if_vectors(remove_fn, new_edges, weights);
thrust::sort_by_key(utility::exec_policy(utility::GetStream(0))->on(utility::GetStream(0)),
thrust::sort_by_key(utility::exec_policy(0)->on(0),
new_edges.begin(), new_edges.end(), weights.begin());
utility::device_vector<Eigen::Vector2i> res_edges(new_edges.size());
utility::device_vector<float> res_weights(new_edges.size());
Expand Down Expand Up @@ -417,7 +417,7 @@ Graph<Dim> &Graph<Dim>::RemoveEdges(
utility::device_vector<float> new_weights;
utility::device_vector<Eigen::Vector3f> new_colors;
utility::device_vector<Eigen::Vector2i> sorted_edges = edges;
thrust::sort(utility::exec_policy(utility::GetStream(0))->on(utility::GetStream(0)),
thrust::sort(utility::exec_policy(0)->on(0),
sorted_edges.begin(), sorted_edges.end());
auto cnst_w = thrust::make_constant_iterator<float>(1.0);
auto cnst_c = thrust::make_constant_iterator<Eigen::Vector3f>(
Expand Down Expand Up @@ -555,7 +555,7 @@ Graph<Dim> &Graph<Dim>::PaintEdgesColor(
const Eigen::Vector3f &color) {
utility::device_vector<Eigen::Vector2i> sorted_edges = edges;
utility::device_vector<size_t> indices(edges.size());
thrust::sort(utility::exec_policy(utility::GetStream(0))->on(utility::GetStream(0)),
thrust::sort(utility::exec_policy(0)->on(0),
sorted_edges.begin(), sorted_edges.end());
thrust::set_intersection(
make_tuple_iterator(this->lines_.begin(),
Expand All @@ -580,7 +580,7 @@ Graph<Dim> &Graph<Dim>::PaintEdgesColor(
[color] __device__(Eigen::Vector3f & c) { c = color; });
if (!is_directed_) {
swap_index(sorted_edges);
thrust::sort(utility::exec_policy(utility::GetStream(0))->on(utility::GetStream(0)),
thrust::sort(utility::exec_policy(0)->on(0),
sorted_edges.begin(), sorted_edges.end());
thrust::set_intersection(
make_tuple_iterator(this->lines_.begin(),
Expand Down Expand Up @@ -686,7 +686,7 @@ std::shared_ptr<typename Graph<Dim>::SSSPResultArray> Graph<Dim>::DijkstraPaths(
utility::device_vector<int> old_to_new_edge_table(this->lines_.size());
thrust::sequence(new_to_old_edge_table.begin(), new_to_old_edge_table.end(),
0);
thrust::sort_by_key(utility::exec_policy(utility::GetStream(0))->on(utility::GetStream(0)),
thrust::sort_by_key(utility::exec_policy(0)->on(0),
sorted_lines.begin(), sorted_lines.end(),
new_to_old_edge_table.begin(),
[] __device__(const Eigen::Vector2i &lhs,
Expand Down
4 changes: 2 additions & 2 deletions src/cupoch/geometry/occupancygrid.cu
Original file line number Diff line number Diff line change
Expand Up @@ -136,7 +136,7 @@ void ComputeFreeVoxels(const utility::device_vector<Eigen::Vector3f>& points,
idx[2] >= max_idx;
});
free_voxels.resize(thrust::distance(free_voxels.begin(), end1));
thrust::sort(utility::exec_policy(utility::GetStream(0))->on(utility::GetStream(0)),
thrust::sort(utility::exec_policy(0)->on(0),
free_voxels.begin(), free_voxels.end());
auto end2 = thrust::unique(free_voxels.begin(), free_voxels.end());
free_voxels.resize(thrust::distance(free_voxels.begin(), end2));
Expand Down Expand Up @@ -190,7 +190,7 @@ void ComputeOccupiedVoxels(
idx[2] >= max_idx;
});
occupied_voxels.resize(thrust::distance(occupied_voxels.begin(), end1));
thrust::sort(utility::exec_policy(utility::GetStream(0))->on(utility::GetStream(0)),
thrust::sort(utility::exec_policy(0)->on(0),
occupied_voxels.begin(), occupied_voxels.end());
auto end2 = thrust::unique(occupied_voxels.begin(), occupied_voxels.end());
occupied_voxels.resize(thrust::distance(occupied_voxels.begin(), end2));
Expand Down
2 changes: 1 addition & 1 deletion src/cupoch/geometry/pointcloud.h
Original file line number Diff line number Diff line change
Expand Up @@ -124,7 +124,7 @@ class PointCloud : public GeometryBase<3> {
std::shared_ptr<PointCloud> UniformDownSample(size_t every_k_points) const;

std::tuple<std::shared_ptr<PointCloud>, utility::device_vector<size_t>>
RemoveRadiusOutliers(size_t nb_points, float search_radius, int max_search_points=NUM_MAX_NN) const;
RemoveRadiusOutliers(size_t nb_points, float search_radius) const;

std::tuple<std::shared_ptr<PointCloud>, utility::device_vector<size_t>>
RemoveStatisticalOutliers(size_t nb_neighbors, float std_ratio) const;
Expand Down
2 changes: 1 addition & 1 deletion src/cupoch/geometry/segmentation.cu
Original file line number Diff line number Diff line change
Expand Up @@ -198,7 +198,7 @@ std::tuple<Eigen::Vector4f, utility::device_vector<size_t>> PointCloud::SegmentP
thrust::host_vector<Eigen::Vector3f> h_pt(3);
for (int itr = 0; itr < num_iterations; itr++) {
thrust::tabulate(d_keys.begin(), d_keys.end(), random_functor(rand(), num_points));
thrust::sort_by_key(utility::exec_policy(utility::GetStream(0))->on(utility::GetStream(0)),
thrust::sort_by_key(utility::exec_policy(0)->on(0),
d_keys.begin(), d_keys.end(), d_cards.begin());
// Fit model to num_model_parameters randomly selected points among the
// inliers.
Expand Down
16 changes: 8 additions & 8 deletions src/cupoch/geometry/trianglemesh.cu
Original file line number Diff line number Diff line change
Expand Up @@ -501,7 +501,7 @@ TriangleMesh &TriangleMesh::ComputeVertexNormals(bool normalized /* = true*/) {
thrust::copy(range.begin(), range.end(), nm_thrice.begin());
utility::device_vector<Eigen::Vector3i> copy_tri = triangles_;
int *tri_ptr = (int *)(thrust::raw_pointer_cast(copy_tri.data()));
thrust::sort_by_key(utility::exec_policy(utility::GetStream(0))->on(utility::GetStream(0)),
thrust::sort_by_key(utility::exec_policy(0)->on(0),
tri_ptr, tri_ptr + copy_tri.size() * 3,
nm_thrice.begin());
auto end = thrust::reduce_by_key(
Expand All @@ -523,7 +523,7 @@ TriangleMesh &TriangleMesh::ComputeEdgeList() {
thrust::raw_pointer_cast(edge_list_.data()));
thrust::for_each(thrust::make_counting_iterator<size_t>(0),
thrust::make_counting_iterator(triangles_.size()), func);
thrust::sort(utility::exec_policy(utility::GetStream(0))->on(utility::GetStream(0)),
thrust::sort(utility::exec_policy(0)->on(0),
edge_list_.begin(), edge_list_.end());
auto end = thrust::unique(edge_list_.begin(), edge_list_.end());
size_t n_out = thrust::distance(edge_list_.begin(), end);
Expand Down Expand Up @@ -956,7 +956,7 @@ TriangleMesh &TriangleMesh::RemoveDuplicatedVertices() {
bool has_vert_color = HasVertexColors();
size_t k = 0;
if (has_vert_normal && has_vert_color) {
thrust::sort_by_key(utility::exec_policy(utility::GetStream(0))->on(utility::GetStream(0)),
thrust::sort_by_key(utility::exec_policy(0)->on(0),
vertices_.begin(), vertices_.end(),
make_tuple_begin(index_new_to_old, vertex_normals_,
vertex_colors_));
Expand All @@ -974,7 +974,7 @@ TriangleMesh &TriangleMesh::RemoveDuplicatedVertices() {
k = thrust::distance(begin, end1.second);
} else if (has_vert_normal) {
thrust::sort_by_key(
utility::exec_policy(utility::GetStream(0))->on(utility::GetStream(0)),
utility::exec_policy(0)->on(0),
vertices_.begin(), vertices_.end(),
make_tuple_begin(index_new_to_old, vertex_normals_));
auto end0 = thrust::reduce_by_key(
Expand All @@ -989,7 +989,7 @@ TriangleMesh &TriangleMesh::RemoveDuplicatedVertices() {
vertex_normals_.begin());
k = thrust::distance(vertex_normals_.begin(), end1.second);
} else if (has_vert_color) {
thrust::sort_by_key(utility::exec_policy(utility::GetStream(0))->on(utility::GetStream(0)),
thrust::sort_by_key(utility::exec_policy(0)->on(0),
vertices_.begin(), vertices_.end(),
make_tuple_begin(index_new_to_old, vertex_colors_));
auto end0 = thrust::reduce_by_key(
Expand All @@ -1004,7 +1004,7 @@ TriangleMesh &TriangleMesh::RemoveDuplicatedVertices() {
vertex_colors_.begin());
k = thrust::distance(vertex_colors_.begin(), end1.second);
} else {
thrust::sort_by_key(utility::exec_policy(utility::GetStream(0))->on(utility::GetStream(0)),
thrust::sort_by_key(utility::exec_policy(0)->on(0),
vertices_.begin(), vertices_.end(),
index_new_to_old.begin());
auto end0 = thrust::reduce_by_key(
Expand Down Expand Up @@ -1061,15 +1061,15 @@ TriangleMesh &TriangleMesh::RemoveDuplicatedTriangles() {
thrust::transform(triangles_.begin(), triangles_.end(),
new_triangles.begin(), align_triangle_functor());
if (has_tri_normal) {
thrust::sort_by_key(utility::exec_policy(utility::GetStream(0))->on(utility::GetStream(0)),
thrust::sort_by_key(utility::exec_policy(0)->on(0),
new_triangles.begin(), new_triangles.end(),
triangle_normals_.begin());
auto end = thrust::unique_by_key(new_triangles.begin(),
new_triangles.end(),
triangle_normals_.begin());
k = thrust::distance(new_triangles.begin(), end.first);
} else {
thrust::sort(utility::exec_policy(utility::GetStream(0))->on(utility::GetStream(0)),
thrust::sort(utility::exec_policy(0)->on(0),
new_triangles.begin(), new_triangles.end());
auto end = thrust::unique(new_triangles.begin(), new_triangles.end());
k = thrust::distance(new_triangles.begin(), end);
Expand Down
6 changes: 3 additions & 3 deletions src/cupoch/geometry/voxelgrid.cu
Original file line number Diff line number Diff line change
Expand Up @@ -251,7 +251,7 @@ VoxelGrid &VoxelGrid::operator+=(const VoxelGrid &voxelgrid) {
voxels_values_.insert(voxels_values_.end(),
voxelgrid.voxels_values_.begin(),
voxelgrid.voxels_values_.end());
thrust::sort_by_key(utility::exec_policy(utility::GetStream(0))->on(utility::GetStream(0)),
thrust::sort_by_key(utility::exec_policy(0)->on(0),
voxels_keys_.begin(), voxels_keys_.end(),
voxels_values_.begin());
utility::device_vector<int> counts(voxels_keys_.size());
Expand Down Expand Up @@ -285,7 +285,7 @@ VoxelGrid VoxelGrid::operator+(const VoxelGrid &voxelgrid) const {
void VoxelGrid::AddVoxel(const Voxel &voxel) {
voxels_keys_.push_back(voxel.grid_index_);
voxels_values_.push_back(voxel);
thrust::sort_by_key(utility::exec_policy(utility::GetStream(0))->on(utility::GetStream(0)),
thrust::sort_by_key(utility::exec_policy(0)->on(0),
voxels_keys_.begin(), voxels_keys_.end(),
voxels_values_.begin());
auto end = thrust::unique_by_key(voxels_keys_.begin(), voxels_keys_.end(),
Expand All @@ -301,7 +301,7 @@ void VoxelGrid::AddVoxels(const utility::device_vector<Voxel> &voxels) {
thrust::make_transform_iterator(
voxels.end(), extract_grid_index_functor()));
voxels_values_.insert(voxels_values_.end(), voxels.begin(), voxels.end());
thrust::sort_by_key(utility::exec_policy(utility::GetStream(0))->on(utility::GetStream(0)),
thrust::sort_by_key(utility::exec_policy(0)->on(0),
voxels_keys_.begin(), voxels_keys_.end(),
voxels_values_.begin());
auto end = thrust::unique_by_key(voxels_keys_.begin(), voxels_keys_.end(),
Expand Down
4 changes: 2 additions & 2 deletions src/cupoch/geometry/voxelgrid_factory.cu
Original file line number Diff line number Diff line change
Expand Up @@ -147,7 +147,7 @@ std::shared_ptr<VoxelGrid> VoxelGrid::CreateDense(const Eigen::Vector3f &origin,
thrust::make_counting_iterator<size_t>(n_total),
make_tuple_begin(output->voxels_keys_, output->voxels_values_),
func);
thrust::sort_by_key(utility::exec_policy(utility::GetStream(0))->on(utility::GetStream(0)),
thrust::sort_by_key(utility::exec_policy(0)->on(0),
output->voxels_keys_.begin(),
output->voxels_keys_.end(),
output->voxels_values_.begin());
Expand Down Expand Up @@ -189,7 +189,7 @@ std::shared_ptr<VoxelGrid> VoxelGrid::CreateFromPointCloudWithinBounds(
input.colors_.begin(),
make_tuple_begin(voxels_keys, voxels_values), func);
}
thrust::sort_by_key(utility::exec_policy(utility::GetStream(0))->on(utility::GetStream(0)),
thrust::sort_by_key(utility::exec_policy(0)->on(0),
voxels_keys.begin(), voxels_keys.end(),
voxels_values.begin());

Expand Down
2 changes: 1 addition & 1 deletion src/cupoch/registration/fast_global_registration.cu
Original file line number Diff line number Diff line change
Expand Up @@ -136,7 +136,7 @@ utility::device_vector<thrust::tuple<int, int>> AdvancedMatching(
thrust::make_counting_iterator<int>(corresK.size()),
corresK.end()),
corres.begin() + nPtj);
thrust::sort(utility::exec_policy(utility::GetStream(0))->on(utility::GetStream(0)),
thrust::sort(utility::exec_policy(0)->on(0),
corres.begin(), corres.end());
utility::LogDebug("points are remained : {:d}", corres.size());

Expand Down
2 changes: 1 addition & 1 deletion src/cupoch/registration/permutohedral.inl
Original file line number Diff line number Diff line change
Expand Up @@ -172,7 +172,7 @@ void Permutohedral<Dim>::BuildLatticeIndexNoBlur(
[] __device__(float w) { return w < 0.0; });
weights.resize(thrust::distance(weights.begin(), w_end));

thrust::sort_by_key(utility::exec_policy(utility::GetStream(0))->on(utility::GetStream(0)),
thrust::sort_by_key(utility::exec_policy(0)->on(0),
keys.begin(), keys.end(),
make_tuple_begin(weights, vertices),
[] __device__(const LatticeCoordKey<Dim>& lhs,
Expand Down
2 changes: 1 addition & 1 deletion src/cupoch/visualization/shader/simple_shader.cu
Original file line number Diff line number Diff line change
Expand Up @@ -850,7 +850,7 @@ bool SimpleShaderForDistanceTransform::PrepareBinding(
make_tuple_iterator(thrust::make_counting_iterator(n_out), dist_trans.voxels_.end()),
make_tuple_iterator(points, colors), func);
auto tp_begin = make_tuple_iterator(points, colors);
thrust::sort(utility::exec_policy(utility::GetStream(0))->on(utility::GetStream(0)),
thrust::sort(utility::exec_policy(0)->on(0),
tp_begin, tp_begin + n_out, alpha_greater_functor());
draw_arrays_mode_ = GL_POINTS;
draw_arrays_size_ = GLsizei(n_out);
Expand Down
7 changes: 3 additions & 4 deletions src/python/cupoch_pybind/geometry/pointcloud.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -173,18 +173,17 @@ void pybind_pointcloud(py::module &m) {
.def(
"remove_radius_outlier",
[](const geometry::PointCloud &pcd, size_t nb_points,
float search_radius, int max_search_points) {
float search_radius) {
auto res = pcd.RemoveRadiusOutliers(nb_points,
search_radius,
max_search_points);
search_radius);
return std::make_tuple(
std::get<0>(res),
wrapper::device_vector_size_t(
std::move(std::get<1>(res))));
},
"Function to remove points that have less than nb_points"
" in a given sphere of a given radius",
"nb_points"_a, "radius"_a, "max_search_points"_a = geometry::NUM_MAX_NN)
"nb_points"_a, "radius"_a)
.def(
"remove_statistical_outlier",
[](const geometry::PointCloud &pcd, size_t nb_neighbors,
Expand Down
Loading

0 comments on commit ac5ca36

Please sign in to comment.