Generalized ICP matching cost factor Segal et al., "Generalized-ICP", RSS2005.
More...
|
| | IntegratedGICPFactor_ (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) |
| | Create a binary ICP factor between target and source poses.
|
| |
|
| IntegratedGICPFactor_ (gtsam::Key target_key, gtsam::Key source_key, const std::shared_ptr< const TargetFrame > &target, const std::shared_ptr< const SourceFrame > &source) |
| |
| | IntegratedGICPFactor_ (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) |
| | Create a unary GICP factor between a fixed target pose and an active source pose.
|
| |
|
| IntegratedGICPFactor_ (const gtsam::Pose3 &fixed_target_pose, gtsam::Key source_key, const std::shared_ptr< const TargetFrame > &target, const std::shared_ptr< const SourceFrame > &source) |
| |
| 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_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.
|
| |
|
void | set_fused_cov_cache_mode (FusedCovCacheMode mode) |
| | Set the cache mode for fused covariance matrices (i.e., mahalanobis).
|
| |
|
double | inlier_fraction () const |
| | Compute the fraction of inlier points that have correspondences with a distance smaller than the trimming threshold.
|
| |
|
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 |
| |
template<typename TargetFrame = gtsam_points::PointCloud, typename SourceFrame = gtsam_points::PointCloud>
class gtsam_points::IntegratedGICPFactor_< TargetFrame, SourceFrame >
Generalized ICP matching cost factor Segal et al., "Generalized-ICP", RSS2005.