wrap BatchFixedLagSmoother.getFactors()

release/4.3a0
Joel Truher 2024-11-29 19:25:16 -08:00 committed by Fan Jiang
parent 979fb93b98
commit 557d7d5827
1 changed files with 3 additions and 0 deletions

View File

@ -715,6 +715,9 @@ virtual class BatchFixedLagSmoother : gtsam::FixedLagSmoother {
void print(string s = "BatchFixedLagSmoother:\n") const; void print(string s = "BatchFixedLagSmoother:\n") const;
gtsam::LevenbergMarquardtParams params() const; gtsam::LevenbergMarquardtParams params() const;
gtsam::NonlinearFactorGraph getFactors() const;
template <VALUE = {gtsam::Point2, gtsam::Rot2, gtsam::Pose2, gtsam::Point3, template <VALUE = {gtsam::Point2, gtsam::Rot2, gtsam::Pose2, gtsam::Point3,
gtsam::Rot3, gtsam::Pose3, gtsam::Cal3_S2, gtsam::Cal3DS2, gtsam::Rot3, gtsam::Pose3, gtsam::Cal3_S2, gtsam::Cal3DS2,
gtsam::Vector, gtsam::Matrix}> gtsam::Vector, gtsam::Matrix}>