ACloudViewer  3.9.4
A Modern Library for 3D Data Processing
ScalableTSDFVolume.h
Go to the documentation of this file.
1 // ----------------------------------------------------------------------------
2 // - CloudViewer: www.cloudViewer.org -
3 // ----------------------------------------------------------------------------
4 // Copyright (c) 2018-2024 www.cloudViewer.org
5 // SPDX-License-Identifier: MIT
6 // ----------------------------------------------------------------------------
7 
8 #pragma once
9 
10 #include <Helper.h>
11 
12 #include <memory>
13 #include <unordered_map>
14 
16 
17 namespace cloudViewer {
18 namespace pipelines {
19 namespace integration {
20 
21 class UniformTSDFVolume;
22 
42 public:
43  struct VolumeUnit {
44  public:
45  VolumeUnit() : volume_(nullptr) {}
46 
47  public:
48  std::shared_ptr<UniformTSDFVolume> volume_;
50  };
51 
52 public:
53  ScalableTSDFVolume(double voxel_length,
54  double sdf_trunc,
55  TSDFVolumeColorType color_type,
56  int volume_unit_resolution = 16,
57  int depth_sampling_stride = 4);
58  ~ScalableTSDFVolume() override;
59 
60 public:
61  void Reset() override;
63  const camera::PinholeCameraIntrinsic &intrinsic,
64  const Eigen::Matrix4d &extrinsic) override;
65  std::shared_ptr<ccPointCloud> ExtractPointCloud() override;
66  std::shared_ptr<ccMesh> ExtractTriangleMesh() override;
68  std::shared_ptr<ccPointCloud> ExtractVoxelPointCloud();
69 
70 public:
74 
78  std::unordered_map<Eigen::Vector3i,
79  VolumeUnit,
82 
83 private:
84  Eigen::Vector3i LocateVolumeUnit(const Eigen::Vector3d &point) {
88  }
89 
90  std::shared_ptr<UniformTSDFVolume> OpenVolumeUnit(
91  const Eigen::Vector3i &index);
92 
93  Eigen::Vector3d GetNormalAt(const Eigen::Vector3d &p);
94 
95  double GetTSDFAt(const Eigen::Vector3d &p);
96 };
97 
98 } // namespace integration
99 } // namespace pipelines
100 } // namespace cloudViewer
std::shared_ptr< core::Tensor > image
Contains the pinhole camera intrinsic parameters.
RGBDImage is for a pair of registered color and depth images,.
Definition: RGBDImage.h:27
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.
std::shared_ptr< ccPointCloud > ExtractVoxelPointCloud()
Debug function to extract the voxel data into a point cloud.
std::shared_ptr< ccMesh > ExtractTriangleMesh() override
Function to extract a triangle mesh, using the marching cubes algorithm. (https://en....
ScalableTSDFVolume(double voxel_length, double sdf_trunc, TSDFVolumeColorType color_type, int volume_unit_resolution=16, int depth_sampling_stride=4)
void Reset() override
Function to reset the TSDFVolume.
std::shared_ptr< ccPointCloud > ExtractPointCloud() override
Function to extract a point cloud with normals.
std::unordered_map< Eigen::Vector3i, VolumeUnit, utility::hash_eigen< Eigen::Vector3i > > volume_units_
Base class of the Truncated Signed Distance Function (TSDF) volume.
Definition: TSDFVolume.h:43
Helper functions for the ml ops.
MiniVec< float, N > floor(const MiniVec< float, N > &a)
Definition: MiniVec.h:75
Generic file read and write utility for python interface.
Eigen::Matrix< Index, 3, 1 > Vector3i
Definition: knncpp.h:30
Definition: lsd.c:149