gtsam_points
Loading...
Searching...
No Matches
Public Types | Public Member Functions | List of all members
gtsam_points::IntegratedVGICPFactor_< SourceFrame > Class Template Reference

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>

Inheritance diagram for gtsam_points::IntegratedVGICPFactor_< SourceFrame >:
Inheritance graph
[legend]
Collaboration diagram for gtsam_points::IntegratedVGICPFactor_< SourceFrame >:
Collaboration graph
[legend]

Public Types

using shared_ptr = gtsam_points::shared_ptr< IntegratedVGICPFactor_ >
 
- Public Types inherited from gtsam_points::IntegratedMatchingCostFactor
using shared_ptr = gtsam_points::shared_ptr< IntegratedMatchingCostFactor >
 

Public Member Functions

 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
 
- Public Member Functions inherited from gtsam_points::IntegratedMatchingCostFactor
 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
 

Additional Inherited Members

- Protected Attributes inherited from gtsam_points::IntegratedMatchingCostFactor
bool is_binary
 
Eigen::Isometry3d fixed_target_pose
 

Detailed Description

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.

Constructor & Destructor Documentation

◆ 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_keyTarget key
source_keySource key
target_voxelsTarget voxelmap
sourceSource 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_poseFixed target pose
source_keySource key
targetTarget voxelized point cloud frame
sourceSource point cloud frame

Member Function Documentation

◆ inlier_fraction()

template<typename SourceFrame = gtsam_points::PointCloud>
double gtsam_points::IntegratedVGICPFactor_< SourceFrame >::inlier_fraction ( ) const
inline

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 >
size_t gtsam_points::IntegratedVGICPFactor_< SourceFrame >::memory_usage ( ) const
overridevirtual

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>
int gtsam_points::IntegratedVGICPFactor_< SourceFrame >::num_inliers ( ) const
inline

Get the number of inlier points.

Note
This function must be called after the factor is linearized.

◆ print()

template<typename SourceFrame >
void gtsam_points::IntegratedVGICPFactor_< SourceFrame >::print ( const std::string &  s = "",
const gtsam::KeyFormatter &  keyFormatter = gtsam::DefaultKeyFormatter 
) const
overridevirtual

Print the factor information.

Reimplemented from gtsam_points::IntegratedMatchingCostFactor.

◆ set_num_threads()

template<typename SourceFrame = gtsam_points::PointCloud>
void gtsam_points::IntegratedVGICPFactor_< SourceFrame >::set_num_threads ( int  n)
inline

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: