Go to the documentation of this file.
59 Projector(
float fx,
float fy,
float cx,
float cy);
66 Reprojector(
float fx,
float fy,
float cx,
float cy);
94 void setLevelIntr(
int level_index,
float fx,
float fy,
float cx,
float cy);
154 struct float12 {
float x,
y,
z,
w,
normal_x,
normal_y,
normal_z,
n4,
c1,
c2,
c3,
c4; };
void renderTangentColors(const Normals &normals, Image &image)
void depthPyr(const Depth &source, Depth &pyramid, float sigma_depth)
void resizePointsNormals(const Points &points, const Normals &normals, Points &points_out, Normals &normals_out)
DeviceArray2D< Point > Points
TsdfVolume(elem_type *data, int3 dims, float3 voxel_size, float trunc_dist, int max_weight)
TsdfVolume host implementation.
__kf_device__ float2 operator()(const float3 &p) const
Projector.
void truncateDepth(Depth &depth, float max_dist)
DeviceArray2D< ushort > Depth
__kf_device__ int find_coresp(int x, int y, float3 &n, float3 &d, float3 &s) const
static void allocate_buffer(DeviceArray2D< float > &buffer, int partials_count=-1)
void operator()(const Depth &dprev, const Normals &nprev, DeviceArray2D< float > &buffer, float *data, cudaStream_t stream)
__kf_device__ elem_type * beg(int x, int y) const
DeviceArray2D< uchar4 > Image
void resizeDepthNormals(const Depth &depth, const Normals &normals, Depth &depth_out, Normals &normals_out)
__kf_device__ float unpack_tsdf(ushort2 value, int &weight)
__kf_device__ elem_type * multzstep(int mult, elem_type *const ptr) const
__kf_device__ elem_type * zstep(elem_type *const ptr) const
void computeNormalsAndMaskDepth(const Reprojector &reproj, Depth &depth, Normals &normals)
__kf_device__ float3 operator()(int x, int y, float z) const
Reprojector.
__kf_device__ ushort2 pack_tsdf(float tsdf, int weight)
packing/unpacking tsdf volume element
__kf_device__ void partial_reduce(const float row[7], PtrStep< float > &partial_buffer) const
void bilateralFilter(const Depth &src, Depth &dst, int kernel_size, float sigma_spatial, float sigma_depth)
__kf_device__ float3 reproj(float x, float y, float z) const
void 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)
DeviceArray2D< Normal > Normals
__kf_device__ elem_type * operator()(int x, int y, int z)
TsdfVolume.
size_t extractCloud(const TsdfVolume &volume, const tsdf_buffer &buffer, const Aff3f &aff, PtrSz< Point > output)
void extractNormals(const TsdfVolume &volume, const tsdf_buffer &buffer, const PtrSz< Point > &points, const Aff3f &aff, const Mat3f &Rinv, float gradient_delta_factor, float4 *output)
ComputeIcpHelper(float dist_thres, float angle_thres)
ComputeIcpHelper.
Structure to handle buffer addresses.
__kf_device__ float2 proj(const float3 &p) const
void clearTSDFSlice(const TsdfVolume &volume, const kfusion::tsdf_buffer *buffer, const Vec3i offset)
PtrStepSz< ushort > Dists
void compute_dists(const Depth &depth, Dists dists, float2 f, float2 c)
void computePointNormals(const Reprojector &reproj, const Depth &depth, Points &points, Normals &normals)
size_t 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 integrate(const Dists &depth, TsdfVolume &volume, tsdf_buffer &buffer, const Aff3f &aff, const Projector &proj)
TsdfVolume & operator=(const TsdfVolume &)
void mergePointNormal(const DeviceArray< Point > &cloud, const DeviceArray< float8 > &normals, const DeviceArray< float12 > &output)
void clear_volume(TsdfVolume volume)
void setLevelIntr(int level_index, float fx, float fy, float cx, float cy)
void renderImage(const Depth &depth, const Normals &normals, const Reprojector &reproj, const Vec3f &light_pose, Image &image)
lvr2
Author(s): Thomas Wiemann
, Sebastian Pütz , Alexander Mock , Lars Kiesow , Lukas Kalbertodt , Tristan Igelbrink , Johan M. von Behren , Dominik Feldschnieders , Alexander Löhr
autogenerated on Wed Mar 2 2022 00:37:23