27 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
28 using shared_ptr = gtsam_points::shared_ptr<IntegratedVGICPFactor_>;
38 gtsam::Key target_key,
39 gtsam::Key source_key,
40 const GaussianVoxelMap::ConstPtr& target_voxels,
41 const std::shared_ptr<const SourceFrame>& source);
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);
59 virtual void print(
const std::string& s =
"",
const gtsam::KeyFormatter& keyFormatter = gtsam::DefaultKeyFormatter)
const override;
79 const int outliers = std::count(correspondences.begin(), correspondences.end(),
nullptr);
80 return correspondences.size() - outliers;
88 const std::shared_ptr<const GaussianVoxelMapCPU>&
get_target()
const {
return target_voxels; }
90 gtsam::NonlinearFactor::shared_ptr clone()
const override {
return gtsam::NonlinearFactor::shared_ptr(
new IntegratedVGICPFactor_(*
this)); }
93 virtual void update_correspondences(
const Eigen::Isometry3d& delta)
const override;
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;
105 FusedCovCacheMode mahalanobis_cache_mode;
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;
113 std::shared_ptr<const GaussianVoxelMapCPU> target_voxels;
114 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_vgicp_factor_impl.hpp:80