wrap HybridSmoother
parent
a35e5a6b08
commit
ed1f8734c9
|
@ -243,9 +243,8 @@ class HybridNonlinearFactorGraph {
|
||||||
|
|
||||||
#include <gtsam/hybrid/HybridNonlinearFactor.h>
|
#include <gtsam/hybrid/HybridNonlinearFactor.h>
|
||||||
class HybridNonlinearFactor : gtsam::HybridFactor {
|
class HybridNonlinearFactor : gtsam::HybridFactor {
|
||||||
HybridNonlinearFactor(
|
HybridNonlinearFactor(const gtsam::DiscreteKey& discreteKey,
|
||||||
const gtsam::DiscreteKey& discreteKey,
|
const std::vector<gtsam::NoiseModelFactor*>& factors);
|
||||||
const std::vector<gtsam::NoiseModelFactor*>& factors);
|
|
||||||
|
|
||||||
HybridNonlinearFactor(
|
HybridNonlinearFactor(
|
||||||
const gtsam::DiscreteKey& discreteKey,
|
const gtsam::DiscreteKey& discreteKey,
|
||||||
|
@ -266,4 +265,19 @@ class HybridNonlinearFactor : gtsam::HybridFactor {
|
||||||
gtsam::DefaultKeyFormatter) const;
|
gtsam::DefaultKeyFormatter) const;
|
||||||
};
|
};
|
||||||
|
|
||||||
|
#include <gtsam/hybrid/HybridSmoother.h>
|
||||||
|
class HybridSmoother {
|
||||||
|
HybridSmoother(const std::optional<double> marginalThreshold = std::nullopt);
|
||||||
|
|
||||||
|
const gtsam::DiscreteValues& fixedValues() const;
|
||||||
|
void reInitialize(gtsam::HybridBayesNet& hybridBayesNet);
|
||||||
|
|
||||||
|
void update(
|
||||||
|
const gtsam::HybridGaussianFactorGraph& graph,
|
||||||
|
std::optional<size_t> maxNrLeaves = std::nullopt,
|
||||||
|
const std::optional<gtsam::Ordering> given_ordering = std::nullopt);
|
||||||
|
|
||||||
|
HybridValues optimize() const;
|
||||||
|
};
|
||||||
|
|
||||||
} // namespace gtsam
|
} // namespace gtsam
|
||||||
|
|
Loading…
Reference in New Issue