Open3D (C++ API)
TSDFVolume.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 
33 
34 namespace open3d {
35 namespace integration {
36 
40 enum class TSDFVolumeColorType {
42  NoColor = 0,
44  RGB8 = 1,
46  Gray32 = 2,
47 };
48 
60 class TSDFVolume {
61 public:
67  TSDFVolume(double voxel_length,
68  double sdf_trunc,
69  TSDFVolumeColorType color_type)
70  : voxel_length_(voxel_length),
71  sdf_trunc_(sdf_trunc),
72  color_type_(color_type) {}
73  virtual ~TSDFVolume() {}
74 
75 public:
77  virtual void Reset() = 0;
78 
80  virtual void Integrate(const geometry::RGBDImage &image,
81  const camera::PinholeCameraIntrinsic &intrinsic,
82  const Eigen::Matrix4d &extrinsic) = 0;
83 
85  virtual std::shared_ptr<geometry::PointCloud> ExtractPointCloud() = 0;
86 
89  virtual std::shared_ptr<geometry::TriangleMesh> ExtractTriangleMesh() = 0;
90 
91 public:
93  double voxel_length_;
95  double sdf_trunc_;
98 };
99 
100 } // namespace integration
101 } // namespace open3d
double voxel_length_
Length of the voxel in meters.
Definition: TSDFVolume.h:93
TSDFVolumeColorType
Definition: TSDFVolume.h:40
double sdf_trunc_
Truncation value for signed distance function (SDF).
Definition: TSDFVolume.h:95
Contains the pinhole camera intrinsic parameters.
Definition: PinholeCameraIntrinsic.h:51
Base class of the Truncated Signed Distance Function (TSDF) volume.
Definition: TSDFVolume.h:60
TSDFVolumeColorType color_type_
Color type of the TSDF volume.
Definition: TSDFVolume.h:97
RGBDImage is for a pair of registered color and depth images,.
Definition: RGBDImage.h:46
Definition: Open3DViewer.h:29
TSDFVolume(double voxel_length, double sdf_trunc, TSDFVolumeColorType color_type)
Default Constructor.
Definition: TSDFVolume.h:67
virtual ~TSDFVolume()
Definition: TSDFVolume.h:73