13 #include <unordered_map>
19 namespace integration {
21 class UniformTSDFVolume;
48 std::shared_ptr<UniformTSDFVolume>
volume_;
56 int volume_unit_resolution = 16,
57 int depth_sampling_stride = 4);
61 void Reset()
override;
64 const Eigen::Matrix4d &extrinsic)
override;
90 std::shared_ptr<UniformTSDFVolume> OpenVolumeUnit(
93 Eigen::Vector3d GetNormalAt(
const Eigen::Vector3d &p);
95 double GetTSDFAt(
const Eigen::Vector3d &p);
std::shared_ptr< core::Tensor > image
Contains the pinhole camera intrinsic parameters.
RGBDImage is for a pair of registered color and depth images,.
int volume_unit_resolution_
double volume_unit_length_
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....
int depth_sampling_stride_
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.
~ScalableTSDFVolume() override
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.
Helper functions for the ml ops.
MiniVec< float, N > floor(const MiniVec< float, N > &a)
Generic file read and write utility for python interface.
Eigen::Matrix< Index, 3, 1 > Vector3i
std::shared_ptr< UniformTSDFVolume > volume_