21 TSDFVoxel(
const Eigen::Vector3i &grid_index,
const Eigen::Vector3d &color)
22 :
Voxel(grid_index, color) {}
33namespace integration {
45 const Eigen::Vector3d &origin = Eigen::Vector3d::Zero());
49 void Reset()
override;
52 const Eigen::Matrix4d &extrinsic)
override;
74 const Eigen::Matrix4d &extrinsic,
77 inline int IndexOf(
int x,
int y,
int z)
const {
81 inline int IndexOf(
const Eigen::Vector3i &xyz)
const {
82 return IndexOf(xyz(0), xyz(1), xyz(2));
97 Eigen::Vector3d GetNormalAt(
const Eigen::Vector3d &p);
99 double GetTSDFAt(
const Eigen::Vector3d &p);
Contains the pinhole camera intrinsic parameters.
Definition PinholeCameraIntrinsic.h:32
The Image class stores image with customizable width, height, num of channels and bytes per channel.
Definition Image.h:34
RGBDImage is for a pair of registered color and depth images,.
Definition RGBDImage.h:27
TSDFVoxel(const Eigen::Vector3i &grid_index)
Definition UniformTSDFVolume.h:20
float weight_
Definition UniformTSDFVolume.h:27
TSDFVoxel()
Definition UniformTSDFVolume.h:19
~TSDFVoxel()
Definition UniformTSDFVolume.h:23
TSDFVoxel(const Eigen::Vector3i &grid_index, const Eigen::Vector3d &color)
Definition UniformTSDFVolume.h:21
float tsdf_
Definition UniformTSDFVolume.h:26
Voxel()
Default Constructor.
Definition VoxelGrid.h:38
TSDFVolume(double voxel_length, double sdf_trunc, TSDFVolumeColorType color_type)
Default Constructor.
Definition TSDFVolume.h:49
Definition BoundingVolume.cpp:19
TSDFVolumeColorType
Definition TSDFVolume.h:22
Definition ColorMapUtils.cpp:19
Definition PinholeCameraIntrinsic.cpp:16