30 #include <unordered_map> 36 namespace integration {
38 class UniformTSDFVolume;
65 std::shared_ptr<UniformTSDFVolume>
volume_;
73 int volume_unit_resolution = 16,
74 int depth_sampling_stride = 4);
78 void Reset()
override;
81 const Eigen::Matrix4d &extrinsic)
override;
94 std::unordered_map<Eigen::Vector3i,
100 Eigen::Vector3i LocateVolumeUnit(
const Eigen::Vector3d &point) {
101 return Eigen::Vector3i((
int)std::floor(point(0) / volume_unit_length_),
102 (
int)std::floor(point(1) / volume_unit_length_),
103 (
int)std::floor(point(2) / volume_unit_length_));
106 std::shared_ptr<UniformTSDFVolume> OpenVolumeUnit(
107 const Eigen::Vector3i &index);
109 Eigen::Vector3d GetNormalAt(
const Eigen::Vector3d &p);
111 double GetTSDFAt(
const Eigen::Vector3d &p);
double volume_unit_length_
Definition: ScalableTSDFVolume.h:88
Definition: ScalableTSDFVolume.h:58
TSDFVolumeColorType
Definition: TSDFVolume.h:37
int volume_unit_resolution_
Definition: ScalableTSDFVolume.h:87
Definition: PinholeCameraIntrinsic.h:42
Definition: TSDFVolume.h:50
Eigen::Vector3i index_
Definition: ScalableTSDFVolume.h:66
int depth_sampling_stride_
Definition: ScalableTSDFVolume.h:89
VolumeUnit()
Definition: ScalableTSDFVolume.h:62
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:53
std::shared_ptr< geometry::TriangleMesh > ExtractTriangleMesh() override
Definition: ScalableTSDFVolume.cpp:220
Definition: RGBDImage.h:38
std::shared_ptr< geometry::PointCloud > ExtractVoxelPointCloud()
Definition: ScalableTSDFVolume.cpp:378
std::unordered_map< Eigen::Vector3i, VolumeUnit, utility::hash_eigen::hash< Eigen::Vector3i > > volume_units_
Definition: ScalableTSDFVolume.h:97
~ScalableTSDFVolume() override
Definition: ScalableTSDFVolume.cpp:49
Definition: PinholeCameraIntrinsic.cpp:34
Definition: ScalableTSDFVolume.h:60
ScalableTSDFVolume(double voxel_length, double sdf_trunc, TSDFVolumeColorType color_type, int volume_unit_resolution=16, int depth_sampling_stride=4)
Definition: ScalableTSDFVolume.cpp:39
std::shared_ptr< geometry::PointCloud > ExtractPointCloud() override
Function to extract a point cloud with normals.
Definition: ScalableTSDFVolume.cpp:109
void Reset() override
Function to reset the TSDFVolume.
Definition: ScalableTSDFVolume.cpp:51
std::shared_ptr< UniformTSDFVolume > volume_
Definition: ScalableTSDFVolume.h:65