HybridSmoother.cpp
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 
20 
21 #include <algorithm>
22 #include <unordered_set>
23 
24 // #define DEBUG_SMOOTHER
25 namespace gtsam {
26 
27 /* ************************************************************************* */
29  hybridBayesNet_ = std::move(hybridBayesNet);
30 }
31 
32 /* ************************************************************************* */
34  this->reInitialize(std::move(hybridBayesNet));
35 }
36 
37 /* ************************************************************************* */
39  const KeySet &lastKeysToEliminate) {
40  // Get all the discrete keys from the factors
41  KeySet allDiscrete = factors.discreteKeySet();
42 
43  // Create KeyVector with continuous keys followed by discrete keys.
44  KeyVector lastKeys;
45 
46  // Insert continuous keys first.
47  for (auto &k : lastKeysToEliminate) {
48  if (!allDiscrete.exists(k)) {
49  lastKeys.push_back(k);
50  }
51  }
52 
53  // Insert discrete keys at the end
54  std::copy(allDiscrete.begin(), allDiscrete.end(),
55  std::back_inserter(lastKeys));
56 
57  // Get an ordering where the new keys are eliminated last
59  factors, KeyVector(lastKeys.begin(), lastKeys.end()), true);
60 
61  return ordering;
62 }
63 
64 /* ************************************************************************* */
66  const HybridGaussianFactorGraph &updatedGraph,
67  const std::optional<Ordering> givenOrdering) {
69  // If no ordering provided, then we compute one
70  if (!givenOrdering.has_value()) {
71  // Get the keys from the new factors
72  KeySet continuousKeysToInclude; // Scheme 1: empty, 15sec/2000, 64sec/3000
73  // (69s without TF)
74  // continuousKeysToInclude = newFactors.keys(); // Scheme 2: all,
75  // 8sec/2000, 160sec/3000 continuousKeysToInclude = updatedGraph.keys(); //
76  // Scheme 3: all, stopped after 80sec/2000
77 
78  // Since updatedGraph now has all the connected conditionals,
79  // we can get the correct ordering.
80  ordering = this->getOrdering(updatedGraph, continuousKeysToInclude);
81  } else {
82  ordering = *givenOrdering;
83  }
84 
85  return ordering;
86 }
87 
88 /* ************************************************************************* */
90  const HybridGaussianFactorGraph &newFactors) {
91  for (Key key : newFactors.discreteKeySet()) {
92  if (fixedValues_.find(key) != fixedValues_.end()) {
93  fixedValues_.erase(key);
94  }
95  }
96 }
97 
98 /* ************************************************************************* */
100  const Values &initial,
101  std::optional<size_t> maxNrLeaves,
102  const std::optional<Ordering> given_ordering) {
103  HybridGaussianFactorGraph linearizedFactors = *newFactors.linearize(initial);
104 
105  // Record the new nonlinear factors and
106  // linearization point for relinearization
107  allFactors_.push_back(newFactors);
109 
110  const KeySet originalNewFactorKeys = newFactors.keys();
111 #ifdef DEBUG_SMOOTHER
112  std::cout << "hybridBayesNet_ size before: " << hybridBayesNet_.size()
113  << std::endl;
114  std::cout << "newFactors size: " << newFactors.size() << std::endl;
115 #endif
116  HybridGaussianFactorGraph updatedGraph;
117  // Add the necessary conditionals from the previous timestep(s).
118  std::tie(updatedGraph, hybridBayesNet_) =
119  addConditionals(linearizedFactors, hybridBayesNet_);
120 #ifdef DEBUG_SMOOTHER
121  // print size of newFactors, updatedGraph, hybridBayesNet_
122  std::cout << "updatedGraph size: " << updatedGraph.size() << std::endl;
123  std::cout << "hybridBayesNet_ size after: " << hybridBayesNet_.size()
124  << std::endl;
125  std::cout << "total size: " << updatedGraph.size() + hybridBayesNet_.size()
126  << std::endl;
127 #endif
128 
129  Ordering ordering = this->maybeComputeOrdering(updatedGraph, given_ordering);
130 
131 #if GTSAM_HYBRID_TIMING
132  gttic_(HybridSmootherEliminate);
133 #endif
134  // Eliminate.
135  HybridBayesNet bayesNetFragment = *updatedGraph.eliminateSequential(ordering);
136 #if GTSAM_HYBRID_TIMING
137  gttoc_(HybridSmootherEliminate);
138 #endif
139 
140 #ifdef DEBUG_SMOOTHER_DETAIL
141  for (auto conditional : bayesNetFragment) {
142  auto e = std::dynamic_pointer_cast<HybridConditional::BaseConditional>(
143  conditional);
144  GTSAM_PRINT(*e);
145  }
146 #endif
147 
148  // Remove fixed values for discrete keys which are introduced in newFactors
149  removeFixedValues(newFactors);
150 
151 #ifdef DEBUG_SMOOTHER
152  // Print discrete keys in the bayesNetFragment:
153  std::cout << "Discrete keys in bayesNetFragment: ";
154  for (auto &key : HybridFactorGraph(bayesNetFragment).discreteKeySet()) {
155  std::cout << DefaultKeyFormatter(key) << " ";
156  }
157 #endif
158 
160  if (maxNrLeaves) {
161 #if GTSAM_HYBRID_TIMING
162  gttic_(HybridSmootherPrune);
163 #endif
164  // `pruneBayesNet` sets the leaves with 0 in discreteFactor to nullptr in
165  // all the conditionals with the same keys in bayesNetFragment.
166  DiscreteValues newlyFixedValues;
167  bayesNetFragment = bayesNetFragment.prune(*maxNrLeaves, marginalThreshold_,
168  &newlyFixedValues);
169  fixedValues_.insert(newlyFixedValues);
170 #if GTSAM_HYBRID_TIMING
171  gttoc_(HybridSmootherPrune);
172 #endif
173  }
174 
175 #ifdef DEBUG_SMOOTHER
176  // Print discrete keys in the bayesNetFragment:
177  std::cout << "\nAfter pruning: ";
178  for (auto &key : HybridFactorGraph(bayesNetFragment).discreteKeySet()) {
179  std::cout << DefaultKeyFormatter(key) << " ";
180  }
181  std::cout << std::endl << std::endl;
182 #endif
183 
184 #ifdef DEBUG_SMOOTHER_DETAIL
185  for (auto conditional : bayesNetFragment) {
186  auto c = std::dynamic_pointer_cast<HybridConditional::BaseConditional>(
187  conditional);
188  GTSAM_PRINT(*c);
189  }
190 #endif
191 
192  // Add the partial bayes net to the posterior bayes net.
193  hybridBayesNet_.add(bayesNetFragment);
194 }
195 
196 /* ************************************************************************* */
197 std::pair<HybridGaussianFactorGraph, HybridBayesNet>
199  const HybridBayesNet &hybridBayesNet) const {
200  HybridGaussianFactorGraph graph(newFactors);
201  HybridBayesNet updatedHybridBayesNet(hybridBayesNet);
202 
203  KeySet involvedKeys = newFactors.keys();
204  auto involved = [](const KeySet &involvedKeys, const Key &key) {
205  return involvedKeys.find(key) != involvedKeys.end();
206  };
207 
208  // If hybridBayesNet is not empty,
209  // it means we have conditionals to add to the factor graph.
210  if (!hybridBayesNet.empty()) {
211  // We add all relevant hybrid conditionals on the last continuous variable
212  // in the previous `hybridBayesNet` to the graph
213 
214  // New conditionals to add to the graph
215  HybridBayesNet newConditionals;
216 
217  // NOTE(Varun) Using a for-range loop doesn't work since some of the
218  // conditionals are invalid pointers
219 
220  // First get all the keys involved.
221  // We do this by iterating over all conditionals, and checking if their
222  // frontals are involved in the factor graph. If yes, then also make the
223  // parent keys involved in the factor graph.
224  for (size_t i = 0; i < hybridBayesNet.size(); i++) {
225  auto conditional = hybridBayesNet.at(i);
226 
227  for (auto &key : conditional->frontals()) {
228  if (involved(involvedKeys, key)) {
229  // Add the conditional parents to involvedKeys
230  // so we add those conditionals too.
231  for (auto &&parentKey : conditional->parents()) {
232  involvedKeys.insert(parentKey);
233  }
234  // Break so we don't add parents twice.
235  break;
236  }
237  }
238  }
239 #ifdef DEBUG_SMOOTHER
240  PrintKeySet(involvedKeys);
241 #endif
242 
243  for (size_t i = 0; i < hybridBayesNet.size(); i++) {
244  auto conditional = hybridBayesNet.at(i);
245 
246  for (auto &key : conditional->frontals()) {
247  if (involved(involvedKeys, key)) {
248  newConditionals.push_back(conditional);
249 
250  // Remove the conditional from the updated Bayes net
251  auto it = find(updatedHybridBayesNet.begin(),
252  updatedHybridBayesNet.end(), conditional);
253  updatedHybridBayesNet.erase(it);
254 
255  break;
256  }
257  }
258  }
259 
260  graph.push_back(newConditionals);
261  }
262 
263  return {graph, updatedHybridBayesNet};
264 }
265 
266 /* ************************************************************************* */
268  size_t index) const {
269  return hybridBayesNet_.at(index)->asHybrid();
270 }
271 
272 /* ************************************************************************* */
274  return hybridBayesNet_;
275 }
276 
277 /* ************************************************************************* */
279  // Solve for the MPE
281 
282  // Add fixed values to the MPE.
283  mpe.insert(fixedValues_);
284 
285  // Given the MPE, compute the optimal continuous values.
287  const VectorValues continuous = gbn.optimize();
288  if (std::find(gbn.begin(), gbn.end(), nullptr) != gbn.end()) {
289  throw std::runtime_error("At least one nullptr factor in hybridBayesNet_");
290  }
291  return HybridValues(continuous, mpe);
292 }
293 
294 /* ************************************************************************* */
299  HybridBayesNet::shared_ptr bayesNet = linearized->eliminateSequential();
300  HybridValues delta = bayesNet->optimize();
303 }
304 
305 /* ************************************************************************* */
307  return linearizationPoint_;
308 }
309 
310 /* ************************************************************************* */
312  return allFactors_;
313 }
314 
315 } // namespace gtsam
gtsam::HybridSmoother::hybridBayesNet
const HybridBayesNet & hybridBayesNet() const
Return the Bayes Net posterior.
Definition: HybridSmoother.cpp:273
gtsam::Ordering::ColamdConstrainedLast
static Ordering ColamdConstrainedLast(const FACTOR_GRAPH &graph, const KeyVector &constrainLast, bool forceOrder=false)
Definition: inference/Ordering.h:112
gtsam::HybridGaussianFactorGraph::shared_ptr
std::shared_ptr< This > shared_ptr
shared_ptr to This
Definition: HybridGaussianFactorGraph.h:120
gtsam::HybridSmoother::linearizationPoint
Values linearizationPoint() const
Return the current linearization point.
Definition: HybridSmoother.cpp:306
gtsam::EliminateableFactorGraph::eliminateSequential
std::shared_ptr< BayesNetType > eliminateSequential(OptionalOrderingType orderingType={}, const Eliminate &function=EliminationTraitsType::DefaultEliminate, OptionalVariableIndex variableIndex={}) const
Definition: EliminateableFactorGraph-inst.h:29
gtsam::HybridSmoother::marginalThreshold_
std::optional< double > marginalThreshold_
The threshold above which we make a decision about a mode.
Definition: HybridSmoother.h:35
gtsam::HybridFactorGraph
Definition: HybridFactorGraph.h:38
gtsam::HybridValues
Definition: HybridValues.h:37
asia::bayesNet
static const DiscreteBayesNet bayesNet
Definition: testDiscreteSearch.cpp:30
gtsam::HybridSmoother::update
void update(const HybridNonlinearFactorGraph &graph, const Values &initial, std::optional< size_t > maxNrLeaves={}, const std::optional< Ordering > givenOrdering={})
Definition: HybridSmoother.cpp:99
gtsam::HybridGaussianConditional::shared_ptr
std::shared_ptr< This > shared_ptr
Definition: HybridGaussianConditional.h:60
e
Array< double, 1, 3 > e(1./3., 0.5, 2.)
gtsam::HybridSmoother::allFactors
HybridNonlinearFactorGraph allFactors() const
Return all the recorded nonlinear factors.
Definition: HybridSmoother.cpp:311
gtsam::HybridBayesNet
Definition: HybridBayesNet.h:37
gtsam::HybridNonlinearFactorGraph
Definition: HybridNonlinearFactorGraph.h:33
c
Scalar Scalar * c
Definition: benchVecAdd.cpp:17
gtsam::HybridSmoother::maybeComputeOrdering
Ordering maybeComputeOrdering(const HybridGaussianFactorGraph &updatedGraph, const std::optional< Ordering > givenOrdering)
Helper to compute the ordering if ordering is not given.
Definition: HybridSmoother.cpp:65
gtsam::FastSet::exists
bool exists(const VALUE &e) const
Definition: FastSet.h:102
gtsam::HybridSmoother::getOrdering
Ordering getOrdering(const HybridGaussianFactorGraph &factors, const KeySet &newFactorKeys)
Get an elimination ordering which eliminates continuous and then discrete.
Definition: HybridSmoother.cpp:38
simple_graph::factors
const GaussianFactorGraph factors
Definition: testJacobianFactor.cpp:213
gtsam::FastSet< Key >
gtsam::KeyVector
FastVector< Key > KeyVector
Define collection type once and for all - also used in wrappers.
Definition: Key.h:92
HybridSmoother.h
An incremental smoother for hybrid factor graphs.
gtsam::DefaultKeyFormatter
KeyFormatter DefaultKeyFormatter
Assign default key formatter.
Definition: Key.cpp:30
gtsam::FactorGraph::erase
iterator erase(iterator item)
Definition: FactorGraph.h:377
gtsam::HybridSmoother::removeFixedValues
void removeFixedValues(const HybridGaussianFactorGraph &newFactors)
Remove fixed discrete values for discrete keys introduced in newFactors.
Definition: HybridSmoother.cpp:89
gtsam::FactorGraph::at
const sharedFactor at(size_t i) const
Definition: FactorGraph.h:306
gtsam::Values::retract
Values retract(const VectorValues &delta) const
Definition: Values.cpp:99
gtsam.examples.PlanarManipulatorExample.delta
def delta(g0, g1)
Definition: PlanarManipulatorExample.py:45
gtsam::VectorValues
Definition: VectorValues.h:74
gttoc_
#define gttoc_(label)
Definition: timing.h:273
gttic_
#define gttic_(label)
Definition: timing.h:268
gtsam::FactorGraph::keys
KeySet keys() const
Definition: FactorGraph-inst.h:85
gtsam::HybridGaussianFactorGraph
Definition: HybridGaussianFactorGraph.h:106
gtsam::HybridSmoother::optimize
HybridValues optimize() const
Optimize the hybrid Bayes Net, taking into accound fixed values.
Definition: HybridSmoother.cpp:278
gtsam::HybridSmoother::addConditionals
std::pair< HybridGaussianFactorGraph, HybridBayesNet > addConditionals(const HybridGaussianFactorGraph &graph, const HybridBayesNet &hybridBayesNet) const
Add conditionals from previous timestep as part of liquefication.
Definition: HybridSmoother.cpp:198
gtsam::HybridBayesNet::mpe
DiscreteValues mpe() const
Compute the Most Probable Explanation (MPE) of the discrete variables.
Definition: HybridBayesNet.cpp:142
GTSAM_PRINT
#define GTSAM_PRINT(x)
Definition: Testable.h:43
gtsam::HybridFactorGraph::discreteKeySet
KeySet discreteKeySet() const
Get all the discrete keys in the factor graph, as a set of Keys.
Definition: HybridFactorGraph.cpp:43
sampling::gbn
static const GaussianBayesNet gbn
Definition: testGaussianBayesNet.cpp:171
gtsam::HybridSmoother::linearizationPoint_
Values linearizationPoint_
Definition: HybridSmoother.h:31
asia::mpe
static const DiscreteValues mpe
Definition: testDiscreteSearch.cpp:34
ordering
static enum @1096 ordering
key
const gtsam::Symbol key('X', 0)
gtsam::FactorGraph::size
size_t size() const
Definition: FactorGraph.h:297
gtsam::HybridSmoother::reInitialize
void reInitialize(HybridBayesNet &&hybridBayesNet)
Definition: HybridSmoother.cpp:28
gtsam::HybridSmoother::hybridBayesNet_
HybridBayesNet hybridBayesNet_
Definition: HybridSmoother.h:33
gtsam::FactorGraph::empty
bool empty() const
Definition: FactorGraph.h:301
gtsam::HybridBayesNet::push_back
void push_back(std::shared_ptr< HybridConditional > conditional)
Add a hybrid conditional using a shared_ptr.
Definition: HybridBayesNet.h:76
gtsam::HybridNonlinearFactorGraph::restrict
HybridNonlinearFactorGraph restrict(const DiscreteValues &assignment) const
Restrict all factors in the graph to the given discrete values.
Definition: HybridNonlinearFactorGraph.cpp:225
gtsam
traits
Definition: SFMdata.h:40
gtsam::HybridSmoother::gaussianMixture
HybridGaussianConditional::shared_ptr gaussianMixture(size_t index) const
Get the hybrid Gaussian conditional from the Bayes Net posterior at index.
Definition: HybridSmoother.cpp:267
gtsam::DiscreteValues
Definition: DiscreteValues.h:34
gtsam::FactorGraph::push_back
IsDerived< DERIVEDFACTOR > push_back(std::shared_ptr< DERIVEDFACTOR > factor)
Add a factor directly using a shared_ptr.
Definition: FactorGraph.h:147
gtsam::Values
Definition: Values.h:65
gtsam::FactorGraph::end
const_iterator end() const
Definition: FactorGraph.h:342
gtsam::DiscreteValues::insert
std::pair< iterator, bool > insert(const value_type &value)
Definition: DiscreteValues.h:71
gtsam::HybridNonlinearFactorGraph::linearize
std::shared_ptr< HybridGaussianFactorGraph > linearize(const Values &continuousValues) const
Linearize all the continuous factors in the HybridNonlinearFactorGraph.
Definition: HybridNonlinearFactorGraph.cpp:139
gtsam::HybridSmoother::fixedValues_
DiscreteValues fixedValues_
Definition: HybridSmoother.h:36
gtsam::FactorGraph::begin
const_iterator begin() const
Definition: FactorGraph.h:339
initial
Definition: testScenarioRunner.cpp:148
gtsam::HybridBayesNet::shared_ptr
std::shared_ptr< HybridBayesNet > shared_ptr
Definition: HybridBayesNet.h:42
gtsam::FactorGraph::add
IsDerived< DERIVEDFACTOR > add(std::shared_ptr< DERIVEDFACTOR > factor)
add is a synonym for push_back.
Definition: FactorGraph.h:171
graph
NonlinearFactorGraph graph
Definition: doc/Code/OdometryExample.cpp:2
gtsam::Key
std::uint64_t Key
Integer nonlinear key type.
Definition: types.h:97
gtsam::PrintKeySet
void PrintKeySet(const KeySet &keys, const string &s, const KeyFormatter &keyFormatter)
Utility function to print sets of keys with optional prefix.
Definition: Key.cpp:88
gtsam::Ordering
Definition: inference/Ordering.h:33
i
int i
Definition: BiCGSTAB_step_by_step.cpp:9
gtsam::HybridSmoother::allFactors_
HybridNonlinearFactorGraph allFactors_
Definition: HybridSmoother.h:30
gtsam::GaussianBayesNet
Definition: GaussianBayesNet.h:35
gtsam::HybridSmoother::relinearize
void relinearize()
Definition: HybridSmoother.cpp:295
gtsam::HybridBayesNet::choose
GaussianBayesNet choose(const DiscreteValues &assignment) const
Get the Gaussian Bayes net P(X|M=m) corresponding to a specific assignment m for the discrete variabl...
Definition: HybridBayesNet.cpp:122
gtsam::Values::insert_or_assign
void insert_or_assign(Key j, const Value &val)
If key j exists, update value, else perform an insert.
Definition: Values.cpp:193


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