expose iSAM object for iFLS, fix __repr__ of iFLS, bFLS
parent
40d3badf1f
commit
75263296b3
|
@ -582,6 +582,8 @@ virtual class BatchFixedLagSmoother : gtsam::FixedLagSmoother {
|
||||||
BatchFixedLagSmoother(double smootherLag);
|
BatchFixedLagSmoother(double smootherLag);
|
||||||
BatchFixedLagSmoother(double smootherLag, const gtsam::LevenbergMarquardtParams& params);
|
BatchFixedLagSmoother(double smootherLag, const gtsam::LevenbergMarquardtParams& params);
|
||||||
|
|
||||||
|
void print(string s = "BatchFixedLagSmoother:\n") const;
|
||||||
|
|
||||||
gtsam::LevenbergMarquardtParams params() const;
|
gtsam::LevenbergMarquardtParams params() 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,
|
||||||
|
@ -595,9 +597,12 @@ virtual class IncrementalFixedLagSmoother : gtsam::FixedLagSmoother {
|
||||||
IncrementalFixedLagSmoother(double smootherLag);
|
IncrementalFixedLagSmoother(double smootherLag);
|
||||||
IncrementalFixedLagSmoother(double smootherLag, const gtsam::ISAM2Params& params);
|
IncrementalFixedLagSmoother(double smootherLag, const gtsam::ISAM2Params& params);
|
||||||
|
|
||||||
|
void print(string s = "IncrementalFixedLagSmoother:\n") const;
|
||||||
|
|
||||||
gtsam::ISAM2Params params() const;
|
gtsam::ISAM2Params params() const;
|
||||||
|
|
||||||
gtsam::NonlinearFactorGraph getFactors() const;
|
gtsam::NonlinearFactorGraph getFactors() const;
|
||||||
|
gtsam::ISAM2 getISAM2() const;
|
||||||
};
|
};
|
||||||
|
|
||||||
#include <gtsam_unstable/nonlinear/ConcurrentFilteringAndSmoothing.h>
|
#include <gtsam_unstable/nonlinear/ConcurrentFilteringAndSmoothing.h>
|
||||||
|
|
|
@ -113,6 +113,9 @@ public:
|
||||||
/// Get results of latest isam2 update
|
/// Get results of latest isam2 update
|
||||||
const ISAM2Result& getISAM2Result() const{ return isamResult_; }
|
const ISAM2Result& getISAM2Result() const{ return isamResult_; }
|
||||||
|
|
||||||
|
/// Get the iSAM2 object which is used for the inference internally
|
||||||
|
const ISAM2& getISAM2() const { return isam_; }
|
||||||
|
|
||||||
protected:
|
protected:
|
||||||
|
|
||||||
/** Create default parameters */
|
/** Create default parameters */
|
||||||
|
|
Loading…
Reference in New Issue