Open3D (C++ API)  0.13.0
All Data Structures Namespaces Files Functions Variables Typedefs Enumerations Enumerator Friends Macros
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  const core::HashmapBackend &backend =
71 
73 
75  void Integrate(const Image &depth,
76  const core::Tensor &intrinsics,
77  const core::Tensor &extrinsics,
78  float depth_scale = 1000.0f,
79  float depth_max = 3.0f);
80 
82  void Integrate(const Image &depth,
83  const Image &color,
84  const core::Tensor &intrinsics,
85  const core::Tensor &extrinsics,
86  float depth_scale = 1000.0f,
87  float depth_max = 3.0f);
88 
90  None = 0,
91  VertexMap = (1 << 0),
92  DepthMap = (1 << 1),
93  ColorMap = (1 << 2),
94  NormalMap = (1 << 3),
95  RangeMap = (1 << 4)
96  };
105  std::unordered_map<SurfaceMaskCode, core::Tensor> RayCast(
106  const core::Tensor &intrinsics,
107  const core::Tensor &extrinsics,
108  int width,
109  int height,
110  float depth_scale = 1000.0f,
111  float depth_min = 0.1f,
112  float depth_max = 3.0f,
113  float weight_threshold = 3.0f,
114  int ray_cast_mask = SurfaceMaskCode::DepthMap |
115  SurfaceMaskCode::ColorMap);
116 
123  int estimate_number = -1,
124  float weight_threshold = 3.0f,
125  int surface_mask = SurfaceMaskCode::VertexMap |
126  SurfaceMaskCode::ColorMap);
127 
134  int estimate_vertices = -1,
135  float weight_threshold = 3.0f,
136  int surface_mask = SurfaceMaskCode::VertexMap |
137  SurfaceMaskCode::NormalMap |
138  SurfaceMaskCode::ColorMap);
139 
145  TSDFVoxelGrid To(const core::Device &device, bool copy = false) const;
146 
148  TSDFVoxelGrid Clone() const { return To(GetDevice(), true); }
149 
151  TSDFVoxelGrid CPU() const { return To(core::Device("CPU:0"), false); }
152 
154  TSDFVoxelGrid CUDA(int device_id = 0) const {
156  false);
157  }
158 
159  core::Device GetDevice() const { return device_; }
160 
161  std::shared_ptr<core::Hashmap> GetBlockHashmap() { return block_hashmap_; }
162 
163 protected:
173  std::pair<core::Tensor, core::Tensor> BufferRadiusNeighbors(
174  const core::Tensor &active_addrs);
175 
176  float voxel_size_;
177  float sdf_trunc_;
178 
180  int64_t block_count_;
181 
183 
184  // Global hashmap
185  std::shared_ptr<core::Hashmap> block_hashmap_;
186 
187  // Local hashmap for the `unique` operation of input points
188  std::shared_ptr<core::Hashmap> point_hashmap_;
190 
191  std::unordered_map<std::string, core::Dtype> attr_dtype_map_;
192 };
193 } // namespace geometry
194 } // namespace t
195 } // namespace open3d
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"), const core::HashmapBackend &backend=core::HashmapBackend::Default)
Default Constructor.
Definition: TSDFVoxelGrid.cpp:38
TSDFVoxelGrid CUDA(int device_id=0) const
Copy TSDFVoxelGrid to CUDA.
Definition: TSDFVoxelGrid.h:154
std::shared_ptr< core::Hashmap > block_hashmap_
Definition: TSDFVoxelGrid.h:185
void Integrate(const Image &depth, const core::Tensor &intrinsics, const core::Tensor &extrinsics, float depth_scale=1000.0f, float depth_max=3.0f)
Depth-only integration.
Definition: TSDFVoxelGrid.cpp:111
Definition: TSDFVoxelGrid.h:94
~TSDFVoxelGrid()
Definition: TSDFVoxelGrid.h:72
Definition: TSDFVoxelGrid.h:91
TSDFVoxelGrid To(const core::Device &device, bool copy=false) const
Definition: TSDFVoxelGrid.cpp:374
Definition: TSDFVoxelGrid.h:92
HashmapBackend
Definition: Hashmap.h:38
A TriangleMesh contains vertices and triangles.
Definition: TriangleMesh.h:106
SurfaceMaskCode
Definition: TSDFVoxelGrid.h:89
PointCloud ExtractSurfacePoints(int estimate_number=-1, float weight_threshold=3.0f, int surface_mask=SurfaceMaskCode::VertexMap|SurfaceMaskCode::ColorMap)
Definition: TSDFVoxelGrid.cpp:274
TSDFVoxelGrid Clone() const
Clone TSDFVoxelGrid on the same device.
Definition: TSDFVoxelGrid.h:148
core::Device device_
Definition: TSDFVoxelGrid.h:182
std::unordered_map< std::string, core::Dtype > attr_dtype_map_
Definition: TSDFVoxelGrid.h:191
Definition: TSDFVoxelGrid.h:90
Definition: TSDFVoxelGrid.h:95
core::Tensor active_block_coords_
Definition: TSDFVoxelGrid.h:189
The Image class stores image with customizable rows, cols, channels, dtype and device.
Definition: Image.h:48
math::float4 color
Definition: LineSetBuffers.cpp:64
TSDFVoxelGrid CPU() const
Copy TSDFVoxelGrid to CPU.
Definition: TSDFVoxelGrid.h:151
std::unordered_map< SurfaceMaskCode, core::Tensor > RayCast(const core::Tensor &intrinsics, const core::Tensor &extrinsics, int width, int height, float depth_scale=1000.0f, float depth_min=0.1f, float depth_max=3.0f, float weight_threshold=3.0f, int ray_cast_mask=SurfaceMaskCode::DepthMap|SurfaceMaskCode::ColorMap)
Definition: TSDFVoxelGrid.cpp:213
float sdf_trunc_
Definition: TSDFVoxelGrid.h:177
TriangleMesh ExtractSurfaceMesh(int estimate_vertices=-1, float weight_threshold=3.0f, int surface_mask=SurfaceMaskCode::VertexMap|SurfaceMaskCode::NormalMap|SurfaceMaskCode::ColorMap)
Definition: TSDFVoxelGrid.cpp:319
core::Device GetDevice() const
Definition: TSDFVoxelGrid.h:159
Definition: Device.h:39
A pointcloud contains a set of 3D points.
Definition: PointCloud.h:95
std::pair< core::Tensor, core::Tensor > BufferRadiusNeighbors(const core::Tensor &active_addrs)
Definition: TSDFVoxelGrid.cpp:387
Definition: TSDFVoxelGrid.h:57
static const Dtype UInt16
Definition: Dtype.h:49
static const Dtype Float32
Definition: Dtype.h:42
std::shared_ptr< core::Hashmap > point_hashmap_
Definition: TSDFVoxelGrid.h:188
int64_t block_resolution_
Definition: TSDFVoxelGrid.h:179
Definition: PinholeCameraIntrinsic.cpp:35
Definition: Tensor.h:50
int64_t block_count_
Definition: TSDFVoxelGrid.h:180
int height
Definition: FilePCD.cpp:72
float voxel_size_
Definition: TSDFVoxelGrid.h:176
Definition: ColorMap.h:35
std::shared_ptr< core::Hashmap > GetBlockHashmap()
Definition: TSDFVoxelGrid.h:161
int width
Definition: FilePCD.cpp:71