33 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
34 using shared_ptr = gtsam_points::shared_ptr<IntegratedGICPFactor_>;
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);
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);
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);
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);
83 virtual void print(
const std::string& s =
"",
const gtsam::KeyFormatter& keyFormatter = gtsam::DefaultKeyFormatter)
const override;
104 correspondence_update_tolerance_rot = angle;
105 correspondence_update_tolerance_trans = trans;
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();
118 gtsam::NonlinearFactor::shared_ptr clone()
const override {
return gtsam::NonlinearFactor::shared_ptr(
new IntegratedGICPFactor_(*
this)); }
121 virtual void update_correspondences(
const Eigen::Isometry3d& delta)
const override;
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;
133 double max_correspondence_distance_sq;
134 FusedCovCacheMode mahalanobis_cache_mode;
136 std::shared_ptr<const NearestNeighborSearch> target_tree;
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;
147 std::shared_ptr<const TargetFrame> target;
148 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.
Definition integrated_gicp_factor_impl.hpp:107