Skip to content

Commit dd49454

Browse files
committed
add convert function
1 parent f971fe5 commit dd49454

File tree

8 files changed

+97
-7
lines changed

8 files changed

+97
-7
lines changed

.github/workflows/c-cpp.yml

+7-5
Original file line numberDiff line numberDiff line change
@@ -57,8 +57,10 @@ jobs:
5757
rename s/linux/manylinux1/ *.whl
5858
- name: Publish package
5959
if: github.event_name == 'push' && startsWith(github.ref, 'refs/tags')
60-
uses: pypa/gh-action-pypi-publish@master
61-
with:
62-
user: ${{ secrets.pypi_username }}
63-
password: ${{ secrets.pypi_password }}
64-
packages_dir: build/lib/python_package
60+
env:
61+
PYPI_USERNAME: ${{ secrets.pypi_username }}
62+
PYPI_PASSWORD: ${{ secrets.pypi_password }}
63+
run: |
64+
python -m pip install twine
65+
cd build/lib/python_package
66+
python -m twine upload -u ${PYPI_USERNAME} -p ${PYPI_PASSWORD} pip_package/*

src/cupoch/geometry/distancetransform.h

+3
Original file line numberDiff line numberDiff line change
@@ -25,6 +25,7 @@
2525
namespace cupoch {
2626
namespace geometry {
2727
class VoxelGrid;
28+
class OccupancyGrid;
2829

2930
class DistanceVoxel {
3031
public:
@@ -68,6 +69,8 @@ class DistanceTransform : public DenseGrid<DistanceVoxel> {
6869
float GetDistance(const Eigen::Vector3f& query) const;
6970
utility::device_vector<float> GetDistances(const utility::device_vector<Eigen::Vector3f>& queries) const;
7071

72+
static std::shared_ptr<DistanceTransform> CreateFromOccupancyGrid(const OccupancyGrid &input);
73+
7174
private:
7275
utility::device_vector<DistanceVoxel> buffer_;
7376
};
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,51 @@
1+
/**
2+
* Copyright (c) 2020 Neka-Nat
3+
* Permission is hereby granted, free of charge, to any person obtaining a copy
4+
* of this software and associated documentation files (the "Software"), to deal
5+
* in the Software without restriction, including without limitation the rights
6+
* to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
7+
* copies of the Software, and to permit persons to whom the Software is
8+
* furnished to do so, subject to the following conditions:
9+
*
10+
* The above copyright notice and this permission notice shall be included in
11+
* all copies or substantial portions of the Software.
12+
*
13+
* THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
14+
* IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
15+
* FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
16+
* AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
17+
* LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
18+
* FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS
19+
* IN THE SOFTWARE.
20+
**/
21+
#include "cupoch/geometry/occupancygrid.h"
22+
#include "cupoch/geometry/distancetransform.h"
23+
24+
namespace cupoch {
25+
namespace geometry {
26+
27+
std::shared_ptr<DistanceTransform> DistanceTransform::CreateFromOccupancyGrid(const OccupancyGrid &input) {
28+
auto output = std::make_shared<DistanceTransform>();
29+
if (input.voxel_size_ <= 0.0) {
30+
utility::LogError("[CreateOccupancyGrid] occupancy grid voxel_size <= 0.");
31+
}
32+
output->voxel_size_ = input.voxel_size_;
33+
output->origin_ = input.origin_;
34+
output->resolution_ = input.resolution_;
35+
output->voxels_.resize(input.voxels_.size());
36+
std::shared_ptr<utility::device_vector<OccupancyVoxel>> occvoxels = input.ExtractOccupiedVoxels();
37+
thrust::transform(occvoxels->begin(), occvoxels->end(),
38+
thrust::make_permutation_iterator(
39+
output->voxels_.begin(),
40+
thrust::make_transform_iterator(occvoxels->begin(),
41+
[res = output->resolution_] __device__ (const OccupancyVoxel& voxel) {
42+
return IndexOf(voxel.grid_index_.cast<int>(), res);
43+
})),
44+
[res = output->resolution_] __device__ (const OccupancyVoxel& voxel) {
45+
return DistanceVoxel(voxel.grid_index_, 0);
46+
});
47+
return output;
48+
}
49+
50+
}
51+
}

src/cupoch/geometry/voxelgrid.h

+4
Original file line numberDiff line numberDiff line change
@@ -41,6 +41,7 @@ class PointCloud;
4141
class TriangleMesh;
4242
class OrientedBoundingBox;
4343
class Image;
44+
class OccupancyGrid;
4445

4546
__device__ const int INVALID_VOXEL_INDEX = std::numeric_limits<int>::min();
4647

@@ -194,6 +195,9 @@ class VoxelGrid : public GeometryBase<3> {
194195
const Eigen::Vector3f &min_bound,
195196
const Eigen::Vector3f &max_bound);
196197

198+
static std::shared_ptr<VoxelGrid> CreateFromOccupancyGrid(
199+
const OccupancyGrid &input);
200+
197201
public:
198202
float voxel_size_ = 0.0;
199203
Eigen::Vector3f origin_ = Eigen::Vector3f::Zero();

src/cupoch/geometry/voxelgrid_factory.cu

+22
Original file line numberDiff line numberDiff line change
@@ -25,6 +25,7 @@
2525
#include "cupoch/geometry/intersection_test.h"
2626
#include "cupoch/geometry/pointcloud.h"
2727
#include "cupoch/geometry/trianglemesh.h"
28+
#include "cupoch/geometry/occupancygrid.h"
2829
#include "cupoch/geometry/voxelgrid.h"
2930
#include "cupoch/utility/console.h"
3031
#include "cupoch/utility/platform.h"
@@ -273,4 +274,25 @@ std::shared_ptr<VoxelGrid> VoxelGrid::CreateFromTriangleMesh(
273274
Eigen::Vector3f max_bound = input.GetMaxBound() + voxel_size3 * 0.5;
274275
return CreateFromTriangleMeshWithinBounds(input, voxel_size, min_bound,
275276
max_bound);
277+
}
278+
279+
std::shared_ptr<VoxelGrid> VoxelGrid::CreateFromOccupancyGrid(
280+
const OccupancyGrid &input) {
281+
auto output = std::make_shared<VoxelGrid>();
282+
if (input.voxel_size_ <= 0.0) {
283+
utility::LogError("[CreateOccupancyGrid] occupancy grid voxel_size <= 0.");
284+
}
285+
output->voxel_size_ = input.voxel_size_;
286+
output->origin_ = input.origin_;
287+
std::shared_ptr<utility::device_vector<OccupancyVoxel>> occvoxels = input.ExtractOccupiedVoxels();
288+
output->voxels_keys_.resize(occvoxels->size());
289+
output->voxels_values_.resize(occvoxels->size());
290+
thrust::transform(occvoxels->begin(), occvoxels->end(),
291+
make_tuple_begin(output->voxels_keys_, output->voxels_values_),
292+
[] __device__ (const OccupancyVoxel& voxel) {
293+
return thrust::make_tuple(voxel.grid_index_.cast<int>(),
294+
Voxel(voxel.grid_index_.cast<int>(),
295+
voxel.color_));
296+
});
297+
return output;
276298
}

src/cupoch/version.txt

+2-2
Original file line numberDiff line numberDiff line change
@@ -1,4 +1,4 @@
11
CUPOCH_VERSION_MAJOR 0
22
CUPOCH_VERSION_MINOR 1
3-
CUPOCH_VERSION_PATCH 3
4-
CUPOCH_VERSION_TWEAK 0
3+
CUPOCH_VERSION_PATCH 4
4+
CUPOCH_VERSION_TWEAK 1

src/python/cupoch_pybind/geometry/distancetransform.cpp

+4
Original file line numberDiff line numberDiff line change
@@ -80,6 +80,10 @@ void pybind_distancetransform(py::module &m) {
8080
"Function to compute EDT from voxel grid.")
8181
.def("get_distance", &geometry::DistanceTransform::GetDistance)
8282
.def("get_distances", &geometry::DistanceTransform::GetDistances)
83+
.def_static(
84+
"create_from_occupancy_grid",
85+
&geometry::DistanceTransform::CreateFromOccupancyGrid,
86+
"Function to make voxels from a Occupancy Grid")
8387
.def_readwrite("voxel_size", &geometry::DistanceTransform::voxel_size_)
8488
.def_readwrite("resolution", &geometry::DistanceTransform::resolution_)
8589
.def_readwrite("origin", &geometry::DistanceTransform::origin_);

src/python/cupoch_pybind/geometry/voxelgrid.cpp

+4
Original file line numberDiff line numberDiff line change
@@ -151,6 +151,10 @@ void pybind_voxelgrid(py::module &m) {
151151
&geometry::VoxelGrid::CreateFromTriangleMeshWithinBounds,
152152
"Function to make voxels from a PointCloud", "input"_a,
153153
"voxel_size"_a, "min_bound"_a, "max_bound"_a)
154+
.def_static(
155+
"create_from_occupancy_grid",
156+
&geometry::VoxelGrid::CreateFromOccupancyGrid,
157+
"Function to make voxels from a Occupancy Grid")
154158
.def_readwrite("origin", &geometry::VoxelGrid::origin_,
155159
"``float32`` vector of length 3: Coorindate of the "
156160
"origin point.")

0 commit comments

Comments
 (0)