Open3D (C++ API)
0.17.0
|
Namespaces | |
odometry | |
Functions | |
void | ComputeFPFHFeature (const core::Tensor &points, const core::Tensor &normals, const core::Tensor &indices, const core::Tensor &distance2, const core::Tensor &counts, core::Tensor &fpfhs) |
void | ComputeFPFHFeatureCPU (const core::Tensor &points, const core::Tensor &normals, const core::Tensor &indices, const core::Tensor &distance2, const core::Tensor &counts, core::Tensor &fpfhs) |
template<typename scalar_t > | |
OPEN3D_HOST_DEVICE void | ComputePairFeature (const scalar_t *p1, const scalar_t *n1, const scalar_t *p2, const scalar_t *n2, scalar_t *feature) |
template<typename scalar_t > | |
OPEN3D_HOST_DEVICE void | UpdateSPFHFeature (const scalar_t *feature, int64_t idx, scalar_t hist_incr, scalar_t *spfh) |
void | FillInRigidAlignmentTerm (core::Tensor &AtA, core::Tensor &Atb, core::Tensor &residual, const core::Tensor &Ti_ps, const core::Tensor &Tj_qs, const core::Tensor &Ri_normal_ps, int i, int j, float threshold) |
void | FillInSLACAlignmentTerm (core::Tensor &AtA, core::Tensor &Atb, core::Tensor &residual, const core::Tensor &Ti_ps, const core::Tensor &Tj_qs, const core::Tensor &normal_ps, const core::Tensor &Ri_normal_ps, const core::Tensor &RjT_Ri_normal_ps, const core::Tensor &cgrid_idx_ps, const core::Tensor &cgrid_idx_qs, const core::Tensor &cgrid_ratio_qs, const core::Tensor &cgrid_ratio_ps, int i, int j, int n, float threshold) |
void | FillInSLACRegularizerTerm (core::Tensor &AtA, core::Tensor &Atb, core::Tensor &residual, const core::Tensor &grid_idx, const core::Tensor &grid_nbs_idx, const core::Tensor &grid_nbs_mask, const core::Tensor &positions_init, const core::Tensor &positions_curr, float weight, int n, int anchor_idx) |
void | FillInRigidAlignmentTermCPU (core::Tensor &AtA, core::Tensor &Atb, core::Tensor &residual, const core::Tensor &Ti_qs, const core::Tensor &Tj_qs, const core::Tensor &Ri_normal_ps, int i, int j, float threshold) |
void | FillInSLACAlignmentTermCPU (core::Tensor &AtA, core::Tensor &Atb, core::Tensor &residual, const core::Tensor &Ti_qs, const core::Tensor &Tj_qs, const core::Tensor &normal_ps, const core::Tensor &Ri_normal_ps, const core::Tensor &RjT_Ri_normal_ps, const core::Tensor &cgrid_idx_ps, const core::Tensor &cgrid_idx_qs, const core::Tensor &cgrid_ratio_qs, const core::Tensor &cgrid_ratio_ps, int i, int j, int n, float threshold) |
void | FillInSLACRegularizerTermCPU (core::Tensor &AtA, core::Tensor &Atb, core::Tensor &residual, const core::Tensor &grid_idx, const core::Tensor &grid_nbs_idx, const core::Tensor &grid_nbs_mask, const core::Tensor &positions_init, const core::Tensor &positions_curr, float weight, int n, int anchor_idx) |
core::Tensor | ComputePosePointToPlane (const core::Tensor &source_positions, const core::Tensor &target_positions, const core::Tensor &target_normals, const core::Tensor &correspondence_indices, const registration::RobustKernel &kernel) |
Computes pose for point to plane registration method. More... | |
core::Tensor | ComputePoseColoredICP (const core::Tensor &source_positions, const core::Tensor &source_colors, const core::Tensor &target_positions, const core::Tensor &target_normals, const core::Tensor &target_colors, const core::Tensor &target_color_gradients, const core::Tensor &correspondence_indices, const registration::RobustKernel &kernel, const double &lambda_geometric) |
Computes pose for colored-icp registration method. More... | |
std::tuple< core::Tensor, core::Tensor > | ComputeRtPointToPoint (const core::Tensor &source_positions, const core::Tensor &target_positions, const core::Tensor &correspondence_indices) |
Computes (R) Rotation {3,3} and (t) translation {3,} for point to point registration method. More... | |
core::Tensor | ComputeInformationMatrix (const core::Tensor &target_positions, const core::Tensor &correspondence_indices) |
Computes Information Matrix of shape {6, 6}, of dtype Float64 on device CPU:0 , from the target point cloud and correspondence indices w.r.t. target point cloud. Only target positions and correspondence indices are required. More... | |
void | ComputePosePointToPlaneCPU (const core::Tensor &source_points, const core::Tensor &target_points, const core::Tensor &target_normals, const core::Tensor &correspondence_indices, core::Tensor &pose, float &residual, int &inlier_count, const core::Dtype &dtype, const core::Device &device, const registration::RobustKernel &kernel) |
void | ComputePoseColoredICPCPU (const core::Tensor &source_points, const core::Tensor &source_colors, const core::Tensor &target_points, const core::Tensor &target_normals, const core::Tensor &target_colors, const core::Tensor &target_color_gradients, const core::Tensor &correspondence_indices, core::Tensor &pose, float &residual, int &inlier_count, const core::Dtype &dtype, const core::Device &device, const registration::RobustKernel &kernel, const double &lambda_geometric) |
void | ComputeRtPointToPointCPU (const core::Tensor &source_points, const core::Tensor &target_points, const core::Tensor &corres, core::Tensor &R, core::Tensor &t, int &inlier_count, const core::Dtype &dtype, const core::Device &device) |
template<typename scalar_t > | |
void | ComputeInformationMatrixKernelCPU (const scalar_t *target_points_ptr, const int64_t *correspondence_indices, const int n, scalar_t *global_sum) |
void | ComputeInformationMatrixCPU (const core::Tensor &target_points, const core::Tensor &correspondence_indices, core::Tensor &information_matrix, const core::Dtype &dtype, const core::Device &device) |
template<typename scalar_t > | |
OPEN3D_HOST_DEVICE bool | GetJacobianPointToPlane (int64_t workload_idx, const scalar_t *source_points_ptr, const scalar_t *target_points_ptr, const scalar_t *target_normals_ptr, const int64_t *correspondence_indices, scalar_t *J_ij, scalar_t &r) |
template bool | GetJacobianPointToPlane (int64_t workload_idx, const float *source_points_ptr, const float *target_points_ptr, const float *target_normals_ptr, const int64_t *correspondence_indices, float *J_ij, float &r) |
template bool | GetJacobianPointToPlane (int64_t workload_idx, const double *source_points_ptr, const double *target_points_ptr, const double *target_normals_ptr, const int64_t *correspondence_indices, double *J_ij, double &r) |
template<typename scalar_t > | |
OPEN3D_HOST_DEVICE bool | GetJacobianColoredICP (const int64_t workload_idx, const scalar_t *source_points_ptr, const scalar_t *source_colors_ptr, const scalar_t *target_points_ptr, const scalar_t *target_normals_ptr, const scalar_t *target_colors_ptr, const scalar_t *target_color_gradients_ptr, const int64_t *correspondence_indices, const scalar_t &sqrt_lambda_geometric, const scalar_t &sqrt_lambda_photometric, scalar_t *J_G, scalar_t *J_I, scalar_t &r_G, scalar_t &r_I) |
template bool | GetJacobianColoredICP (const int64_t workload_idx, const float *source_points_ptr, const float *source_colors_ptr, const float *target_points_ptr, const float *target_normals_ptr, const float *target_colors_ptr, const float *target_color_gradients_ptr, const int64_t *correspondence_indices, const float &sqrt_lambda_geometric, const float &sqrt_lambda_photometric, float *J_G, float *J_I, float &r_G, float &r_I) |
template bool | GetJacobianColoredICP (const int64_t workload_idx, const double *source_points_ptr, const double *source_colors_ptr, const double *target_points_ptr, const double *target_normals_ptr, const double *target_colors_ptr, const double *target_color_gradients_ptr, const int64_t *correspondence_indices, const double &sqrt_lambda_geometric, const double &sqrt_lambda_photometric, double *J_G, double *J_I, double &r_G, double &r_I) |
template<typename scalar_t > | |
OPEN3D_HOST_DEVICE bool | GetInformationJacobians (int64_t workload_idx, const scalar_t *target_points_ptr, const int64_t *correspondence_indices, scalar_t *jacobian_x, scalar_t *jacobian_y, scalar_t *jacobian_z) |
template bool | GetInformationJacobians (int64_t workload_idx, const float *target_points_ptr, const int64_t *correspondence_indices, float *jacobian_x, float *jacobian_y, float *jacobian_z) |
template bool | GetInformationJacobians (int64_t workload_idx, const double *target_points_ptr, const int64_t *correspondence_indices, double *jacobian_x, double *jacobian_y, double *jacobian_z) |
core::Tensor | RtToTransformation (const core::Tensor &R, const core::Tensor &t) |
Convert rotation and translation to the transformation matrix. More... | |
core::Tensor | PoseToTransformation (const core::Tensor &pose) |
Convert pose to the transformation matrix. More... | |
void | DecodeAndSolve6x6 (const core::Tensor &A_reduction, core::Tensor &delta, float &inlier_residual, int &inlier_count) |
Decodes a 6x6 linear system from a compressed 29x1 tensor. More... | |
template<typename scalar_t > | |
OPEN3D_HOST_DEVICE void | PoseToTransformationImpl (scalar_t *transformation_ptr, const scalar_t *pose_ptr) |
Shared implementation for PoseToTransformation function. More... | |
void open3d::t::pipelines::kernel::ComputeFPFHFeature | ( | const core::Tensor & | points, |
const core::Tensor & | normals, | ||
const core::Tensor & | indices, | ||
const core::Tensor & | distance2, | ||
const core::Tensor & | counts, | ||
core::Tensor & | fpfhs | ||
) |
void open3d::t::pipelines::kernel::ComputeFPFHFeatureCPU | ( | const core::Tensor & | points, |
const core::Tensor & | normals, | ||
const core::Tensor & | indices, | ||
const core::Tensor & | distance2, | ||
const core::Tensor & | counts, | ||
core::Tensor & | fpfhs | ||
) |
core::Tensor open3d::t::pipelines::kernel::ComputeInformationMatrix | ( | const core::Tensor & | target_positions, |
const core::Tensor & | correspondence_indices | ||
) |
Computes Information Matrix
of shape {6, 6}, of dtype Float64
on device CPU:0
, from the target point cloud and correspondence indices w.r.t. target point cloud. Only target positions and correspondence indices are required.
target_positions | The target point positions. |
correspondence_indices | Tensor of type Int64 containing indices of corresponding target positions, where the value is the target index and the index of the value itself is the source index. It contains -1 as value at index with no correspondence. |
void open3d::t::pipelines::kernel::ComputeInformationMatrixCPU | ( | const core::Tensor & | target_points, |
const core::Tensor & | correspondence_indices, | ||
core::Tensor & | information_matrix, | ||
const core::Dtype & | dtype, | ||
const core::Device & | device | ||
) |
void open3d::t::pipelines::kernel::ComputeInformationMatrixKernelCPU | ( | const scalar_t * | target_points_ptr, |
const int64_t * | correspondence_indices, | ||
const int | n, | ||
scalar_t * | global_sum | ||
) |
OPEN3D_HOST_DEVICE void open3d::t::pipelines::kernel::ComputePairFeature | ( | const scalar_t * | p1, |
const scalar_t * | n1, | ||
const scalar_t * | p2, | ||
const scalar_t * | n2, | ||
scalar_t * | feature | ||
) |
core::Tensor open3d::t::pipelines::kernel::ComputePoseColoredICP | ( | const core::Tensor & | source_positions, |
const core::Tensor & | source_colors, | ||
const core::Tensor & | target_positions, | ||
const core::Tensor & | target_normals, | ||
const core::Tensor & | target_colors, | ||
const core::Tensor & | target_color_gradients, | ||
const core::Tensor & | correspondence_indices, | ||
const registration::RobustKernel & | kernel, | ||
const double & | lambda_geometric | ||
) |
Computes pose for colored-icp registration method.
source_positions | source point positions of Float32 or Float64 dtype. |
source_colors | source point colors of same dtype as source point positions. |
target_positions | target point positions of same dtype as source point positions. |
target_normals | target point normals of same dtype as source point positions. |
target_colors | target point colors of same dtype as source point positions. |
target_color_gradients | targets point color gradients of same dtype as source point positions. |
correspondence_indices | Tensor of type Int64 containing indices of corresponding target positions, where the value is the target index and the index of the value itself is the source index. It contains -1 as value at index with no correspondence. |
kernel | statistical robust kernel for outlier rejection. |
lambda_geometric | λ ∈ [0,1] in the overall energy λEG + (1−λ)EC . Refer the documentation of Colored-ICP for more information. |
void open3d::t::pipelines::kernel::ComputePoseColoredICPCPU | ( | const core::Tensor & | source_points, |
const core::Tensor & | source_colors, | ||
const core::Tensor & | target_points, | ||
const core::Tensor & | target_normals, | ||
const core::Tensor & | target_colors, | ||
const core::Tensor & | target_color_gradients, | ||
const core::Tensor & | correspondence_indices, | ||
core::Tensor & | pose, | ||
float & | residual, | ||
int & | inlier_count, | ||
const core::Dtype & | dtype, | ||
const core::Device & | device, | ||
const registration::RobustKernel & | kernel, | ||
const double & | lambda_geometric | ||
) |
core::Tensor open3d::t::pipelines::kernel::ComputePosePointToPlane | ( | const core::Tensor & | source_positions, |
const core::Tensor & | target_positions, | ||
const core::Tensor & | target_normals, | ||
const core::Tensor & | correspondence_indices, | ||
const registration::RobustKernel & | kernel | ||
) |
Computes pose for point to plane registration method.
source_positions | source point positions of Float32 or Float64 dtype. |
target_positions | target point positions of same dtype as source point positions. |
target_normals | target point normals of same dtype as source point positions. |
correspondence_indices | Tensor of type Int64 containing indices of corresponding target positions, where the value is the target index and the index of the value itself is the source index. It contains -1 as value at index with no correspondence. |
kernel | statistical robust kernel for outlier rejection. |
void open3d::t::pipelines::kernel::ComputePosePointToPlaneCPU | ( | const core::Tensor & | source_points, |
const core::Tensor & | target_points, | ||
const core::Tensor & | target_normals, | ||
const core::Tensor & | correspondence_indices, | ||
core::Tensor & | pose, | ||
float & | residual, | ||
int & | inlier_count, | ||
const core::Dtype & | dtype, | ||
const core::Device & | device, | ||
const registration::RobustKernel & | kernel | ||
) |
std::tuple< core::Tensor, core::Tensor > open3d::t::pipelines::kernel::ComputeRtPointToPoint | ( | const core::Tensor & | source_positions, |
const core::Tensor & | target_positions, | ||
const core::Tensor & | correspondence_indices | ||
) |
Computes (R) Rotation {3,3} and (t) translation {3,} for point to point registration method.
source_positions | source point positions of Float32 or Float64 dtype. |
target_positions | target point positions of same dtype as source point positions. |
correspondence_indices | Tensor of type Int64 containing indices of corresponding target positions, where the value is the target index and the index of the value itself is the source index. It contains -1 as value at index with no correspondence. |
void open3d::t::pipelines::kernel::ComputeRtPointToPointCPU | ( | const core::Tensor & | source_points, |
const core::Tensor & | target_points, | ||
const core::Tensor & | corres, | ||
core::Tensor & | R, | ||
core::Tensor & | t, | ||
int & | inlier_count, | ||
const core::Dtype & | dtype, | ||
const core::Device & | device | ||
) |
void open3d::t::pipelines::kernel::DecodeAndSolve6x6 | ( | const core::Tensor & | A_reduction, |
core::Tensor & | delta, | ||
float & | inlier_residual, | ||
int & | inlier_count | ||
) |
Decodes a 6x6 linear system from a compressed 29x1 tensor.
A_reduction | 1x29 tensor storing a linear system, (21 for \(J^T J\) matrix, 6 for \(J^T r\), 1 for residual, 1 for inlier count). |
delta | 6d tensor for a se3 tangent vector. |
inlier_residual | Float residual for the inliers. |
inlier_count | Int number of inliers. |
void open3d::t::pipelines::kernel::FillInRigidAlignmentTerm | ( | core::Tensor & | AtA, |
core::Tensor & | Atb, | ||
core::Tensor & | residual, | ||
const core::Tensor & | Ti_ps, | ||
const core::Tensor & | Tj_qs, | ||
const core::Tensor & | Ri_normal_ps, | ||
int | i, | ||
int | j, | ||
float | threshold | ||
) |
void open3d::t::pipelines::kernel::FillInRigidAlignmentTermCPU | ( | core::Tensor & | AtA, |
core::Tensor & | Atb, | ||
core::Tensor & | residual, | ||
const core::Tensor & | Ti_qs, | ||
const core::Tensor & | Tj_qs, | ||
const core::Tensor & | Ri_normal_ps, | ||
int | i, | ||
int | j, | ||
float | threshold | ||
) |
void open3d::t::pipelines::kernel::FillInSLACAlignmentTerm | ( | core::Tensor & | AtA, |
core::Tensor & | Atb, | ||
core::Tensor & | residual, | ||
const core::Tensor & | Ti_ps, | ||
const core::Tensor & | Tj_qs, | ||
const core::Tensor & | normal_ps, | ||
const core::Tensor & | Ri_normal_ps, | ||
const core::Tensor & | RjT_Ri_normal_ps, | ||
const core::Tensor & | cgrid_idx_ps, | ||
const core::Tensor & | cgrid_idx_qs, | ||
const core::Tensor & | cgrid_ratio_qs, | ||
const core::Tensor & | cgrid_ratio_ps, | ||
int | i, | ||
int | j, | ||
int | n, | ||
float | threshold | ||
) |
void open3d::t::pipelines::kernel::FillInSLACAlignmentTermCPU | ( | core::Tensor & | AtA, |
core::Tensor & | Atb, | ||
core::Tensor & | residual, | ||
const core::Tensor & | Ti_qs, | ||
const core::Tensor & | Tj_qs, | ||
const core::Tensor & | normal_ps, | ||
const core::Tensor & | Ri_normal_ps, | ||
const core::Tensor & | RjT_Ri_normal_ps, | ||
const core::Tensor & | cgrid_idx_ps, | ||
const core::Tensor & | cgrid_idx_qs, | ||
const core::Tensor & | cgrid_ratio_qs, | ||
const core::Tensor & | cgrid_ratio_ps, | ||
int | i, | ||
int | j, | ||
int | n, | ||
float | threshold | ||
) |
void open3d::t::pipelines::kernel::FillInSLACRegularizerTerm | ( | core::Tensor & | AtA, |
core::Tensor & | Atb, | ||
core::Tensor & | residual, | ||
const core::Tensor & | grid_idx, | ||
const core::Tensor & | grid_nbs_idx, | ||
const core::Tensor & | grid_nbs_mask, | ||
const core::Tensor & | positions_init, | ||
const core::Tensor & | positions_curr, | ||
float | weight, | ||
int | n, | ||
int | anchor_idx | ||
) |
void open3d::t::pipelines::kernel::FillInSLACRegularizerTermCPU | ( | core::Tensor & | AtA, |
core::Tensor & | Atb, | ||
core::Tensor & | residual, | ||
const core::Tensor & | grid_idx, | ||
const core::Tensor & | grid_nbs_idx, | ||
const core::Tensor & | grid_nbs_mask, | ||
const core::Tensor & | positions_init, | ||
const core::Tensor & | positions_curr, | ||
float | weight, | ||
int | n, | ||
int | anchor_idx | ||
) |
template bool open3d::t::pipelines::kernel::GetInformationJacobians | ( | int64_t | workload_idx, |
const double * | target_points_ptr, | ||
const int64_t * | correspondence_indices, | ||
double * | jacobian_x, | ||
double * | jacobian_y, | ||
double * | jacobian_z | ||
) |
template bool open3d::t::pipelines::kernel::GetInformationJacobians | ( | int64_t | workload_idx, |
const float * | target_points_ptr, | ||
const int64_t * | correspondence_indices, | ||
float * | jacobian_x, | ||
float * | jacobian_y, | ||
float * | jacobian_z | ||
) |
|
inline |
template bool open3d::t::pipelines::kernel::GetJacobianColoredICP | ( | const int64_t | workload_idx, |
const double * | source_points_ptr, | ||
const double * | source_colors_ptr, | ||
const double * | target_points_ptr, | ||
const double * | target_normals_ptr, | ||
const double * | target_colors_ptr, | ||
const double * | target_color_gradients_ptr, | ||
const int64_t * | correspondence_indices, | ||
const double & | sqrt_lambda_geometric, | ||
const double & | sqrt_lambda_photometric, | ||
double * | J_G, | ||
double * | J_I, | ||
double & | r_G, | ||
double & | r_I | ||
) |
template bool open3d::t::pipelines::kernel::GetJacobianColoredICP | ( | const int64_t | workload_idx, |
const float * | source_points_ptr, | ||
const float * | source_colors_ptr, | ||
const float * | target_points_ptr, | ||
const float * | target_normals_ptr, | ||
const float * | target_colors_ptr, | ||
const float * | target_color_gradients_ptr, | ||
const int64_t * | correspondence_indices, | ||
const float & | sqrt_lambda_geometric, | ||
const float & | sqrt_lambda_photometric, | ||
float * | J_G, | ||
float * | J_I, | ||
float & | r_G, | ||
float & | r_I | ||
) |
|
inline |
template bool open3d::t::pipelines::kernel::GetJacobianPointToPlane | ( | int64_t | workload_idx, |
const double * | source_points_ptr, | ||
const double * | target_points_ptr, | ||
const double * | target_normals_ptr, | ||
const int64_t * | correspondence_indices, | ||
double * | J_ij, | ||
double & | r | ||
) |
template bool open3d::t::pipelines::kernel::GetJacobianPointToPlane | ( | int64_t | workload_idx, |
const float * | source_points_ptr, | ||
const float * | target_points_ptr, | ||
const float * | target_normals_ptr, | ||
const int64_t * | correspondence_indices, | ||
float * | J_ij, | ||
float & | r | ||
) |
|
inline |
core::Tensor open3d::t::pipelines::kernel::PoseToTransformation | ( | const core::Tensor & | pose | ) |
Convert pose to the transformation matrix.
pose | Pose [alpha beta gamma, tx, ty, tz], a shape {6} tensor of dtype Float32, where alpha, beta, gamma are the Euler angles in the ZYX order. |
|
inline |
Shared implementation for PoseToTransformation function.
core::Tensor open3d::t::pipelines::kernel::RtToTransformation | ( | const core::Tensor & | R, |
const core::Tensor & | t | ||
) |
Convert rotation and translation to the transformation matrix.
R | Rotation, a tensor of shape {3, 3}. |
t | Translation, a tensor of shape {3,}. |
OPEN3D_HOST_DEVICE void open3d::t::pipelines::kernel::UpdateSPFHFeature | ( | const scalar_t * | feature, |
int64_t | idx, | ||
scalar_t | hist_incr, | ||
scalar_t * | spfh | ||
) |