move HybridSmoother method definitions to cpp file

release/4.3a0
Varun Agrawal 2025-02-09 11:44:03 -05:00
parent 582d67eea4
commit 74637d82d6
2 changed files with 17 additions and 9 deletions

View File

@ -24,6 +24,16 @@
// #define DEBUG_SMOOTHER // #define DEBUG_SMOOTHER
namespace gtsam { namespace gtsam {
/* ************************************************************************* */
void HybridSmoother::reInitialize(HybridBayesNet &&hybridBayesNet) {
hybridBayesNet_ = std::move(hybridBayesNet);
}
/* ************************************************************************* */
void HybridSmoother::reInitialize(HybridBayesNet &hybridBayesNet) {
this->reInitialize(std::move(hybridBayesNet));
}
/* ************************************************************************* */ /* ************************************************************************* */
Ordering HybridSmoother::getOrdering(const HybridGaussianFactorGraph &factors, Ordering HybridSmoother::getOrdering(const HybridGaussianFactorGraph &factors,
const KeySet &lastKeysToEliminate) { const KeySet &lastKeysToEliminate) {
@ -78,9 +88,11 @@ void HybridSmoother::update(const HybridGaussianFactorGraph &newFactors,
// If no ordering provided, then we compute one // If no ordering provided, then we compute one
if (!given_ordering.has_value()) { if (!given_ordering.has_value()) {
// Get the keys from the new factors // Get the keys from the new factors
KeySet continuousKeysToInclude; // Scheme 1: empty, 15sec/2000, 64sec/3000 (69s without TF) KeySet continuousKeysToInclude; // Scheme 1: empty, 15sec/2000, 64sec/3000
// continuousKeysToInclude = newFactors.keys(); // Scheme 2: all, 8sec/2000, 160sec/3000 // (69s without TF)
// continuousKeysToInclude = updatedGraph.keys(); // Scheme 3: all, stopped after 80sec/2000 // continuousKeysToInclude = newFactors.keys(); // Scheme 2: all,
// 8sec/2000, 160sec/3000 continuousKeysToInclude = updatedGraph.keys(); //
// Scheme 3: all, stopped after 80sec/2000
// Since updatedGraph now has all the connected conditionals, // Since updatedGraph now has all the connected conditionals,
// we can get the correct ordering. // we can get the correct ordering.

View File

@ -49,17 +49,13 @@ class GTSAM_EXPORT HybridSmoother {
/** /**
* Re-initialize the smoother from a new hybrid Bayes Net. * Re-initialize the smoother from a new hybrid Bayes Net.
*/ */
void reInitialize(HybridBayesNet&& hybridBayesNet) { void reInitialize(HybridBayesNet&& hybridBayesNet);
hybridBayesNet_ = std::move(hybridBayesNet);
}
/** /**
* Re-initialize the smoother from * Re-initialize the smoother from
* a new hybrid Bayes Net (non rvalue version). * a new hybrid Bayes Net (non rvalue version).
*/ */
void reInitialize(HybridBayesNet& hybridBayesNet) { void reInitialize(HybridBayesNet& hybridBayesNet);
this->reInitialize(std::move(hybridBayesNet));
}
/** /**
* Given new factors, perform an incremental update. * Given new factors, perform an incremental update.