Open3D (C++ API)  0.12.0
TSDFVoxelGrid.h
Go to the documentation of this file.
1 // ----------------------------------------------------------------------------
2 // - Open3D: www.open3d.org -
3 // ----------------------------------------------------------------------------
4 // The MIT License (MIT)
5 //
6 // Copyright (c) 2018 www.open3d.org
7 //
8 // Permission is hereby granted, free of charge, to any person obtaining a copy
9 // of this software and associated documentation files (the "Software"), to deal
10 // in the Software without restriction, including without limitation the rights
11 // to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
12 // copies of the Software, and to permit persons to whom the Software is
13 // furnished to do so, subject to the following conditions:
14 //
15 // The above copyright notice and this permission notice shall be included in
16 // all copies or substantial portions of the Software.
17 //
18 // THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
19 // IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
20 // FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
21 // AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
22 // LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
23 // FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS
24 // IN THE SOFTWARE.
25 // ----------------------------------------------------------------------------
26 
27 #pragma once
28 
29 #include <Eigen/Core>
30 #include <string>
31 #include <unordered_map>
32 #include <unordered_set>
33 
34 #include "open3d/core/Tensor.h"
35 #include "open3d/core/TensorList.h"
42 
43 namespace open3d {
44 namespace t {
45 namespace geometry {
46 
58 public:
60  TSDFVoxelGrid(std::unordered_map<std::string, core::Dtype> attr_dtype_map =
61  {{"tsdf", core::Dtype::Float32},
62  {"weight", core::Dtype::UInt16},
63  {"color", core::Dtype::UInt16}},
64  float voxel_size = 3.0 / 512.0, /* in meter */
65  float sdf_trunc = 0.04, /* in meter */
66  int64_t block_resolution = 16, /* block Tensor resolution */
67  int64_t block_count = 1000,
68  const core::Device &device = core::Device("CPU:0"));
69 
71 
73  void Integrate(const Image &depth,
74  const core::Tensor &intrinsics,
75  const core::Tensor &extrinsics,
76  double depth_scale = 1000.0,
77  double depth_max = 3.0);
78 
80  void Integrate(const Image &depth,
81  const Image &color,
82  const core::Tensor &intrinsics,
83  const core::Tensor &extrinsics,
84  double depth_scale = 1000.0,
85  double depth_max = 3.0);
86 
89 
92 
94  TSDFVoxelGrid Copy(const core::Device &device);
95 
98 
100  TSDFVoxelGrid CUDA(int device_id = 0);
101 
103 
104 protected:
114  std::pair<core::Tensor, core::Tensor> BufferRadiusNeighbors(
115  const core::Tensor &active_addrs);
116 
117  float voxel_size_;
118  float sdf_trunc_;
119 
121  int64_t block_count_;
122 
124 
125  std::shared_ptr<core::Hashmap> block_hashmap_;
126 
127  std::unordered_map<std::string, core::Dtype> attr_dtype_map_;
128 };
129 } // namespace geometry
130 } // namespace t
131 } // namespace open3d
std::shared_ptr< core::Hashmap > block_hashmap_
Definition: TSDFVoxelGrid.h:125
~TSDFVoxelGrid()
Definition: TSDFVoxelGrid.h:70
TSDFVoxelGrid CUDA(int device_id=0)
Copy TSDFVoxelGrid to CUDA.
Definition: TSDFVoxelGrid.cpp:316
TSDFVoxelGrid CPU()
Copy TSDFVoxelGrid to CPU.
Definition: TSDFVoxelGrid.cpp:309
A TriangleMesh contains vertices and triangles.
Definition: TriangleMesh.h:106
TSDFVoxelGrid(std::unordered_map< std::string, core::Dtype > attr_dtype_map={{"tsdf", core::Dtype::Float32}, {"weight", core::Dtype::UInt16}, {"color", core::Dtype::UInt16}}, float voxel_size=3.0/512.0, float sdf_trunc=0.04, int64_t block_resolution=16, int64_t block_count=1000, const core::Device &device=core::Device("CPU:0"))
Default Constructor.
Definition: TSDFVoxelGrid.cpp:38
core::Device device_
Definition: TSDFVoxelGrid.h:123
std::unordered_map< std::string, core::Dtype > attr_dtype_map_
Definition: TSDFVoxelGrid.h:127
The Image class stores image with customizable rols, cols, channels, dtype and device.
Definition: Image.h:45
math::float4 color
Definition: LineSetBuffers.cpp:64
float sdf_trunc_
Definition: TSDFVoxelGrid.h:118
TSDFVoxelGrid Copy(const core::Device &device)
Copy TSDFVoxelGrid to the target device.
Definition: TSDFVoxelGrid.cpp:300
Definition: Device.h:39
A pointcloud contains a set of 3D points.
Definition: PointCloud.h:94
std::pair< core::Tensor, core::Tensor > BufferRadiusNeighbors(const core::Tensor &active_addrs)
Definition: TSDFVoxelGrid.cpp:325
Definition: TSDFVoxelGrid.h:57
static const Dtype UInt16
Definition: Dtype.h:47
static const Dtype Float32
Definition: Dtype.h:42
void Integrate(const Image &depth, const core::Tensor &intrinsics, const core::Tensor &extrinsics, double depth_scale=1000.0, double depth_max=3.0)
Depth-only integration.
Definition: TSDFVoxelGrid.cpp:110
PointCloud ExtractSurfacePoints()
Extract point cloud near iso-surfaces.
Definition: TSDFVoxelGrid.cpp:220
int64_t block_resolution_
Definition: TSDFVoxelGrid.h:120
Definition: PinholeCameraIntrinsic.cpp:35
Definition: Tensor.h:48
int64_t block_count_
Definition: TSDFVoxelGrid.h:121
TriangleMesh ExtractSurfaceMesh()
Extract mesh near iso-surfaces with Marching Cubes.
Definition: TSDFVoxelGrid.cpp:257
core::Device GetDevice()
Definition: TSDFVoxelGrid.h:102
float voxel_size_
Definition: TSDFVoxelGrid.h:117