Voxelized GICP matching cost factor Koide et al., "Voxelized GICP for Fast and Accurate 3D Point Cloud Registration", ICRA2021 Koide et al., "Globally Consistent 3D LiDAR Mapping with GPU-accelerated GICP Matching Cost Factors", RA-L2021.
More...
#include <integrated_vgicp_factor.hpp>
|
| | IntegratedVGICPFactor_ (gtsam::Key target_key, gtsam::Key source_key, const GaussianVoxelMap::ConstPtr &target_voxels, const std::shared_ptr< const SourceFrame > &source) |
| | Create a binary VGICP factor between target and source poses.
|
| |
| | IntegratedVGICPFactor_ (const gtsam::Pose3 &fixed_target_pose, gtsam::Key source_key, const GaussianVoxelMap::ConstPtr &target_voxels, const std::shared_ptr< const SourceFrame > &source) |
| | Create a unary VGICP factor between a fixed target pose and an active source pose.
|
| |
| virtual void | print (const std::string &s="", const gtsam::KeyFormatter &keyFormatter=gtsam::DefaultKeyFormatter) const override |
| | Print the factor information.
|
| |
| virtual size_t | memory_usage () const override |
| | Calculate the memory usage of this factor.
|
| |
| void | set_num_threads (int n) |
| | Set the number of thread used for linearization of this factor.
|
| |
|
void | set_fused_cov_cache_mode (FusedCovCacheMode mode) |
| | Set the cache mode for fused covariance matrices (i.e., mahalanobis).
|
| |
| int | num_inliers () const |
| | Get the number of inlier points.
|
| |
| double | inlier_fraction () const |
| | Compute the fraction of inlier points that have correspondences fell in a voxel.
|
| |
|
const std::shared_ptr< const GaussianVoxelMapCPU > & | get_target () const |
| | Get the target voxelmap.
|
| |
|
gtsam::NonlinearFactor::shared_ptr | clone () const override |
| |
| | IntegratedMatchingCostFactor (gtsam::Key target_key, gtsam::Key source_key) |
| | Create a binary matching cost factor between target and source poses.
|
| |
| | IntegratedMatchingCostFactor (const gtsam::Pose3 &fixed_target_pose, gtsam::Key source_key) |
| | Create a unary matching cost factor between a fixed target pose and an active source pose.
|
| |
|
virtual size_t | dim () const override |
| |
| virtual double | error (const gtsam::Values &values) const override |
| |
|
virtual gtsam::GaussianFactor::shared_ptr | linearize (const gtsam::Values &values) const override |
| |
|
const Eigen::Isometry3d & | get_fixed_target_pose () const |
| |
|
Eigen::Isometry3d | calc_delta (const gtsam::Values &values) const |
| |
|
|
bool | is_binary |
| |
|
Eigen::Isometry3d | fixed_target_pose |
| |
template<typename SourceFrame = gtsam_points::PointCloud>
class gtsam_points::IntegratedVGICPFactor_< SourceFrame >
Voxelized GICP matching cost factor Koide et al., "Voxelized GICP for Fast and Accurate 3D Point Cloud Registration", ICRA2021 Koide et al., "Globally Consistent 3D LiDAR Mapping with GPU-accelerated GICP Matching Cost Factors", RA-L2021.
◆ IntegratedVGICPFactor_() [1/2]
template<typename SourceFrame >
| gtsam_points::IntegratedVGICPFactor_< SourceFrame >::IntegratedVGICPFactor_ |
( |
gtsam::Key |
target_key, |
|
|
gtsam::Key |
source_key, |
|
|
const GaussianVoxelMap::ConstPtr & |
target_voxels, |
|
|
const std::shared_ptr< const SourceFrame > & |
source |
|
) |
| |
Create a binary VGICP factor between target and source poses.
- Parameters
-
| target_key | Target key |
| source_key | Source key |
| target_voxels | Target voxelmap |
| source | Source point cloud frame |
◆ IntegratedVGICPFactor_() [2/2]
template<typename SourceFrame >
| gtsam_points::IntegratedVGICPFactor_< SourceFrame >::IntegratedVGICPFactor_ |
( |
const gtsam::Pose3 & |
fixed_target_pose, |
|
|
gtsam::Key |
source_key, |
|
|
const GaussianVoxelMap::ConstPtr & |
target_voxels, |
|
|
const std::shared_ptr< const SourceFrame > & |
source |
|
) |
| |
Create a unary VGICP factor between a fixed target pose and an active source pose.
- Parameters
-
| fixed_target_pose | Fixed target pose |
| source_key | Source key |
| target | Target voxelized point cloud frame |
| source | Source point cloud frame |
◆ inlier_fraction()
template<typename SourceFrame = gtsam_points::PointCloud>
Compute the fraction of inlier points that have correspondences fell in a voxel.
- Note
- This function must be called after the factor is linearized.
◆ memory_usage()
template<typename SourceFrame >
Calculate the memory usage of this factor.
- Note
- The result is approximate and does not account for objects not owned by this factor (e.g., point clouds)
- Returns
- Memory usage in bytes (Approximate size in bytes)
Reimplemented from gtsam_points::IntegratedMatchingCostFactor.
◆ num_inliers()
template<typename SourceFrame = gtsam_points::PointCloud>
Get the number of inlier points.
- Note
- This function must be called after the factor is linearized.
◆ print()
template<typename SourceFrame >
◆ set_num_threads()
template<typename SourceFrame = gtsam_points::PointCloud>
Set the number of thread used for linearization of this factor.
- Note
- If your GTSAM is built with TBB, linearization is already multi-threaded and setting n>1 can rather affect the processing speed.
The documentation for this class was generated from the following files: