expose some iSAM2/FixedLagSmoothing functionality for the bindings
parent
a2caa0caf7
commit
0814efafd7
|
@ -313,6 +313,10 @@ struct GTSAM_EXPORT ISAM2Params {
|
||||||
return enablePartialRelinearizationCheck;
|
return enablePartialRelinearizationCheck;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
bool isFindUnusedFactorSlots() const {
|
||||||
|
return findUnusedFactorSlots;
|
||||||
|
}
|
||||||
|
|
||||||
void setOptimizationParams(OptimizationParams optimizationParams) {
|
void setOptimizationParams(OptimizationParams optimizationParams) {
|
||||||
this->optimizationParams = optimizationParams;
|
this->optimizationParams = optimizationParams;
|
||||||
}
|
}
|
||||||
|
@ -344,6 +348,9 @@ struct GTSAM_EXPORT ISAM2Params {
|
||||||
bool enablePartialRelinearizationCheck) {
|
bool enablePartialRelinearizationCheck) {
|
||||||
this->enablePartialRelinearizationCheck = enablePartialRelinearizationCheck;
|
this->enablePartialRelinearizationCheck = enablePartialRelinearizationCheck;
|
||||||
}
|
}
|
||||||
|
void setFindUnusedFactorSlots(bool findUnusedFactorSlots) {
|
||||||
|
this->findUnusedFactorSlots = findUnusedFactorSlots;
|
||||||
|
}
|
||||||
|
|
||||||
GaussianFactorGraph::Eliminate getEliminationFunction() const {
|
GaussianFactorGraph::Eliminate getEliminationFunction() const {
|
||||||
return factorization == CHOLESKY
|
return factorization == CHOLESKY
|
||||||
|
|
|
@ -696,6 +696,9 @@ class ISAM2Params {
|
||||||
bool isEnablePartialRelinearizationCheck() const;
|
bool isEnablePartialRelinearizationCheck() const;
|
||||||
void setEnablePartialRelinearizationCheck(
|
void setEnablePartialRelinearizationCheck(
|
||||||
bool enablePartialRelinearizationCheck);
|
bool enablePartialRelinearizationCheck);
|
||||||
|
bool isFindUnusedFactorSlots() const;
|
||||||
|
void setFindUnusedFactorSlots(bool findUnusedFactorSlots);
|
||||||
|
|
||||||
};
|
};
|
||||||
|
|
||||||
class ISAM2Clique {
|
class ISAM2Clique {
|
||||||
|
|
|
@ -567,6 +567,10 @@ virtual class FixedLagSmoother {
|
||||||
double smootherLag() const;
|
double smootherLag() const;
|
||||||
|
|
||||||
gtsam::FixedLagSmootherResult update(const gtsam::NonlinearFactorGraph& newFactors, const gtsam::Values& newTheta, const gtsam::FixedLagSmootherKeyTimestampMap& timestamps);
|
gtsam::FixedLagSmootherResult update(const gtsam::NonlinearFactorGraph& newFactors, const gtsam::Values& newTheta, const gtsam::FixedLagSmootherKeyTimestampMap& timestamps);
|
||||||
|
gtsam::FixedLagSmootherResult update(const gtsam::NonlinearFactorGraph &newFactors,
|
||||||
|
const gtsam::Values &newTheta,
|
||||||
|
const gtsam::FixedLagSmootherKeyTimestampMap ×tamps,
|
||||||
|
const gtsam::FactorIndices &factorsToRemove);
|
||||||
gtsam::Values calculateEstimate() const;
|
gtsam::Values calculateEstimate() const;
|
||||||
};
|
};
|
||||||
|
|
||||||
|
@ -590,6 +594,8 @@ virtual class IncrementalFixedLagSmoother : gtsam::FixedLagSmoother {
|
||||||
IncrementalFixedLagSmoother(double smootherLag, const gtsam::ISAM2Params& params);
|
IncrementalFixedLagSmoother(double smootherLag, const gtsam::ISAM2Params& params);
|
||||||
|
|
||||||
gtsam::ISAM2Params params() const;
|
gtsam::ISAM2Params params() const;
|
||||||
|
|
||||||
|
gtsam::NonlinearFactorGraph getFactors() const;
|
||||||
};
|
};
|
||||||
|
|
||||||
#include <gtsam_unstable/nonlinear/ConcurrentFilteringAndSmoothing.h>
|
#include <gtsam_unstable/nonlinear/ConcurrentFilteringAndSmoothing.h>
|
||||||
|
|
Loading…
Reference in New Issue