|
| 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 | +} |
0 commit comments