Skip to content

Commit

Permalink
add convert function
Browse files Browse the repository at this point in the history
  • Loading branch information
neka-nat committed Sep 27, 2020
1 parent f971fe5 commit dd49454
Show file tree
Hide file tree
Showing 8 changed files with 97 additions and 7 deletions.
12 changes: 7 additions & 5 deletions .github/workflows/c-cpp.yml
Original file line number Diff line number Diff line change
Expand Up @@ -57,8 +57,10 @@ jobs:
rename s/linux/manylinux1/ *.whl
- name: Publish package
if: github.event_name == 'push' && startsWith(github.ref, 'refs/tags')
uses: pypa/gh-action-pypi-publish@master
with:
user: ${{ secrets.pypi_username }}
password: ${{ secrets.pypi_password }}
packages_dir: build/lib/python_package
env:
PYPI_USERNAME: ${{ secrets.pypi_username }}
PYPI_PASSWORD: ${{ secrets.pypi_password }}
run: |
python -m pip install twine
cd build/lib/python_package
python -m twine upload -u ${PYPI_USERNAME} -p ${PYPI_PASSWORD} pip_package/*
3 changes: 3 additions & 0 deletions src/cupoch/geometry/distancetransform.h
Original file line number Diff line number Diff line change
Expand Up @@ -25,6 +25,7 @@
namespace cupoch {
namespace geometry {
class VoxelGrid;
class OccupancyGrid;

class DistanceVoxel {
public:
Expand Down Expand Up @@ -68,6 +69,8 @@ class DistanceTransform : public DenseGrid<DistanceVoxel> {
float GetDistance(const Eigen::Vector3f& query) const;
utility::device_vector<float> GetDistances(const utility::device_vector<Eigen::Vector3f>& queries) const;

static std::shared_ptr<DistanceTransform> CreateFromOccupancyGrid(const OccupancyGrid &input);

private:
utility::device_vector<DistanceVoxel> buffer_;
};
Expand Down
51 changes: 51 additions & 0 deletions src/cupoch/geometry/distancetransform_factory.cu
Original file line number Diff line number Diff line change
@@ -0,0 +1,51 @@
/**
* Copyright (c) 2020 Neka-Nat
* Permission is hereby granted, free of charge, to any person obtaining a copy
* of this software and associated documentation files (the "Software"), to deal
* in the Software without restriction, including without limitation the rights
* to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
* copies of the Software, and to permit persons to whom the Software is
* furnished to do so, subject to the following conditions:
*
* The above copyright notice and this permission notice shall be included in
* all copies or substantial portions of the Software.
*
* THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
* IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
* FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
* AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
* LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
* FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS
* IN THE SOFTWARE.
**/
#include "cupoch/geometry/occupancygrid.h"
#include "cupoch/geometry/distancetransform.h"

namespace cupoch {
namespace geometry {

std::shared_ptr<DistanceTransform> DistanceTransform::CreateFromOccupancyGrid(const OccupancyGrid &input) {
auto output = std::make_shared<DistanceTransform>();
if (input.voxel_size_ <= 0.0) {
utility::LogError("[CreateOccupancyGrid] occupancy grid voxel_size <= 0.");
}
output->voxel_size_ = input.voxel_size_;
output->origin_ = input.origin_;
output->resolution_ = input.resolution_;
output->voxels_.resize(input.voxels_.size());
std::shared_ptr<utility::device_vector<OccupancyVoxel>> occvoxels = input.ExtractOccupiedVoxels();
thrust::transform(occvoxels->begin(), occvoxels->end(),
thrust::make_permutation_iterator(
output->voxels_.begin(),
thrust::make_transform_iterator(occvoxels->begin(),
[res = output->resolution_] __device__ (const OccupancyVoxel& voxel) {
return IndexOf(voxel.grid_index_.cast<int>(), res);
})),
[res = output->resolution_] __device__ (const OccupancyVoxel& voxel) {
return DistanceVoxel(voxel.grid_index_, 0);
});
return output;
}

}
}
4 changes: 4 additions & 0 deletions src/cupoch/geometry/voxelgrid.h
Original file line number Diff line number Diff line change
Expand Up @@ -41,6 +41,7 @@ class PointCloud;
class TriangleMesh;
class OrientedBoundingBox;
class Image;
class OccupancyGrid;

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

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

static std::shared_ptr<VoxelGrid> CreateFromOccupancyGrid(
const OccupancyGrid &input);

public:
float voxel_size_ = 0.0;
Eigen::Vector3f origin_ = Eigen::Vector3f::Zero();
Expand Down
22 changes: 22 additions & 0 deletions src/cupoch/geometry/voxelgrid_factory.cu
Original file line number Diff line number Diff line change
Expand Up @@ -25,6 +25,7 @@
#include "cupoch/geometry/intersection_test.h"
#include "cupoch/geometry/pointcloud.h"
#include "cupoch/geometry/trianglemesh.h"
#include "cupoch/geometry/occupancygrid.h"
#include "cupoch/geometry/voxelgrid.h"
#include "cupoch/utility/console.h"
#include "cupoch/utility/platform.h"
Expand Down Expand Up @@ -273,4 +274,25 @@ std::shared_ptr<VoxelGrid> VoxelGrid::CreateFromTriangleMesh(
Eigen::Vector3f max_bound = input.GetMaxBound() + voxel_size3 * 0.5;
return CreateFromTriangleMeshWithinBounds(input, voxel_size, min_bound,
max_bound);
}

std::shared_ptr<VoxelGrid> VoxelGrid::CreateFromOccupancyGrid(
const OccupancyGrid &input) {
auto output = std::make_shared<VoxelGrid>();
if (input.voxel_size_ <= 0.0) {
utility::LogError("[CreateOccupancyGrid] occupancy grid voxel_size <= 0.");
}
output->voxel_size_ = input.voxel_size_;
output->origin_ = input.origin_;
std::shared_ptr<utility::device_vector<OccupancyVoxel>> occvoxels = input.ExtractOccupiedVoxels();
output->voxels_keys_.resize(occvoxels->size());
output->voxels_values_.resize(occvoxels->size());
thrust::transform(occvoxels->begin(), occvoxels->end(),
make_tuple_begin(output->voxels_keys_, output->voxels_values_),
[] __device__ (const OccupancyVoxel& voxel) {
return thrust::make_tuple(voxel.grid_index_.cast<int>(),
Voxel(voxel.grid_index_.cast<int>(),
voxel.color_));
});
return output;
}
4 changes: 2 additions & 2 deletions src/cupoch/version.txt
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
CUPOCH_VERSION_MAJOR 0
CUPOCH_VERSION_MINOR 1
CUPOCH_VERSION_PATCH 3
CUPOCH_VERSION_TWEAK 0
CUPOCH_VERSION_PATCH 4
CUPOCH_VERSION_TWEAK 1
4 changes: 4 additions & 0 deletions src/python/cupoch_pybind/geometry/distancetransform.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -80,6 +80,10 @@ void pybind_distancetransform(py::module &m) {
"Function to compute EDT from voxel grid.")
.def("get_distance", &geometry::DistanceTransform::GetDistance)
.def("get_distances", &geometry::DistanceTransform::GetDistances)
.def_static(
"create_from_occupancy_grid",
&geometry::DistanceTransform::CreateFromOccupancyGrid,
"Function to make voxels from a Occupancy Grid")
.def_readwrite("voxel_size", &geometry::DistanceTransform::voxel_size_)
.def_readwrite("resolution", &geometry::DistanceTransform::resolution_)
.def_readwrite("origin", &geometry::DistanceTransform::origin_);
Expand Down
4 changes: 4 additions & 0 deletions src/python/cupoch_pybind/geometry/voxelgrid.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -151,6 +151,10 @@ void pybind_voxelgrid(py::module &m) {
&geometry::VoxelGrid::CreateFromTriangleMeshWithinBounds,
"Function to make voxels from a PointCloud", "input"_a,
"voxel_size"_a, "min_bound"_a, "max_bound"_a)
.def_static(
"create_from_occupancy_grid",
&geometry::VoxelGrid::CreateFromOccupancyGrid,
"Function to make voxels from a Occupancy Grid")
.def_readwrite("origin", &geometry::VoxelGrid::origin_,
"``float32`` vector of length 3: Coorindate of the "
"origin point.")
Expand Down

0 comments on commit dd49454

Please sign in to comment.