|
void | kfusion::device::bilateralFilter (const Depth &src, Depth &dst, int kernel_size, float sigma_spatial, float sigma_depth) |
|
void | kfusion::device::clear_volume (TsdfVolume volume) |
|
void | kfusion::device::clearTSDFSlice (const TsdfVolume &volume, const kfusion::tsdf_buffer *buffer, const Vec3i offset) |
|
void | kfusion::device::compute_dists (const Depth &depth, Dists dists, float2 f, float2 c) |
|
void | kfusion::device::computeNormalsAndMaskDepth (const Reprojector &reproj, Depth &depth, Normals &normals) |
|
void | kfusion::device::computePointNormals (const Reprojector &reproj, const Depth &depth, Points &points, Normals &normals) |
|
void | kfusion::device::depthPyr (const Depth &source, Depth &pyramid, float sigma_depth) |
|
size_t | kfusion::device::extractCloud (const TsdfVolume &volume, const tsdf_buffer &buffer, const Aff3f &aff, PtrSz< Point > output) |
|
void | kfusion::device::extractNormals (const TsdfVolume &volume, const tsdf_buffer &buffer, const PtrSz< Point > &points, const Aff3f &aff, const Mat3f &Rinv, float gradient_delta_factor, float4 *output) |
|
size_t | kfusion::device::extractSliceAsCloud (const TsdfVolume &volume, const kfusion::tsdf_buffer *buffer, const Vec3i minBounds, const Vec3i maxBounds, const Vec3i globalShift, const Aff3f &aff, PtrSz< Point > output) |
|
void | kfusion::device::integrate (const Dists &depth, TsdfVolume &volume, tsdf_buffer &buffer, const Aff3f &aff, const Projector &proj) |
|
void | kfusion::device::mergePointNormal (const DeviceArray< Point > &cloud, const DeviceArray< float8 > &normals, const DeviceArray< float12 > &output) |
|
__kf_device__ ushort2 | kfusion::device::pack_tsdf (float tsdf, int weight) |
| packing/unpacking tsdf volume element More...
|
|
void | kfusion::device::raycast (const TsdfVolume &volume, tsdf_buffer &buffer, const Aff3f &aff, const Mat3f &Rinv, const Reprojector &reproj, Depth &depth, Normals &normals, float step_factor, float delta_factor) |
|
void | kfusion::device::raycast (const TsdfVolume &volume, tsdf_buffer &buffer, const Aff3f &aff, const Mat3f &Rinv, const Reprojector &reproj, Points &points, Normals &normals, float step_factor, float delta_factor) |
|
void | kfusion::device::renderImage (const Depth &depth, const Normals &normals, const Reprojector &reproj, const Vec3f &light_pose, Image &image) |
|
void | kfusion::device::renderImage (const Points &points, const Normals &normals, const Reprojector &reproj, const Vec3f &light_pose, Image &image) |
|
void | kfusion::device::renderTangentColors (const Normals &normals, Image &image) |
|
void | kfusion::device::resizeDepthNormals (const Depth &depth, const Normals &normals, Depth &depth_out, Normals &normals_out) |
|
void | kfusion::device::resizePointsNormals (const Points &points, const Normals &normals, Points &points_out, Normals &normals_out) |
|
void | kfusion::device::truncateDepth (Depth &depth, float max_dist) |
|
__kf_device__ float | kfusion::device::unpack_tsdf (ushort2 value) |
|
__kf_device__ float | kfusion::device::unpack_tsdf (ushort2 value, int &weight) |
|