Open3D (C++ API)  0.18.0+fcc396e
ScalableTSDFVolume.h
Go to the documentation of this file.
1 // ----------------------------------------------------------------------------
2 // - Open3D: www.open3d.org -
3 // ----------------------------------------------------------------------------
4 // Copyright (c) 2018-2024 www.open3d.org
5 // SPDX-License-Identifier: MIT
6 // ----------------------------------------------------------------------------
7 
8 #pragma once
9 
10 #include <memory>
11 #include <unordered_map>
12 
14 #include "open3d/utility/Helper.h"
15 
16 namespace open3d {
17 namespace pipelines {
18 namespace integration {
19 
20 class UniformTSDFVolume;
21 
41 public:
42  struct VolumeUnit {
43  public:
44  VolumeUnit() : volume_(NULL) {}
45 
46  public:
47  std::shared_ptr<UniformTSDFVolume> volume_;
48  Eigen::Vector3i index_;
49  };
50 
51 public:
52  ScalableTSDFVolume(double voxel_length,
53  double sdf_trunc,
54  TSDFVolumeColorType color_type,
55  int volume_unit_resolution = 16,
56  int depth_sampling_stride = 4);
57  ~ScalableTSDFVolume() override;
58 
59 public:
60  void Reset() override;
62  const camera::PinholeCameraIntrinsic &intrinsic,
63  const Eigen::Matrix4d &extrinsic) override;
64  std::shared_ptr<geometry::PointCloud> ExtractPointCloud() override;
65  std::shared_ptr<geometry::TriangleMesh> ExtractTriangleMesh() override;
67  std::shared_ptr<geometry::PointCloud> ExtractVoxelPointCloud();
68 
69 public:
73 
77  std::unordered_map<Eigen::Vector3i,
78  VolumeUnit,
81 
82 private:
83  Eigen::Vector3i LocateVolumeUnit(const Eigen::Vector3d &point) {
84  return Eigen::Vector3i((int)std::floor(point(0) / volume_unit_length_),
85  (int)std::floor(point(1) / volume_unit_length_),
86  (int)std::floor(point(2) / volume_unit_length_));
87  }
88 
89  std::shared_ptr<UniformTSDFVolume> OpenVolumeUnit(
90  const Eigen::Vector3i &index);
91 
92  Eigen::Vector3d GetNormalAt(const Eigen::Vector3d &p);
93 
94  double GetTSDFAt(const Eigen::Vector3d &p);
95 };
96 
97 } // namespace integration
98 } // namespace pipelines
99 } // namespace open3d
std::shared_ptr< core::Tensor > image
Definition: FilamentRenderer.cpp:183
Contains the pinhole camera intrinsic parameters.
Definition: PinholeCameraIntrinsic.h:32
RGBDImage is for a pair of registered color and depth images,.
Definition: RGBDImage.h:27
Definition: ScalableTSDFVolume.h:40
std::shared_ptr< geometry::TriangleMesh > ExtractTriangleMesh() override
Function to extract a triangle mesh, using the marching cubes algorithm. (https://en....
Definition: ScalableTSDFVolume.cpp:203
ScalableTSDFVolume(double voxel_length, double sdf_trunc, TSDFVolumeColorType color_type, int volume_unit_resolution=16, int depth_sampling_stride=4)
Definition: ScalableTSDFVolume.cpp:21
void Reset() override
Function to reset the TSDFVolume.
Definition: ScalableTSDFVolume.cpp:33
void Integrate(const geometry::RGBDImage &image, const camera::PinholeCameraIntrinsic &intrinsic, const Eigen::Matrix4d &extrinsic) override
Function to integrate an RGB-D image into the volume.
Definition: ScalableTSDFVolume.cpp:35
double volume_unit_length_
Definition: ScalableTSDFVolume.h:71
~ScalableTSDFVolume() override
Definition: ScalableTSDFVolume.cpp:31
std::unordered_map< Eigen::Vector3i, VolumeUnit, utility::hash_eigen< Eigen::Vector3i > > volume_units_
Definition: ScalableTSDFVolume.h:80
int depth_sampling_stride_
Definition: ScalableTSDFVolume.h:72
int volume_unit_resolution_
Definition: ScalableTSDFVolume.h:70
std::shared_ptr< geometry::PointCloud > ExtractVoxelPointCloud()
Debug function to extract the voxel data into a point cloud.
Definition: ScalableTSDFVolume.cpp:353
std::shared_ptr< geometry::PointCloud > ExtractPointCloud() override
Function to extract a point cloud with normals.
Definition: ScalableTSDFVolume.cpp:100
Base class of the Truncated Signed Distance Function (TSDF) volume.
Definition: TSDFVolume.h:42
TSDFVolumeColorType
Definition: TSDFVolume.h:22
FN_SPECIFIERS MiniVec< float, N > floor(const MiniVec< float, N > &a)
Definition: MiniVec.h:75
Definition: PinholeCameraIntrinsic.cpp:16
Eigen::Vector3i index_
Definition: ScalableTSDFVolume.h:48
std::shared_ptr< UniformTSDFVolume > volume_
Definition: ScalableTSDFVolume.h:47
Definition: Helper.h:71