gtsam_points
Loading...
Searching...
No Matches
integrated_vgicp_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/types/gaussian_voxelmap_cpu.hpp>
12#include <gtsam_points/factors/integrated_matching_cost_factor.hpp>
13#include <gtsam_points/factors/integrated_gicp_factor.hpp>
14
15namespace gtsam_points {
16
17struct GaussianVoxel;
18
24template <typename SourceFrame = gtsam_points::PointCloud>
26public:
27 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
28 using shared_ptr = gtsam_points::shared_ptr<IntegratedVGICPFactor_>;
29
38 gtsam::Key target_key,
39 gtsam::Key source_key,
40 const GaussianVoxelMap::ConstPtr& target_voxels,
41 const std::shared_ptr<const SourceFrame>& source);
42
51 const gtsam::Pose3& fixed_target_pose,
52 gtsam::Key source_key,
53 const GaussianVoxelMap::ConstPtr& target_voxels,
54 const std::shared_ptr<const SourceFrame>& source);
55
56 virtual ~IntegratedVGICPFactor_() override;
57
59 virtual void print(const std::string& s = "", const gtsam::KeyFormatter& keyFormatter = gtsam::DefaultKeyFormatter) const override;
60
66 virtual size_t memory_usage() const override;
67
71 void set_num_threads(int n) { num_threads = n; }
72
74 void set_fused_cov_cache_mode(FusedCovCacheMode mode) { mahalanobis_cache_mode = mode; }
75
78 int num_inliers() const {
79 const int outliers = std::count(correspondences.begin(), correspondences.end(), nullptr);
80 return correspondences.size() - outliers;
81 }
82
85 double inlier_fraction() const { return num_inliers() / static_cast<double>(correspondences.size()); }
86
88 const std::shared_ptr<const GaussianVoxelMapCPU>& get_target() const { return target_voxels; }
89
90 gtsam::NonlinearFactor::shared_ptr clone() const override { return gtsam::NonlinearFactor::shared_ptr(new IntegratedVGICPFactor_(*this)); }
91
92private:
93 virtual void update_correspondences(const Eigen::Isometry3d& delta) const override;
94
95 virtual double evaluate(
96 const Eigen::Isometry3d& delta,
97 Eigen::Matrix<double, 6, 6>* H_target = nullptr,
98 Eigen::Matrix<double, 6, 6>* H_source = nullptr,
99 Eigen::Matrix<double, 6, 6>* H_target_source = nullptr,
100 Eigen::Matrix<double, 6, 1>* b_target = nullptr,
101 Eigen::Matrix<double, 6, 1>* b_source = nullptr) const override;
102
103private:
104 int num_threads;
105 FusedCovCacheMode mahalanobis_cache_mode;
106
107 // I'm unhappy to have mutable members...
108 mutable Eigen::Isometry3d linearization_point;
109 mutable std::vector<const GaussianVoxel*> correspondences;
110 mutable std::vector<Eigen::Matrix4d> mahalanobis_full;
111 mutable std::vector<Eigen::Matrix<float, 6, 1>> mahalanobis_compact;
112
113 std::shared_ptr<const GaussianVoxelMapCPU> target_voxels;
114 std::shared_ptr<const SourceFrame> source;
115};
116
117using IntegratedVGICPFactor = IntegratedVGICPFactor_<>;
118
119} // namespace gtsam_points
Abstraction of LSQ-based scan matching constraints between point clouds.
Definition integrated_matching_cost_factor.hpp:19
Voxelized GICP matching cost factor Koide et al., "Voxelized GICP for Fast and Accurate 3D Point Clou...
Definition integrated_vgicp_factor.hpp:25
virtual size_t memory_usage() const override
Calculate the memory usage of this factor.
Definition integrated_vgicp_factor_impl.hpp:93
void set_fused_cov_cache_mode(FusedCovCacheMode mode)
Set the cache mode for fused covariance matrices (i.e., mahalanobis).
Definition integrated_vgicp_factor.hpp:74
virtual void print(const std::string &s="", const gtsam::KeyFormatter &keyFormatter=gtsam::DefaultKeyFormatter) const override
Print the factor information.
Definition integrated_vgicp_factor_impl.hpp:80
void set_num_threads(int n)
Set the number of thread used for linearization of this factor.
Definition integrated_vgicp_factor.hpp:71
double inlier_fraction() const
Compute the fraction of inlier points that have correspondences fell in a voxel.
Definition integrated_vgicp_factor.hpp:85
const std::shared_ptr< const GaussianVoxelMapCPU > & get_target() const
Get the target voxelmap.
Definition integrated_vgicp_factor.hpp:88
int num_inliers() const
Get the number of inlier points.
Definition integrated_vgicp_factor.hpp:78