gtsam_points
Loading...
Searching...
No Matches
Public Types | Public Member Functions | List of all members
gtsam_points::IntegratedVGICPFactorGPU Class Reference

GPU-accelerated 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_gpu.hpp>

Inheritance diagram for gtsam_points::IntegratedVGICPFactorGPU:
Inheritance graph
[legend]
Collaboration diagram for gtsam_points::IntegratedVGICPFactorGPU:
Collaboration graph
[legend]

Public Types

using shared_ptr = gtsam_points::shared_ptr< IntegratedVGICPFactorGPU >
 
- Public Types inherited from gtsam_points::NonlinearFactorGPU
using shared_ptr = gtsam_points::shared_ptr< NonlinearFactorGPU >
 

Public Member Functions

 IntegratedVGICPFactorGPU (gtsam::Key target_key, gtsam::Key source_key, const GaussianVoxelMap::ConstPtr &target, const PointCloud::ConstPtr &source, CUstream_st *stream=nullptr, std::shared_ptr< TempBufferManager > temp_buffer=nullptr)
 Create a binary VGICP_GPU factor between target and source poses.
 
 IntegratedVGICPFactorGPU (const gtsam::Pose3 &fixed_target_pose, gtsam::Key source_key, const GaussianVoxelMap::ConstPtr &target, const PointCloud::ConstPtr &source, CUstream_st *stream=nullptr, std::shared_ptr< TempBufferManager > temp_buffer=nullptr)
 Create a unary VGICP_GPU 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.
 
size_t memory_usage () const
 Calculate the CPU memory usage of this factor.
 
size_t memory_usage_gpu () const
 Calculate the GPU memory usage of this factor.
 
void set_enable_offloading (bool enable)
 Enable or disable GPU memory offloading.
 
void set_enable_surface_validation (bool enable)
 Enable or disable surface orientation validation for correspondence search.
 
void set_inlier_update_thresh (double trans, double angle)
 Set the threshold values to trigger inlier points update. Setting larger values reduces GPU sync but may affect the registration accuracy.
 
int num_inliers () const
 Get the number of inlier points.
 
double inlier_fraction () const
 Get the fraction of inlier points.
 
GaussianVoxelMapGPU::ConstPtr get_target () const
 Get the target voxelmap.
 
Eigen::Isometry3f get_fixed_target_pose () const
 Get the pose of the fixed target. This function is only valid for unary factors.
 
 IntegratedVGICPFactorGPU (const IntegratedVGICPFactorGPU &)=delete
 
IntegratedVGICPFactorGPUoperator= (const IntegratedVGICPFactorGPU &)=delete
 
virtual gtsam::NonlinearFactor::shared_ptr clone () const override
 
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
 
virtual size_t linearization_input_size () const override
 Size of data to be uploaded to the GPU before linearization.
 
virtual size_t linearization_output_size () const override
 Size of data to be downloaded from the GPU after linearization.
 
virtual size_t evaluation_input_size () const override
 Size of data to be uploaded to the GPU before cost evaluation.
 
virtual size_t evaluation_output_size () const override
 Size of data to be downloaded from the GPU after cost evaluation.
 
virtual void set_linearization_point (const gtsam::Values &values, void *lin_input_cpu) override
 Write linearization input data to the upload buffer.
 
virtual void issue_linearize (const void *lin_input_cpu, const void *lin_input_gpu, void *lin_output_gpu) override
 Issue linearization task.
 
virtual void store_linearized (const void *lin_output_cpu) override
 Read linearization output data from the download buffer.
 
virtual void set_evaluation_point (const gtsam::Values &values, void *eval_input_cpu) override
 Write cost evaluation input data to the upload buffer.
 
virtual void issue_compute_error (const void *lin_input_cpu, const void *eval_input_cpu, const void *lin_input_gpu, const void *eval_input_gpu, void *eval_output_gpu) override
 Issue cost evaluation task.
 
virtual void store_computed_error (const void *eval_output_cpu) override
 Read cost evaluation output data from the download buffer.
 
virtual void sync () override
 Perform CPU-GPU synchronization and wait for the task.
 
- Public Member Functions inherited from gtsam_points::NonlinearFactorGPU
template<typename CONTAINER >
 NonlinearFactorGPU (const CONTAINER &keys)
 

Detailed Description

GPU-accelerated 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

◆ IntegratedVGICPFactorGPU() [1/2]

gtsam_points::IntegratedVGICPFactorGPU::IntegratedVGICPFactorGPU ( gtsam::Key  target_key,
gtsam::Key  source_key,
const GaussianVoxelMap::ConstPtr &  target,
const PointCloud::ConstPtr &  source,
CUstream_st *  stream = nullptr,
std::shared_ptr< TempBufferManager temp_buffer = nullptr 
)

Create a binary VGICP_GPU factor between target and source poses.

Parameters
target_keyTarget key
source_keySource key
targetTarget voxelmap
sourceSource frame
streamCUDA stream
temp_bufferCUDA temporary buffer manager

◆ IntegratedVGICPFactorGPU() [2/2]

gtsam_points::IntegratedVGICPFactorGPU::IntegratedVGICPFactorGPU ( const gtsam::Pose3 &  fixed_target_pose,
gtsam::Key  source_key,
const GaussianVoxelMap::ConstPtr &  target,
const PointCloud::ConstPtr &  source,
CUstream_st *  stream = nullptr,
std::shared_ptr< TempBufferManager temp_buffer = nullptr 
)

Create a unary VGICP_GPU factor between a fixed target pose and an active source pose.

Parameters
targfixed_target_poseFixed target pose
source_keySource key
targetTarget voxelmap
sourceSource frame
streamCUDA stream
temp_bufferCUDA temporary buffer manager

Member Function Documentation

◆ evaluation_input_size()

virtual size_t gtsam_points::IntegratedVGICPFactorGPU::evaluation_input_size ( ) const
overridevirtual

Size of data to be uploaded to the GPU before cost evaluation.

Returns
size_t

Implements gtsam_points::NonlinearFactorGPU.

◆ evaluation_output_size()

virtual size_t gtsam_points::IntegratedVGICPFactorGPU::evaluation_output_size ( ) const
overridevirtual

Size of data to be downloaded from the GPU after cost evaluation.

Returns
size_t

Implements gtsam_points::NonlinearFactorGPU.

◆ inlier_fraction()

double gtsam_points::IntegratedVGICPFactorGPU::inlier_fraction ( ) const

Get the fraction of inlier points.

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

◆ issue_compute_error()

virtual void gtsam_points::IntegratedVGICPFactorGPU::issue_compute_error ( const void *  lin_input_cpu,
const void *  eval_input_cpu,
const void *  lin_input_gpu,
const void *  eval_input_gpu,
void *  eval_output_gpu 
)
overridevirtual

Issue cost evaluation task.

Parameters
lin_input_cpuLinearization input data on the CPU memory (size == linearization_input_size)
eval_input_cpuCost evaluation input data on the CPU memory (size == evaluation_input_size)
lin_input_gpuLinearization input data on the GPU memory (size == linearization_input_size)
eval_input_gpuCost evaluation input data on the GPU memory (size == evaluation_input_size)
eval_output_gpuOutput data destination on the GPU memory (size == evaluation_output_size)

Implements gtsam_points::NonlinearFactorGPU.

◆ issue_linearize()

virtual void gtsam_points::IntegratedVGICPFactorGPU::issue_linearize ( const void *  lin_input_cpu,
const void *  lin_input_gpu,
void *  lin_output_gpu 
)
overridevirtual

Issue linearization task.

Parameters
lin_input_cpuLinearization input data on the CPU memory (size == linearization_input_size)
lin_input_gpuLinearization input data on the GPU memory (size == linearization_input_size)
lin_output_gpuOutput data destination on the GPU memory (size == linearization_output_size)

Implements gtsam_points::NonlinearFactorGPU.

◆ linearization_input_size()

virtual size_t gtsam_points::IntegratedVGICPFactorGPU::linearization_input_size ( ) const
overridevirtual

Size of data to be uploaded to the GPU before linearization.

Returns
size_t

Implements gtsam_points::NonlinearFactorGPU.

◆ linearization_output_size()

virtual size_t gtsam_points::IntegratedVGICPFactorGPU::linearization_output_size ( ) const
overridevirtual

Size of data to be downloaded from the GPU after linearization.

Returns
size_t

Implements gtsam_points::NonlinearFactorGPU.

◆ memory_usage()

size_t gtsam_points::IntegratedVGICPFactorGPU::memory_usage ( ) const

Calculate the CPU 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
Approximate CPU memory usage in bytes

◆ memory_usage_gpu()

size_t gtsam_points::IntegratedVGICPFactorGPU::memory_usage_gpu ( ) const

Calculate the GPU 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
Approximate GPU memory usage in bytes

◆ num_inliers()

int gtsam_points::IntegratedVGICPFactorGPU::num_inliers ( ) const

Get the number of inlier points.

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

◆ set_enable_surface_validation()

void gtsam_points::IntegratedVGICPFactorGPU::set_enable_surface_validation ( bool  enable)

Enable or disable surface orientation validation for correspondence search.

Note
To enable surface orientation validation, source frame must have point normals

◆ set_evaluation_point()

virtual void gtsam_points::IntegratedVGICPFactorGPU::set_evaluation_point ( const gtsam::Values &  values,
void *  eval_input_cpu 
)
overridevirtual

Write cost evaluation input data to the upload buffer.

Parameters
valuesCurrent estimate
eval_input_cpuData upload buffer (size == evaluation_input_size)

Implements gtsam_points::NonlinearFactorGPU.

◆ set_linearization_point()

virtual void gtsam_points::IntegratedVGICPFactorGPU::set_linearization_point ( const gtsam::Values &  values,
void *  lin_input_cpu 
)
overridevirtual

Write linearization input data to the upload buffer.

Parameters
valuesCurrent estimate
lin_input_cpuData upload buffer (size == linearization_input_size)

Implements gtsam_points::NonlinearFactorGPU.

◆ store_computed_error()

virtual void gtsam_points::IntegratedVGICPFactorGPU::store_computed_error ( const void *  eval_output_cpu)
overridevirtual

Read cost evaluation output data from the download buffer.

Parameters
eval_output_cpuData down load buffer (size == evaluation_output_size)

Implements gtsam_points::NonlinearFactorGPU.

◆ store_linearized()

virtual void gtsam_points::IntegratedVGICPFactorGPU::store_linearized ( const void *  lin_output_cpu)
overridevirtual

Read linearization output data from the download buffer.

Parameters
lin_output_cpuData download buffer (size == linearization_output_size)

Implements gtsam_points::NonlinearFactorGPU.

◆ sync()

virtual void gtsam_points::IntegratedVGICPFactorGPU::sync ( )
overridevirtual

Perform CPU-GPU synchronization and wait for the task.

Implements gtsam_points::NonlinearFactorGPU.


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