19 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
20 using shared_ptr = gtsam_points::shared_ptr<IntegratedCT_GICPFactor_<TargetFrame, SourceFrame>>;
31 gtsam::Key source_t0_key,
32 gtsam::Key source_t1_key,
33 const std::shared_ptr<const TargetFrame>& target,
34 const std::shared_ptr<const SourceFrame>& source,
35 const std::shared_ptr<const NearestNeighborSearch>& target_tree);
45 gtsam::Key source_t0_key,
46 gtsam::Key source_t1_key,
47 const std::shared_ptr<const TargetFrame>& target,
48 const std::shared_ptr<const SourceFrame>& source);
53 virtual void print(
const std::string& s =
"",
const gtsam::KeyFormatter& keyFormatter = gtsam::DefaultKeyFormatter)
const override;
55 virtual size_t memory_usage()
const override;
57 virtual double error(
const gtsam::Values& values)
const override;
58 virtual gtsam::GaussianFactor::shared_ptr linearize(
const gtsam::Values& values)
const override;
61 virtual void update_correspondences()
const override;
63 mutable std::vector<Eigen::Matrix4d> mahalanobis;
virtual void print(const std::string &s="", const gtsam::KeyFormatter &keyFormatter=gtsam::DefaultKeyFormatter) const override
Print the factor information.
Definition integrated_ct_gicp_factor_impl.hpp:50