Open3D (C++ API)  0.18.0
Public Member Functions | Static Public Attributes
open3d::t::pipelines::slac::ControlGrid Class Reference

#include <ControlGrid.h>

Public Member Functions

 ControlGrid ()=default
 Default constructor. More...
 
 ControlGrid (float grid_size, int64_t grid_count=1000, const core::Device &device=core::Device("CPU:0"))
 Constructor with initial grid size and grid count estimation. More...
 
 ControlGrid (float grid_size, const core::Tensor &keys, const core::Tensor &values, const core::Device &device=core::Device("CPU:0"))
 
void Touch (const geometry::PointCloud &pcd)
 Allocate control grids in the shared camera space. More...
 
void Compactify ()
 
std::tuple< core::Tensor, core::Tensor, core::TensorGetNeighborGridMap ()
 
geometry::PointCloud Parameterize (const geometry::PointCloud &pcd)
 
geometry::PointCloud Deform (const geometry::PointCloud &pcd)
 Non-rigidly deform a point cloud using the control grid. More...
 
geometry::Image Deform (const geometry::Image &depth, const core::Tensor &intrinsics, const core::Tensor &extrinsics, float depth_scale, float depth_max)
 
geometry::RGBDImage Deform (const geometry::RGBDImage &rgbd, const core::Tensor &intrinsics, const core::Tensor &extrinsics, float depth_scale, float depth_max)
 
core::Tensor GetInitPositions ()
 Get control grid original positions directly from tensor keys. More...
 
core::Tensor GetCurrPositions ()
 
std::shared_ptr< core::HashMapGetHashMap ()
 
int64_t Size ()
 
core::Device GetDevice ()
 
int64_t GetAnchorIdx ()
 

Static Public Attributes

static const std::string kGrid8NbIndices = "Grid8NbIndices"
 
static const std::string kGrid8NbVertexInterpRatios
 8 neighbor grid interpolation ratio for vertex per point. More...
 
static const std::string kGrid8NbNormalInterpRatios
 8 neighbor grid interpolation ratio for normal per point. More...
 

Detailed Description

ControlGrid is a spatially hashed voxel grid used for non-rigid point cloud registration and TSDF integration. Each grid stores a map from the initial grid location to the deformed location. You can imagine a control grid as a jelly that is warped upon perturbation with its overall shape preserved. Reference: https://github.com/qianyizh/ElasticReconstruction/blob/master/FragmentOptimizer/OptApp.cpp http://vladlen.info/papers/elastic-fragments.pdf

Constructor & Destructor Documentation

◆ ControlGrid() [1/3]

open3d::t::pipelines::slac::ControlGrid::ControlGrid ( )
default

Default constructor.

◆ ControlGrid() [2/3]

open3d::t::pipelines::slac::ControlGrid::ControlGrid ( float  grid_size,
int64_t  grid_count = 1000,
const core::Device device = core::Device("CPU:0") 
)

Constructor with initial grid size and grid count estimation.

◆ ControlGrid() [3/3]

open3d::t::pipelines::slac::ControlGrid::ControlGrid ( float  grid_size,
const core::Tensor keys,
const core::Tensor values,
const core::Device device = core::Device("CPU:0") 
)

Constructor with known keys (Int32 x 3 positions) and values (Float32 x 3 shifted positions).

Member Function Documentation

◆ Compactify()

void open3d::t::pipelines::slac::ControlGrid::Compactify ( )

Force rehashing, so that all entries are remapped to [0, size) and form a contiguous index map.

◆ Deform() [1/3]

geometry::Image open3d::t::pipelines::slac::ControlGrid::Deform ( const geometry::Image depth,
const core::Tensor intrinsics,
const core::Tensor extrinsics,
float  depth_scale,
float  depth_max 
)

Non-rigidly deform a depth image by

  • unprojecting the depth image to a point cloud;
  • deform the point cloud;
  • project the deformed point cloud back to the image.

◆ Deform() [2/3]

geometry::PointCloud open3d::t::pipelines::slac::ControlGrid::Deform ( const geometry::PointCloud pcd)

Non-rigidly deform a point cloud using the control grid.

◆ Deform() [3/3]

geometry::RGBDImage open3d::t::pipelines::slac::ControlGrid::Deform ( const geometry::RGBDImage rgbd,
const core::Tensor intrinsics,
const core::Tensor extrinsics,
float  depth_scale,
float  depth_max 
)

Non-rigidly deform an RGBD image by

  • unprojecting the depth image to a point cloud;
  • deform the point cloud;
  • project the deformed point cloud back to the image.

◆ GetAnchorIdx()

int64_t open3d::t::pipelines::slac::ControlGrid::GetAnchorIdx ( )
inline

◆ GetCurrPositions()

core::Tensor open3d::t::pipelines::slac::ControlGrid::GetCurrPositions ( )
inline

Get control grid shifted positions from tensor values (optimized in-place).

◆ GetDevice()

core::Device open3d::t::pipelines::slac::ControlGrid::GetDevice ( )
inline

◆ GetHashMap()

std::shared_ptr<core::HashMap> open3d::t::pipelines::slac::ControlGrid::GetHashMap ( )
inline

◆ GetInitPositions()

core::Tensor open3d::t::pipelines::slac::ControlGrid::GetInitPositions ( )
inline

Get control grid original positions directly from tensor keys.

◆ GetNeighborGridMap()

std::tuple< core::Tensor, core::Tensor, core::Tensor > open3d::t::pipelines::slac::ControlGrid::GetNeighborGridMap ( )

Get the neighbor indices per grid to construct the regularizer.

Returns
A 6-way neighbor grid map for all the active entries of shape (N, ).
  • buf_indices Active indices in the buffer of shape (N, )
  • buf_indices_nb Neighbor indices (including non-allocated entries) for the active entries of shape (N, 6).
  • masks_nb Corresponding neighbor masks of shape (N, 6).

◆ Parameterize()

geometry::PointCloud open3d::t::pipelines::slac::ControlGrid::Parameterize ( const geometry::PointCloud pcd)

Parameterize an input point cloud by embedding each point in the grid with 8 corners via indexing and interpolation.

Returns
A PointCloud with parameterization attributes:
  • neighbors: Index of 8 neighbor control grid points of shape (8, ) in Int64.
  • ratios: Interpolation ratios of 8 neighbor control grid points of shape (8, ) in Float32.

TODO(wei): allow entries with less than 8 neighbors, probably in a kernel. Now we simply discard them and only accepts points with all 8 neighbors in the control grid map.

◆ Size()

int64_t open3d::t::pipelines::slac::ControlGrid::Size ( )
inline

◆ Touch()

void open3d::t::pipelines::slac::ControlGrid::Touch ( const geometry::PointCloud pcd)

Allocate control grids in the shared camera space.

Field Documentation

◆ kGrid8NbIndices

const std::string open3d::t::pipelines::slac::ControlGrid::kGrid8NbIndices = "Grid8NbIndices"
static

Attributes used to extend the point cloud to support neighbor lookup. 8 neighbor grid index per point.

◆ kGrid8NbNormalInterpRatios

const std::string open3d::t::pipelines::slac::ControlGrid::kGrid8NbNormalInterpRatios
static
Initial value:
=
"Grid8NbNormalInterpRatios"

8 neighbor grid interpolation ratio for normal per point.

◆ kGrid8NbVertexInterpRatios

const std::string open3d::t::pipelines::slac::ControlGrid::kGrid8NbVertexInterpRatios
static
Initial value:
=
"Grid8NbVertexInterpRatios"

8 neighbor grid interpolation ratio for vertex per point.


The documentation for this class was generated from the following files: