gtsam_points
Loading...
Searching...
No Matches
integrated_gicp_factor.hpp
1// SPDX-License-Identifier: MIT
2// Copyright (c) 2021 Kenji Koide (k.koide@aist.go.jp)
3
4#pragma once
5
6#include <gtsam/nonlinear/NonlinearFactor.h>
7
8#include <memory>
9#include <gtsam_points/util/gtsam_migration.hpp>
10#include <gtsam_points/types/point_cloud.hpp>
11#include <gtsam_points/factors/integrated_matching_cost_factor.hpp>
12
13namespace gtsam_points {
14
15struct NearestNeighborSearch;
16
20enum class FusedCovCacheMode {
21 FULL, // Full matrix (4x4 double : 128 bit per point, fast)
22 COMPACT, // Compact matrix (upper-trianguler of 3x3 float, 24 bit per point, intermediate)
23 NONE // No cache (0 bit per point, slow)
24};
25
30template <typename TargetFrame = gtsam_points::PointCloud, typename SourceFrame = gtsam_points::PointCloud>
32public:
33 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
34 using shared_ptr = gtsam_points::shared_ptr<IntegratedGICPFactor_>;
35
45 gtsam::Key target_key,
46 gtsam::Key source_key,
47 const std::shared_ptr<const TargetFrame>& target,
48 const std::shared_ptr<const SourceFrame>& source,
49 const std::shared_ptr<const NearestNeighborSearch>& target_tree);
50
53 gtsam::Key target_key,
54 gtsam::Key source_key,
55 const std::shared_ptr<const TargetFrame>& target,
56 const std::shared_ptr<const SourceFrame>& source);
57
67 const gtsam::Pose3& fixed_target_pose,
68 gtsam::Key source_key,
69 const std::shared_ptr<const TargetFrame>& target,
70 const std::shared_ptr<const SourceFrame>& source,
71 const std::shared_ptr<const NearestNeighborSearch>& target_tree);
72
75 const gtsam::Pose3& fixed_target_pose,
76 gtsam::Key source_key,
77 const std::shared_ptr<const TargetFrame>& target,
78 const std::shared_ptr<const SourceFrame>& source);
79
80 virtual ~IntegratedGICPFactor_() override;
81
83 virtual void print(const std::string& s = "", const gtsam::KeyFormatter& keyFormatter = gtsam::DefaultKeyFormatter) const override;
84
90 virtual size_t memory_usage() const override;
91
95 void set_num_threads(int n) { num_threads = n; }
96
99 void set_max_correspondence_distance(double dist) { max_correspondence_distance_sq = dist * dist; }
100
103 void set_correspondence_update_tolerance(double angle, double trans) {
104 correspondence_update_tolerance_rot = angle;
105 correspondence_update_tolerance_trans = trans;
106 }
107
109 void set_fused_cov_cache_mode(FusedCovCacheMode mode) { mahalanobis_cache_mode = mode; }
110
112 double inlier_fraction() const {
113 const int outliers = std::count(correspondences.begin(), correspondences.end(), -1);
114 const int inliers = correspondences.size() - outliers;
115 return static_cast<double>(inliers) / correspondences.size();
116 }
117
118 gtsam::NonlinearFactor::shared_ptr clone() const override { return gtsam::NonlinearFactor::shared_ptr(new IntegratedGICPFactor_(*this)); }
119
120private:
121 virtual void update_correspondences(const Eigen::Isometry3d& delta) const override;
122
123 virtual double evaluate(
124 const Eigen::Isometry3d& delta,
125 Eigen::Matrix<double, 6, 6>* H_target = nullptr,
126 Eigen::Matrix<double, 6, 6>* H_source = nullptr,
127 Eigen::Matrix<double, 6, 6>* H_target_source = nullptr,
128 Eigen::Matrix<double, 6, 1>* b_target = nullptr,
129 Eigen::Matrix<double, 6, 1>* b_source = nullptr) const override;
130
131private:
132 int num_threads;
133 double max_correspondence_distance_sq;
134 FusedCovCacheMode mahalanobis_cache_mode;
135
136 std::shared_ptr<const NearestNeighborSearch> target_tree;
137
138 // I'm unhappy to have mutable members...
139 double correspondence_update_tolerance_rot;
140 double correspondence_update_tolerance_trans;
141 mutable Eigen::Isometry3d linearization_point;
142 mutable Eigen::Isometry3d last_correspondence_point;
143 mutable std::vector<long> correspondences;
144 mutable std::vector<Eigen::Matrix4d> mahalanobis_full;
145 mutable std::vector<Eigen::Matrix<float, 6, 1>> mahalanobis_compact;
146
147 std::shared_ptr<const TargetFrame> target;
148 std::shared_ptr<const SourceFrame> source;
149};
150
151using IntegratedGICPFactor = IntegratedGICPFactor_<>;
152
153} // namespace gtsam_points
Generalized ICP matching cost factor Segal et al., "Generalized-ICP", RSS2005.
Definition integrated_gicp_factor.hpp:31
void set_correspondence_update_tolerance(double angle, double trans)
Correspondences are updated only when the displacement from the last update point is larger than thes...
Definition integrated_gicp_factor.hpp:103
virtual size_t memory_usage() const override
Calculate the memory usage of this factor.
Definition integrated_gicp_factor_impl.hpp:126
double inlier_fraction() const
Compute the fraction of inlier points that have correspondences with a distance smaller than the trim...
Definition integrated_gicp_factor.hpp:112
void set_max_correspondence_distance(double dist)
Set the maximum distance between corresponding points. Correspondences with distances larger than thi...
Definition integrated_gicp_factor.hpp:99
void set_num_threads(int n)
Set the number of thread used for linearization of this factor.
Definition integrated_gicp_factor.hpp:95
virtual void print(const std::string &s="", const gtsam::KeyFormatter &keyFormatter=gtsam::DefaultKeyFormatter) const override
Print the factor information.
Definition integrated_gicp_factor_impl.hpp:107
void set_fused_cov_cache_mode(FusedCovCacheMode mode)
Set the cache mode for fused covariance matrices (i.e., mahalanobis).
Definition integrated_gicp_factor.hpp:109
Abstraction of LSQ-based scan matching constraints between point clouds.
Definition integrated_matching_cost_factor.hpp:19