HybridSmoother.h
Go to the documentation of this file.
1 /* ----------------------------------------------------------------------------
2 
3  * GTSAM Copyright 2010, Georgia Tech Research Corporation,
4  * Atlanta, Georgia 30332-0415
5  * All Rights Reserved
6  * Authors: Frank Dellaert, et al. (see THANKS for the full author list)
7 
8  * See LICENSE for the license information
9 
10  * -------------------------------------------------------------------------- */
11 
23 
24 #include <optional>
25 
26 namespace gtsam {
27 
28 class GTSAM_EXPORT HybridSmoother {
29  private:
32 
35  std::optional<double> marginalThreshold_;
37 
38  public:
46  HybridSmoother(const std::optional<double> marginalThreshold = {})
47  : marginalThreshold_(marginalThreshold) {}
48 
50  const DiscreteValues& fixedValues() const { return fixedValues_; }
51 
55  void reInitialize(HybridBayesNet&& hybridBayesNet);
56 
61  void reInitialize(HybridBayesNet& hybridBayesNet);
62 
83  std::optional<size_t> maxNrLeaves = {},
84  const std::optional<Ordering> givenOrdering = {});
85 
98  Ordering getOrdering(const HybridGaussianFactorGraph& factors,
99  const KeySet& newFactorKeys);
100 
110  std::pair<HybridGaussianFactorGraph, HybridBayesNet> addConditionals(
111  const HybridGaussianFactorGraph& graph,
112  const HybridBayesNet& hybridBayesNet) const;
113 
121  HybridGaussianConditional::shared_ptr gaussianMixture(size_t index) const;
122 
124  const HybridBayesNet& hybridBayesNet() const;
125 
127  HybridValues optimize() const;
128 
131  void relinearize();
132 
134  Values linearizationPoint() const;
135 
137  HybridNonlinearFactorGraph allFactors() const;
138 
139  private:
141  Ordering maybeComputeOrdering(const HybridGaussianFactorGraph& updatedGraph,
142  const std::optional<Ordering> givenOrdering);
143 
145  void removeFixedValues(const HybridGaussianFactorGraph& newFactors);
146 };
147 
148 } // namespace gtsam
gtsam::HybridSmoother::HybridSmoother
HybridSmoother(const std::optional< double > marginalThreshold={})
Constructor.
Definition: HybridSmoother.h:46
gtsam::HybridSmoother::marginalThreshold_
std::optional< double > marginalThreshold_
The threshold above which we make a decision about a mode.
Definition: HybridSmoother.h:35
relicense.update
def update(text)
Definition: relicense.py:46
gtsam::HybridGaussianConditional::shared_ptr
std::shared_ptr< This > shared_ptr
Definition: HybridGaussianConditional.h:60
HybridNonlinearFactorGraph.h
Nonlinear hybrid factor graph that uses type erasure.
gtsam::HybridBayesNet
Definition: HybridBayesNet.h:37
DiscreteFactorGraph.h
gtsam::HybridNonlinearFactorGraph
Definition: HybridNonlinearFactorGraph.h:33
gtsam::optimize
Point3 optimize(const NonlinearFactorGraph &graph, const Values &values, Key landmarkKey)
Definition: triangulation.cpp:177
simple_graph::factors
const GaussianFactorGraph factors
Definition: testJacobianFactor.cpp:213
Values
HybridBayesNet.h
A Bayes net of Gaussian Conditionals indexed by discrete keys.
HybridValues
gtsam::KeySet
FastSet< Key > KeySet
Definition: Key.h:96
gtsam::HybridSmoother::linearizationPoint_
Values linearizationPoint_
Definition: HybridSmoother.h:31
gtsam::HybridSmoother
Definition: HybridSmoother.h:28
gtsam::HybridSmoother::hybridBayesNet_
HybridBayesNet hybridBayesNet_
Definition: HybridSmoother.h:33
HybridGaussianFactorGraph.h
Linearized Hybrid factor graph that uses type erasure.
gtsam
traits
Definition: SFMdata.h:40
gtsam::DiscreteValues
Definition: DiscreteValues.h:34
gtsam::Values
Definition: Values.h:65
gtsam::HybridSmoother::fixedValues_
DiscreteValues fixedValues_
Definition: HybridSmoother.h:36
getOrdering
static std::shared_ptr< Ordering > getOrdering(const vector< GeneralCamera > &cameras, const vector< Point3 > &landmarks)
Definition: testGeneralSFMFactor.cpp:118
initial
Definition: testScenarioRunner.cpp:148
gtsam::HybridSmoother::fixedValues
const DiscreteValues & fixedValues() const
Return fixed values:
Definition: HybridSmoother.h:50
graph
NonlinearFactorGraph graph
Definition: doc/Code/OdometryExample.cpp:2
gtsam::HybridSmoother::allFactors_
HybridNonlinearFactorGraph allFactors_
Definition: HybridSmoother.h:30


gtsam
Author(s):
autogenerated on Wed Mar 19 2025 03:01:48