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

Naive point-to-point ICP matching cost factor Zhang, "Iterative Point Matching for Registration of Free-Form Curve", IJCV1994. More...

#include <integrated_icp_factor.hpp>

Inheritance diagram for gtsam_points::IntegratedICPFactor_< TargetFrame, SourceFrame >:
Inheritance graph
[legend]
Collaboration diagram for gtsam_points::IntegratedICPFactor_< TargetFrame, SourceFrame >:
Collaboration graph
[legend]

Public Types

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

Public Member Functions

 IntegratedICPFactor_ (gtsam::Key target_key, gtsam::Key source_key, const std::shared_ptr< const TargetFrame > &target, const std::shared_ptr< const SourceFrame > &source, const std::shared_ptr< const NearestNeighborSearch > &target_tree, bool use_point_to_plane=false)
 Create a binary ICP factor between two poses.
 
 IntegratedICPFactor_ (gtsam::Key target_key, gtsam::Key source_key, const std::shared_ptr< const TargetFrame > &target, const std::shared_ptr< const SourceFrame > &source, bool use_point_to_plane=false)
 Create a binary ICP factor between two poses.
 
 IntegratedICPFactor_ (const gtsam::Pose3 &fixed_target_pose, gtsam::Key source_key, const std::shared_ptr< const TargetFrame > &target, const std::shared_ptr< const SourceFrame > &source, const std::shared_ptr< const NearestNeighborSearch > &target_tree, bool use_point_to_plane=false)
 Create a unary ICP factor between a fixed target pose and an active source pose.
 
 IntegratedICPFactor_ (const gtsam::Pose3 &fixed_target_pose, gtsam::Key source_key, const std::shared_ptr< const TargetFrame > &target, const std::shared_ptr< const SourceFrame > &source, bool use_point_to_plane=false)
 Create a unary ICP 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_max_correspondence_distance (double dist)
 Set the maximum distance between corresponding points. Correspondences with distances larger than this will be rejected (i.e., correspondence trimming).
 
void set_point_to_plane_distance (bool use)
 Enable or disable point-to-plane distance computation.
 
void set_correspondence_update_tolerance (double angle, double trans)
 Correspondences are updated only when the displacement from the last update point is larger than these threshold values.
 
- 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 TargetFrame = gtsam_points::PointCloud, typename SourceFrame = gtsam_points::PointCloud>
class gtsam_points::IntegratedICPFactor_< TargetFrame, SourceFrame >

Naive point-to-point ICP matching cost factor Zhang, "Iterative Point Matching for Registration of Free-Form Curve", IJCV1994.

Constructor & Destructor Documentation

◆ IntegratedICPFactor_() [1/2]

template<typename TargetFrame , typename SourceFrame >
gtsam_points::IntegratedICPFactor_< TargetFrame, SourceFrame >::IntegratedICPFactor_ ( gtsam::Key  target_key,
gtsam::Key  source_key,
const std::shared_ptr< const TargetFrame > &  target,
const std::shared_ptr< const SourceFrame > &  source,
const std::shared_ptr< const NearestNeighborSearch > &  target_tree,
bool  use_point_to_plane = false 
)

Create a binary ICP factor between two poses.

Parameters
target_keyTarget key
source_keySource key
targetTarget point cloud frame
sourceSource point cloud frame
target_treeTarget nearest neighbor search
use_point_to_planeIf true, use point-to-plane distance instead of point-to-point distance

◆ IntegratedICPFactor_() [2/2]

template<typename TargetFrame , typename SourceFrame >
gtsam_points::IntegratedICPFactor_< TargetFrame, SourceFrame >::IntegratedICPFactor_ ( const gtsam::Pose3 &  fixed_target_pose,
gtsam::Key  source_key,
const std::shared_ptr< const TargetFrame > &  target,
const std::shared_ptr< const SourceFrame > &  source,
const std::shared_ptr< const NearestNeighborSearch > &  target_tree,
bool  use_point_to_plane = false 
)

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

Parameters
fixed_target_poseFixed target pose
source_keySource key
targetTarget point cloud frame
sourceSource point cloud frame
target_treeTarget nearest neighbor search
use_point_to_planeIf true, use point-to-plane distance instead of point-to-point distance

Member Function Documentation

◆ memory_usage()

template<typename TargetFrame , typename SourceFrame >
size_t gtsam_points::IntegratedICPFactor_< TargetFrame, 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.

◆ print()

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

Print the factor information.

Reimplemented from gtsam_points::IntegratedMatchingCostFactor.

◆ set_correspondence_update_tolerance()

template<typename TargetFrame = gtsam_points::PointCloud, typename SourceFrame = gtsam_points::PointCloud>
void gtsam_points::IntegratedICPFactor_< TargetFrame, SourceFrame >::set_correspondence_update_tolerance ( double  angle,
double  trans 
)
inline

Correspondences are updated only when the displacement from the last update point is larger than these threshold values.

Note
Default values are angle=trans=0 and correspondences are updated every linearization call.

◆ set_num_threads()

template<typename TargetFrame = gtsam_points::PointCloud, typename SourceFrame = gtsam_points::PointCloud>
void gtsam_points::IntegratedICPFactor_< TargetFrame, 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: