#include <tsdf_volume.hpp>
|
| virtual void | applyAffine (const Affine3f &affine) |
| |
| virtual void | clear () |
| |
| void | clearSlice (const kfusion::tsdf_buffer *buffer, const Vec3i offset) const |
| |
| void | create (const Vec3i &dims) |
| |
| CudaData | data () |
| |
| const CudaData | data () const |
| |
| DeviceArray< Point > | fetchCloud (DeviceArray< Point > &cloud_buffer, const tsdf_buffer &buffer) const |
| |
| void | fetchNormals (const DeviceArray< Point > &cloud, const tsdf_buffer &buffer, DeviceArray< Normal > &normals) const |
| |
| DeviceArray< Point > | fetchSliceAsCloud (DeviceArray< Point > &cloud_buffer, const kfusion::tsdf_buffer *buffer, const Vec3i minBounds, const Vec3i maxBounds, const Vec3i globalShift) const |
| | Generates cloud using GPU in connected6 mode only. More...
|
| |
| ushort2 * | getCoord (int x, int y, int z, int dim_x, int dim_y) |
| |
| Vec3i | getDims () const |
| |
| float | getGradientDeltaFactor () const |
| |
| Vec3i | getGridOrigin () const |
| |
| int | getMaxWeight () const |
| |
| Affine3f | getPose () const |
| |
| float | getRaycastStepFactor () const |
| |
| Vec3f | getSize () const |
| |
| float | getTruncDist () const |
| |
| Vec3f | getVoxelSize () const |
| |
| virtual void | integrate (const Dists &dists, tsdf_buffer &buffer, const Affine3f &camera_pose, const Intr &intr) |
| |
| virtual void | raycast (const Affine3f &camera_pose, tsdf_buffer &buffer, const Intr &intr, Cloud &points, Normals &normals) |
| |
| virtual void | raycast (const Affine3f &camera_pose, tsdf_buffer &buffer, const Intr &intr, Depth &depth, Normals &normals) |
| |
| void | setGradientDeltaFactor (float factor) |
| |
| void | setGridOrigin (const Vec3i &origin) |
| |
| void | setMaxWeight (int weight) |
| |
| void | setPose (const Affine3f &pose) |
| |
| void | setRaycastStepFactor (float factor) |
| |
| void | setSize (const Vec3f &size) |
| |
| void | setTruncDist (float distance) |
| |
| void | swap (CudaData &data) |
| |
| | TsdfVolume (const cv::Vec3i &dims) |
| | TsdfVolume. More...
|
| |
| virtual | ~TsdfVolume () |
| |
Definition at line 11 of file tsdf_volume.hpp.
◆ TsdfVolume()
| kfusion::cuda::TsdfVolume::TsdfVolume |
( |
const cv::Vec3i & |
dims | ) |
|
◆ ~TsdfVolume()
| kfusion::cuda::TsdfVolume::~TsdfVolume |
( |
| ) |
|
|
virtual |
◆ applyAffine()
| void kfusion::cuda::TsdfVolume::applyAffine |
( |
const Affine3f & |
affine | ) |
|
|
virtual |
◆ clear()
| void kfusion::cuda::TsdfVolume::clear |
( |
| ) |
|
|
virtual |
◆ clearSlice()
◆ create()
| void kfusion::cuda::TsdfVolume::create |
( |
const Vec3i & |
dims | ) |
|
◆ data() [1/2]
| CudaData kfusion::cuda::TsdfVolume::data |
( |
| ) |
|
◆ data() [2/2]
| CudaData kfusion::cuda::TsdfVolume::data |
( |
| ) |
const |
◆ fetchCloud()
◆ fetchNormals()
◆ fetchSliceAsCloud()
Generates cloud using GPU in connected6 mode only.
- Parameters
-
| [out] | cloud_buffer_xyz | buffer to store point cloud |
| cloud_buffer_intensity | |
| [in] | buffer | Pointer to the buffer struct that contains information about memory addresses of the tsdf volume memory block, which are used for the cyclic buffer. |
| [in] | shiftX | Offset in indices. |
| [in] | shiftY | Offset in indices. |
| [in] | shiftZ | Offset in indices. |
- Returns
- DeviceArray with disabled reference counting that points to filled part of cloud_buffer.
Definition at line 184 of file tsdf_volume.cpp.
◆ getCoord()
| ushort2 * kfusion::cuda::TsdfVolume::getCoord |
( |
int |
x, |
|
|
int |
y, |
|
|
int |
z, |
|
|
int |
dim_x, |
|
|
int |
dim_y |
|
) |
| |
◆ getDims()
| Vec3i kfusion::cuda::TsdfVolume::getDims |
( |
| ) |
const |
◆ getGradientDeltaFactor()
| float kfusion::cuda::TsdfVolume::getGradientDeltaFactor |
( |
| ) |
const |
◆ getGridOrigin()
| Vec3i kfusion::cuda::TsdfVolume::getGridOrigin |
( |
| ) |
const |
◆ getMaxWeight()
| int kfusion::cuda::TsdfVolume::getMaxWeight |
( |
| ) |
const |
◆ getPose()
| Affine3f kfusion::cuda::TsdfVolume::getPose |
( |
| ) |
const |
◆ getRaycastStepFactor()
| float kfusion::cuda::TsdfVolume::getRaycastStepFactor |
( |
| ) |
const |
◆ getSize()
| Vec3f kfusion::cuda::TsdfVolume::getSize |
( |
| ) |
const |
◆ getTruncDist()
| float kfusion::cuda::TsdfVolume::getTruncDist |
( |
| ) |
const |
◆ getVoxelSize()
| Vec3f kfusion::cuda::TsdfVolume::getVoxelSize |
( |
| ) |
const |
◆ integrate()
◆ raycast() [1/2]
◆ raycast() [2/2]
◆ setGradientDeltaFactor()
| void kfusion::cuda::TsdfVolume::setGradientDeltaFactor |
( |
float |
factor | ) |
|
◆ setGridOrigin()
| void kfusion::cuda::TsdfVolume::setGridOrigin |
( |
const Vec3i & |
origin | ) |
|
◆ setMaxWeight()
| void kfusion::cuda::TsdfVolume::setMaxWeight |
( |
int |
weight | ) |
|
◆ setPose()
| void kfusion::cuda::TsdfVolume::setPose |
( |
const Affine3f & |
pose | ) |
|
◆ setRaycastStepFactor()
| void kfusion::cuda::TsdfVolume::setRaycastStepFactor |
( |
float |
factor | ) |
|
◆ setSize()
| void kfusion::cuda::TsdfVolume::setSize |
( |
const Vec3f & |
size | ) |
|
◆ setTruncDist()
| void kfusion::cuda::TsdfVolume::setTruncDist |
( |
float |
distance | ) |
|
◆ swap()
| void kfusion::cuda::TsdfVolume::swap |
( |
CudaData & |
data | ) |
|
◆ data_
| CudaData kfusion::cuda::TsdfVolume::data_ |
|
private |
◆ dims_
| Vec3i kfusion::cuda::TsdfVolume::dims_ |
|
private |
◆ gradient_delta_factor_
| float kfusion::cuda::TsdfVolume::gradient_delta_factor_ |
|
private |
◆ max_weight_
| int kfusion::cuda::TsdfVolume::max_weight_ |
|
private |
◆ pose_
| Affine3f kfusion::cuda::TsdfVolume::pose_ |
|
private |
◆ raycast_step_factor_
| float kfusion::cuda::TsdfVolume::raycast_step_factor_ |
|
private |
◆ size_
| Vec3f kfusion::cuda::TsdfVolume::size_ |
|
private |
◆ trunc_dist_
| float kfusion::cuda::TsdfVolume::trunc_dist_ |
|
private |
The documentation for this class was generated from the following files: