![]() |
ACloudViewer
3.9.4
A Modern Library for 3D Data Processing
|
Classes | |
| class | ControlGrid |
| struct | SLACOptimizerParams |
| struct | SLACDebugOption |
Typedefs | |
| using | PoseGraph = cloudViewer::pipelines::registration::PoseGraph |
Functions | |
| static PointCloud | CreateTPCDFromFile (const std::string &fname, const core::Device &device=core::Device("CPU:0")) |
| static void | FillInRigidAlignmentTerm (Tensor &AtA, Tensor &Atb, Tensor &residual, PointCloud &tpcd_i, PointCloud &tpcd_j, const Tensor &Ti, const Tensor &Tj, const int i, const int j, const float threshold) |
| void | FillInRigidAlignmentTerm (Tensor &AtA, Tensor &Atb, Tensor &residual, const std::vector< std::string > &fnames, const PoseGraph &pose_graph, const SLACOptimizerParams ¶ms, const SLACDebugOption &debug_option) |
| static void | FillInSLACAlignmentTerm (Tensor &AtA, Tensor &Atb, Tensor &residual, ControlGrid &ctr_grid, const PointCloud &tpcd_param_i, const PointCloud &tpcd_param_j, const Tensor &Ti, const Tensor &Tj, const int i, const int j, const int n_fragments, const float threshold) |
| void | FillInSLACAlignmentTerm (Tensor &AtA, Tensor &Atb, Tensor &residual, ControlGrid &ctr_grid, const std::vector< std::string > &fnames, const PoseGraph &pose_graph, const SLACOptimizerParams ¶ms, const SLACDebugOption &debug_option) |
| void | FillInSLACRegularizerTerm (Tensor &AtA, Tensor &Atb, Tensor &residual, ControlGrid &ctr_grid, int n_frags, const SLACOptimizerParams ¶ms, const SLACDebugOption &debug_option) |
| static std::vector< std::string > | PreprocessPointClouds (const std::vector< std::string > &fnames, const SLACOptimizerParams ¶ms) |
| static core::Tensor | ConvertCorrespondencesTargetIndexedToCx2Form (const core::Tensor &target_correspondences) |
| static core::Tensor | GetCorrespondenceSetForPointCloudPair (int i, int j, PointCloud &tpcd_i, PointCloud &tpcd_j, const core::Tensor &T_i, const core::Tensor &T_j, const core::Tensor &T_ij, float distance_threshold, float fitness_threshold, bool debug) |
| void | SaveCorrespondencesForPointClouds (const std::vector< std::string > &fnames_processed, const PoseGraph &fragment_pose_graph, const SLACOptimizerParams ¶ms=SLACOptimizerParams(), const SLACDebugOption &debug_option=SLACDebugOption()) |
| Read pose graph containing loop closures and odometry to compute putative correspondences between pairs of pointclouds. More... | |
| static void | InitializeControlGrid (ControlGrid &ctr_grid, const std::vector< std::string > &fnames) |
| static void | UpdatePoses (PoseGraph &fragment_pose_graph, core::Tensor &delta) |
| static void | UpdateControlGrid (ControlGrid &ctr_grid, core::Tensor &delta) |
| std::pair< PoseGraph, ControlGrid > | RunSLACOptimizerForFragments (const std::vector< std::string > &fragment_filenames, const PoseGraph &fragment_pose_graph, const SLACOptimizerParams ¶ms=SLACOptimizerParams(), const SLACDebugOption &debug_option=SLACDebugOption()) |
| Simultaneous Localization and Calibration: Self-Calibration of Consumer Depth Cameras, CVPR 2014 Qian-Yi Zhou and Vladlen Koltun Estimate a shared control grid for all fragments for scene reconstruction, implemented in https://github.com/qianyizh/ElasticReconstruction. More... | |
| PoseGraph | RunRigidOptimizerForFragments (const std::vector< std::string > &fragment_filenames, const PoseGraph &fragment_pose_graph, const SLACOptimizerParams ¶ms=SLACOptimizerParams(), const SLACDebugOption &debug_option=SLACDebugOption()) |
| Extended ICP to simultaneously align multiple point clouds with dense pairwise point-to-plane distances. More... | |
| static Eigen::Vector3d | Jet (double v, double vmin, double vmax) |
| void | VisualizePointCloudCorrespondences (const t::geometry::PointCloud &tpcd_i, const t::geometry::PointCloud &tpcd_j, const core::Tensor correspondences, const core::Tensor &T_ij) |
| Visualize pairs with correspondences. More... | |
| void | VisualizePointCloudEmbedding (t::geometry::PointCloud &tpcd_param, ControlGrid &ctr_grid, bool show_lines) |
| void | VisualizePointCloudDeformation (const geometry::PointCloud &tpcd_param, ControlGrid &ctr_grid) |
| void | VisualizeGridDeformation (ControlGrid &cgrid) |
| void | pybind_slac (py::module &m) |
Variables | |
| static const Eigen::Vector3d | kSourceColor = Eigen::Vector3d(0, 1, 0) |
| static const Eigen::Vector3d | kTargetColor = Eigen::Vector3d(1, 0, 0) |
| static const Eigen::Vector3d | kCorresColor = Eigen::Vector3d(0, 0, 1) |
| static const std::unordered_map< std::string, std::string > | map_shared_argument_docstrings |
| using cloudViewer::t::pipelines::slac::PoseGraph = typedef cloudViewer::pipelines::registration::PoseGraph |
Definition at line 22 of file SLACOptimizer.h.
|
static |
Definition at line 86 of file SLACOptimizer.cpp.
References cloudViewer::core::Tensor::Arange(), cloudViewer::core::Tensor::GetDevice(), cloudViewer::core::Tensor::GetLength(), cloudViewer::core::Tensor::IndexGet(), cloudViewer::core::Int64, cloudViewer::core::Tensor::Ne(), cloudViewer::core::Tensor::Reshape(), cloudViewer::core::Tensor::SetItem(), and cloudViewer::core::TensorKey::Slice().
Referenced by GetCorrespondenceSetForPointCloudPair().
|
static |
Definition at line 29 of file FillInLinearSystemImpl.h.
References cloudViewer::io::CreatePointCloudFromFile(), cloudViewer::core::Float32, and cloudViewer::t::geometry::PointCloud::FromLegacy().
Referenced by FillInRigidAlignmentTerm(), FillInSLACAlignmentTerm(), InitializeControlGrid(), and SaveCorrespondencesForPointClouds().
| void cloudViewer::t::pipelines::slac::FillInRigidAlignmentTerm | ( | Tensor & | AtA, |
| Tensor & | Atb, | ||
| Tensor & | residual, | ||
| const std::vector< std::string > & | fnames, | ||
| const PoseGraph & | pose_graph, | ||
| const SLACOptimizerParams & | params, | ||
| const SLACDebugOption & | debug_option | ||
| ) |
Definition at line 56 of file FillInLinearSystemImpl.h.
References CreateTPCDFromFile(), cloudViewer::t::pipelines::slac::SLACDebugOption::debug_, cloudViewer::t::pipelines::slac::SLACDebugOption::debug_start_node_idx_, cloudViewer::pipelines::registration::PoseGraph::edges_, cloudViewer::core::eigen_converter::EigenMatrixToTensor(), cloudViewer::utility::filesystem::FileExists(), FillInRigidAlignmentTerm(), cloudViewer::core::Float32, format, cloudViewer::t::geometry::PointCloud::GetPointNormals(), cloudViewer::t::geometry::PointCloud::GetPointPositions(), cloudViewer::core::Tensor::IndexGet(), cloudViewer::core::Tensor::Inverse(), cloudViewer::core::Tensor::Load(), LogWarning, cloudViewer::core::Tensor::Matmul(), cloudViewer::pipelines::registration::PoseGraph::nodes_, params, cloudViewer::t::geometry::PointCloud::SetPointNormals(), cloudViewer::core::Tensor::To(), and VisualizePointCloudCorrespondences().
|
static |
Definition at line 37 of file FillInLinearSystemImpl.h.
References cloudViewer::t::pipelines::kernel::FillInRigidAlignmentTerm(), cloudViewer::t::geometry::PointCloud::GetPointNormals(), cloudViewer::t::geometry::PointCloud::GetPointPositions(), and cloudViewer::t::geometry::PointCloud::Transform().
Referenced by FillInRigidAlignmentTerm(), and RunRigidOptimizerForFragments().
|
static |
Definition at line 103 of file FillInLinearSystemImpl.h.
References cloudViewer::core::Tensor::Add_(), cloudViewer::core::Tensor::Contiguous(), cloudViewer::t::pipelines::slac::ControlGrid::Deform(), cloudViewer::t::pipelines::kernel::FillInSLACAlignmentTerm(), cloudViewer::t::geometry::PointCloud::GetPointAttr(), cloudViewer::t::geometry::PointCloud::GetPointNormals(), cloudViewer::t::geometry::PointCloud::GetPointPositions(), cloudViewer::t::pipelines::slac::ControlGrid::kGrid8NbIndices, cloudViewer::t::pipelines::slac::ControlGrid::kGrid8NbVertexInterpRatios, cloudViewer::core::Tensor::Matmul(), cloudViewer::core::Tensor::Slice(), and cloudViewer::core::Tensor::T().
Referenced by FillInSLACAlignmentTerm(), and RunSLACOptimizerForFragments().
| void cloudViewer::t::pipelines::slac::FillInSLACAlignmentTerm | ( | Tensor & | AtA, |
| Tensor & | Atb, | ||
| Tensor & | residual, | ||
| ControlGrid & | ctr_grid, | ||
| const std::vector< std::string > & | fnames, | ||
| const PoseGraph & | pose_graph, | ||
| const SLACOptimizerParams & | params, | ||
| const SLACDebugOption & | debug_option | ||
| ) |
Definition at line 153 of file FillInLinearSystemImpl.h.
References CreateTPCDFromFile(), cloudViewer::t::pipelines::slac::SLACDebugOption::debug_, cloudViewer::t::pipelines::slac::SLACDebugOption::debug_start_node_idx_, cloudViewer::pipelines::registration::PoseGraph::edges_, cloudViewer::core::eigen_converter::EigenMatrixToTensor(), cloudViewer::utility::filesystem::FileExists(), FillInSLACAlignmentTerm(), cloudViewer::core::Float32, format, cloudViewer::t::geometry::PointCloud::GetPointNormals(), cloudViewer::t::geometry::PointCloud::GetPointPositions(), cloudViewer::core::Tensor::IndexGet(), cloudViewer::core::Tensor::Inverse(), cloudViewer::core::Tensor::Load(), LogWarning, cloudViewer::core::Tensor::Matmul(), cloudViewer::pipelines::registration::PoseGraph::nodes_, cloudViewer::t::pipelines::slac::ControlGrid::Parameterize(), params, cloudViewer::t::geometry::PointCloud::SetPointNormals(), cloudViewer::core::Tensor::To(), VisualizePointCloudCorrespondences(), VisualizePointCloudDeformation(), and VisualizePointCloudEmbedding().
| void cloudViewer::t::pipelines::slac::FillInSLACRegularizerTerm | ( | Tensor & | AtA, |
| Tensor & | Atb, | ||
| Tensor & | residual, | ||
| ControlGrid & | ctr_grid, | ||
| int | n_frags, | ||
| const SLACOptimizerParams & | params, | ||
| const SLACDebugOption & | debug_option | ||
| ) |
Definition at line 216 of file FillInLinearSystemImpl.h.
References cloudViewer::t::pipelines::slac::SLACDebugOption::debug_, cloudViewer::t::pipelines::kernel::FillInSLACRegularizerTerm(), cloudViewer::t::pipelines::slac::ControlGrid::GetAnchorIdx(), cloudViewer::t::pipelines::slac::ControlGrid::GetCurrPositions(), cloudViewer::t::pipelines::slac::ControlGrid::GetInitPositions(), cloudViewer::t::pipelines::slac::ControlGrid::GetNeighborGridMap(), params, and VisualizeGridDeformation().
Referenced by RunSLACOptimizerForFragments().
|
static |
Definition at line 129 of file SLACOptimizer.cpp.
References AssertTensorDevice, AssertTensorDtype, AssertTensorShape, cloudViewer::t::geometry::PointCloud::Clone(), ConvertCorrespondencesTargetIndexedToCx2Form(), cloudViewer::t::geometry::PointCloud::GetDevice(), cloudViewer::core::Tensor::GetDtype(), cloudViewer::core::Tensor::GetLength(), cloudViewer::t::geometry::PointCloud::GetPointPositions(), cloudViewer::core::nns::NearestNeighborSearch::HybridIndex(), cloudViewer::core::nns::NearestNeighborSearch::HybridSearch(), cloudViewer::core::Tensor::IndexGet(), cloudViewer::core::Int64, cloudViewer::core::Tensor::Inverse(), cloudViewer::core::Tensor::Le(), LogDebug, LogError, cloudViewer::core::Tensor::Matmul(), cloudViewer::core::Tensor::Sum(), cloudViewer::core::Tensor::To(), cloudViewer::t::geometry::PointCloud::Transform(), and VisualizePointCloudCorrespondences().
Referenced by SaveCorrespondencesForPointClouds().
|
static |
Definition at line 254 of file SLACOptimizer.cpp.
References CreateTPCDFromFile(), cloudViewer::t::pipelines::slac::ControlGrid::GetDevice(), LogInfo, and cloudViewer::t::pipelines::slac::ControlGrid::Touch().
Referenced by RunSLACOptimizerForFragments().
|
static |
Definition at line 21 of file Visualization.cpp.
|
static |
Definition at line 26 of file SLACOptimizer.cpp.
References cloudViewer::t::io::CreatePointCloudFromFile(), cloudViewer::utility::filesystem::FileExists(), format, cloudViewer::utility::filesystem::GetFileNameWithoutDirectory(), LogError, LogInfo, cloudViewer::utility::filesystem::MakeDirectory(), params, and cloudViewer::t::io::WritePointCloud().
Referenced by RunRigidOptimizerForFragments(), and RunSLACOptimizerForFragments().
| void cloudViewer::t::pipelines::slac::pybind_slac | ( | py::module & | m | ) |
Definition at line 35 of file slac.cpp.
References cloudViewer::t::pipelines::slac::ControlGrid::Compactify(), cloudViewer::t::pipelines::slac::SLACDebugOption::debug_, cloudViewer::t::pipelines::slac::SLACDebugOption::debug_start_node_idx_, cloudViewer::t::pipelines::slac::SLACOptimizerParams::device_, cloudViewer::t::pipelines::slac::SLACOptimizerParams::distance_threshold_, cloudViewer::t::pipelines::slac::SLACOptimizerParams::fitness_threshold_, format, cloudViewer::docstring::FunctionDocInject(), cloudViewer::t::pipelines::slac::ControlGrid::GetAnchorIdx(), cloudViewer::t::pipelines::slac::ControlGrid::GetCurrPositions(), cloudViewer::t::pipelines::slac::ControlGrid::GetDevice(), cloudViewer::t::pipelines::slac::ControlGrid::GetInitPositions(), cloudViewer::t::pipelines::slac::ControlGrid::GetNeighborGridMap(), map_shared_argument_docstrings, cloudViewer::t::pipelines::slac::SLACOptimizerParams::max_iterations_, params, cloudViewer::t::pipelines::slac::SLACOptimizerParams::regularizer_weight_, RunRigidOptimizerForFragments(), RunSLACOptimizerForFragments(), SaveCorrespondencesForPointClouds(), cloudViewer::t::pipelines::slac::ControlGrid::Size(), cloudViewer::t::pipelines::slac::SLACOptimizerParams::slac_folder_, and cloudViewer::t::pipelines::slac::SLACOptimizerParams::voxel_size_.
Referenced by cloudViewer::t::pipelines::pybind_pipelines().
| PoseGraph cloudViewer::t::pipelines::slac::RunRigidOptimizerForFragments | ( | const std::vector< std::string > & | fragment_filenames, |
| const PoseGraph & | fragment_pose_graph, | ||
| const SLACOptimizerParams & | params = SLACOptimizerParams(), |
||
| const SLACDebugOption & | debug_option = SLACDebugOption() |
||
| ) |
Extended ICP to simultaneously align multiple point clouds with dense pairwise point-to-plane distances.
| fragment_fnames | Vector of filenames for pointcloud fragments. |
| fragment_pose_graph | Legacy PoseGraph for pointcloud fragments. |
| params | Parameters to tune in rigid optimization. |
| debug_option | Debug options. |
Definition at line 370 of file SLACOptimizer.cpp.
References cloudViewer::core::Tensor::Arange(), FillInRigidAlignmentTerm(), cloudViewer::core::Float32, cloudViewer::core::Tensor::IndexSet(), LogInfo, cloudViewer::utility::filesystem::MakeDirectory(), cloudViewer::core::Tensor::Ones(), params, PreprocessPointClouds(), SaveCorrespondencesForPointClouds(), cloudViewer::core::Tensor::Solve(), UpdatePoses(), and cloudViewer::core::Tensor::Zeros().
Referenced by pybind_slac().
| std::pair< PoseGraph, ControlGrid > cloudViewer::t::pipelines::slac::RunSLACOptimizerForFragments | ( | const std::vector< std::string > & | fragment_filenames, |
| const PoseGraph & | fragment_pose_graph, | ||
| const SLACOptimizerParams & | params = SLACOptimizerParams(), |
||
| const SLACDebugOption & | debug_option = SLACDebugOption() |
||
| ) |
Simultaneous Localization and Calibration: Self-Calibration of Consumer Depth Cameras, CVPR 2014 Qian-Yi Zhou and Vladlen Koltun Estimate a shared control grid for all fragments for scene reconstruction, implemented in https://github.com/qianyizh/ElasticReconstruction.
| fragment_filenames | Vector of filenames for pointcloud fragments. |
| fragment_pose_graph | Legacy PoseGraph for pointcloud fragments. |
| params | Parameters to tune in SLAC. |
| debug_option | Debug options. |
Definition at line 298 of file SLACOptimizer.cpp.
References cloudViewer::core::Tensor::Arange(), cloudViewer::t::pipelines::slac::ControlGrid::Compactify(), FillInSLACAlignmentTerm(), FillInSLACRegularizerTerm(), cloudViewer::core::Float32, cloudViewer::core::Tensor::GetLength(), cloudViewer::core::Tensor::IndexSet(), InitializeControlGrid(), cloudViewer::core::Int64, LogInfo, cloudViewer::core::make_pair(), cloudViewer::utility::filesystem::MakeDirectory(), cloudViewer::pipelines::registration::PoseGraph::nodes_, cloudViewer::core::Tensor::Ones(), params, PreprocessPointClouds(), SaveCorrespondencesForPointClouds(), cloudViewer::t::pipelines::slac::ControlGrid::Size(), cloudViewer::core::Tensor::Slice(), cloudViewer::core::Tensor::Solve(), UpdateControlGrid(), UpdatePoses(), and cloudViewer::core::Tensor::Zeros().
Referenced by pybind_slac().
| void cloudViewer::t::pipelines::slac::SaveCorrespondencesForPointClouds | ( | const std::vector< std::string > & | fnames_processed, |
| const PoseGraph & | fragment_pose_graph, | ||
| const SLACOptimizerParams & | params = SLACOptimizerParams(), |
||
| const SLACDebugOption & | debug_option = SLACDebugOption() |
||
| ) |
Read pose graph containing loop closures and odometry to compute putative correspondences between pairs of pointclouds.
| fnames_processed | Vector of filenames for processed pointcloud fragments. |
| fragment_pose_graph | Legacy PoseGraph for pointcloud fragments. |
| params | Parameters to tune in finding correspondences. |
| debug_option | SLACDebugOption containing the debug options. |
Definition at line 209 of file SLACOptimizer.cpp.
References CreateTPCDFromFile(), cloudViewer::t::pipelines::slac::SLACDebugOption::debug_, cloudViewer::pipelines::registration::PoseGraph::edges_, cloudViewer::core::eigen_converter::EigenMatrixToTensor(), cloudViewer::utility::filesystem::FileExists(), format, GetCorrespondenceSetForPointCloudPair(), cloudViewer::core::Tensor::GetLength(), LogInfo, cloudViewer::pipelines::registration::PoseGraph::nodes_, params, and cloudViewer::core::Tensor::Save().
Referenced by pybind_slac(), RunRigidOptimizerForFragments(), and RunSLACOptimizerForFragments().
|
static |
Definition at line 289 of file SLACOptimizer.cpp.
References cloudViewer::t::pipelines::slac::ControlGrid::GetCurrPositions(), cloudViewer::core::Tensor::GetLength(), LogError, cloudViewer::t::pipelines::slac::ControlGrid::Size(), cloudViewer::core::Tensor::Slice(), and cloudViewer::core::Tensor::View().
Referenced by RunSLACOptimizerForFragments().
|
static |
Definition at line 266 of file SLACOptimizer.cpp.
References cloudViewer::core::eigen_converter::EigenMatrixToTensor(), cloudViewer::core::Float32, cloudViewer::core::Tensor::GetLength(), LogError, cloudViewer::core::Tensor::Matmul(), cloudViewer::pipelines::registration::PoseGraph::nodes_, cloudViewer::t::pipelines::kernel::PoseToTransformation(), cloudViewer::core::eigen_converter::TensorToEigenMatrixXf(), cloudViewer::t::geometry::kernel::image::To(), cloudViewer::core::Tensor::To(), and cloudViewer::core::Tensor::View().
Referenced by RunRigidOptimizerForFragments(), and RunSLACOptimizerForFragments().
| void cloudViewer::t::pipelines::slac::VisualizeGridDeformation | ( | ControlGrid & | cgrid | ) |
Definition at line 187 of file Visualization.cpp.
References cloudViewer::geometry::LineSet::CreateFromPointCloudCorrespondences(), cloudViewer::visualization::DrawGeometries(), cloudViewer::t::pipelines::slac::ControlGrid::GetCurrPositions(), cloudViewer::t::pipelines::slac::ControlGrid::GetInitPositions(), cloudViewer::core::Tensor::GetLength(), cloudViewer::t::pipelines::slac::ControlGrid::GetNeighborGridMap(), cloudViewer::core::make_pair(), cloudViewer::t::pipelines::slac::ControlGrid::Size(), cloudViewer::core::Tensor::Slice(), cloudViewer::core::Tensor::To(), and cloudViewer::t::geometry::PointCloud::ToLegacy().
Referenced by FillInSLACRegularizerTerm().
| void cloudViewer::t::pipelines::slac::VisualizePointCloudCorrespondences | ( | const t::geometry::PointCloud & | tpcd_i, |
| const t::geometry::PointCloud & | tpcd_j, | ||
| const core::Tensor | correspondences, | ||
| const core::Tensor & | T_ij | ||
| ) |
Visualize pairs with correspondences.
| tpcd_i,source | point cloud. |
| tpcd_j,target | point cloud. |
| correspondences | Putative correspondence between tcpd_i and tpcd_j. |
| T_ij | Transformation from tpcd_i to tpcd_j. Use T_j.Inverse() @ T_i (node transformation in a pose graph) to check global correspondences , and T_ij (edge transformation) to check pairwise correspondences. |
Definition at line 46 of file Visualization.cpp.
References cloudViewer::t::geometry::PointCloud::Clone(), cloudViewer::geometry::LineSet::CreateFromPointCloudCorrespondences(), cloudViewer::visualization::DrawGeometries(), cloudViewer::core::Tensor::GetLength(), kCorresColor, kSourceColor, kTargetColor, cloudViewer::core::make_pair(), cloudViewer::core::Tensor::To(), cloudViewer::t::geometry::PointCloud::ToLegacy(), and cloudViewer::t::geometry::PointCloud::Transform().
Referenced by FillInRigidAlignmentTerm(), FillInSLACAlignmentTerm(), and GetCorrespondenceSetForPointCloudPair().
| void cloudViewer::t::pipelines::slac::VisualizePointCloudDeformation | ( | const geometry::PointCloud & | tpcd_param, |
| ControlGrid & | ctr_grid | ||
| ) |
Definition at line 139 of file Visualization.cpp.
References cloudViewer::geometry::LineSet::CreateFromPointCloudCorrespondences(), cloudViewer::t::pipelines::slac::ControlGrid::Deform(), cloudViewer::visualization::DrawGeometries(), cloudViewer::t::pipelines::slac::ControlGrid::GetCurrPositions(), cloudViewer::t::pipelines::slac::ControlGrid::GetInitPositions(), cloudViewer::t::geometry::PointCloud::GetPointAttr(), cloudViewer::core::Tensor::IndexGet(), cloudViewer::core::Int64, cloudViewer::core::make_pair(), and cloudViewer::t::geometry::PointCloud::ToLegacy().
Referenced by FillInSLACAlignmentTerm().
| void cloudViewer::t::pipelines::slac::VisualizePointCloudEmbedding | ( | t::geometry::PointCloud & | tpcd_param, |
| ControlGrid & | ctr_grid, | ||
| bool | show_lines | ||
| ) |
Definition at line 80 of file Visualization.cpp.
References cloudViewer::t::pipelines::slac::ControlGrid::GetCurrPositions(), cloudViewer::t::geometry::PointCloud::GetPointAttr(), cloudViewer::t::geometry::PointCloud::GetPointPositions(), cloudViewer::core::Tensor::IndexGet(), cloudViewer::core::Int64, cloudViewer::t::pipelines::slac::ControlGrid::kGrid8NbIndices, cloudViewer::t::pipelines::slac::ControlGrid::Size(), cloudViewer::core::Tensor::Slice(), and cloudViewer::t::geometry::PointCloud::ToLegacy().
Referenced by FillInSLACAlignmentTerm().
|
static |
Definition at line 19 of file Visualization.cpp.
Referenced by VisualizePointCloudCorrespondences().
|
static |
Definition at line 17 of file Visualization.cpp.
Referenced by VisualizePointCloudCorrespondences().
|
static |
Definition at line 18 of file Visualization.cpp.
Referenced by VisualizePointCloudCorrespondences().
|
static |
Definition at line 24 of file slac.cpp.
Referenced by pybind_slac().