ConcurrentBatchFilter.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 
21 #include <gtsam/base/timing.h>
22 #include <gtsam/base/debug.h>
23 
24 namespace gtsam {
25 
26 /* ************************************************************************* */
28  const std::string& indent, const KeyFormatter& keyFormatter) {
29  std::cout << indent;
30  if(factor) {
31  if(std::dynamic_pointer_cast<LinearContainerFactor>(factor)) {
32  std::cout << "l( ";
33  } else {
34  std::cout << "f( ";
35  }
36  for(Key key: *factor) {
37  std::cout << keyFormatter(key) << " ";
38  }
39  std::cout << ")" << std::endl;
40  } else {
41  std::cout << "{ nullptr }" << std::endl;
42  }
43 }
44 
45 /* ************************************************************************* */
47  const std::string& indent, const std::string& title, const KeyFormatter& keyFormatter) {
48  std::cout << indent << title << std::endl;
49  for(const NonlinearFactor::shared_ptr& factor: factors) {
50  PrintNonlinearFactor(factor, indent + " ", keyFormatter);
51  }
52 }
53 
54 /* ************************************************************************* */
56  const std::string& indent, const std::string& title, const KeyFormatter& keyFormatter) {
57  std::cout << indent << title << std::endl;
58  for(size_t slot: slots) {
59  PrintNonlinearFactor(factors.at(slot), indent + " ", keyFormatter);
60  }
61 }
62 
63 /* ************************************************************************* */
65  const std::string& indent, const KeyFormatter& keyFormatter) {
66  std::cout << indent;
67  if(factor) {
68  JacobianFactor::shared_ptr jf = std::dynamic_pointer_cast<JacobianFactor>(factor);
69  HessianFactor::shared_ptr hf = std::dynamic_pointer_cast<HessianFactor>(factor);
70  if(jf) {
71  std::cout << "j( ";
72  } else if(hf) {
73  std::cout << "h( ";
74  } else {
75  std::cout << "g( ";
76  }
77  for(Key key: *factor) {
78  std::cout << keyFormatter(key) << " ";
79  }
80  std::cout << ")" << std::endl;
81  } else {
82  std::cout << "{ nullptr }" << std::endl;
83  }
84 }
85 
86 /* ************************************************************************* */
88  const std::string& indent, const std::string& title, const KeyFormatter& keyFormatter) {
89  std::cout << indent << title << std::endl;
90  for(const GaussianFactor::shared_ptr& factor: factors) {
91  PrintLinearFactor(factor, indent + " ", keyFormatter);
92  }
93 }
94 
95 /* ************************************************************************* */
96 void ConcurrentBatchFilter::print(const std::string& s, const KeyFormatter& keyFormatter) const {
97  std::cout << s;
98  PrintNonlinearFactorGraph(factors_, " ", "Factors:");
99  PrintKeys(theta_.keys(), " ", "Values:");
100  PrintNonlinearFactorGraph(smootherFactors_, " ", "Cached Smoother Factors:");
101  PrintKeys(smootherValues_.keys(), " ", "Cached Smoother Values:");
102 }
103 
104 /* ************************************************************************* */
105 bool ConcurrentBatchFilter::equals(const ConcurrentFilter& rhs, double tol) const {
106  const ConcurrentBatchFilter* filter = dynamic_cast<const ConcurrentBatchFilter*>(&rhs);
107  return filter
108  && factors_.equals(filter->factors_)
109  && theta_.equals(filter->theta_)
110  && ordering_.equals(filter->ordering_)
111  && delta_.equals(filter->delta_)
118 }
119 
120 /* ************************************************************************* */
122  const std::optional<FastList<Key> >& keysToMove, const std::optional< std::vector<size_t> >& removeFactorIndices) {
123 
124  gttic(update);
125 
126 // const bool debug = ISDEBUG("ConcurrentBatchFilter update");
127  const bool debug = false;
128 
129  if(debug) std::cout << "ConcurrentBatchFilter::update Begin" << std::endl;
130 
131  // Create the return result meta-data
132  Result result;
133 
134  if(debug) std::cout << "ConcurrentBatchFilter::update Augmenting System ..." << std::endl;
135 
136  // Update all of the internal variables with the new information
137  gttic(augment_system);
138 
139  // Add the new variables to theta
140  theta_.insert(newTheta);
141  // Add new variables to the end of the ordering
142  for (const auto key : newTheta.keys()) {
143  ordering_.push_back(key);
144  }
145  // Augment Delta
146  delta_.insert(newTheta.zeroVectors());
147 
148  // Add the new factors to the graph, updating the variable index
149  result.newFactorsIndices = insertFactors(newFactors);
150 
151  if(removeFactorIndices){
152  if(debug){
153  std::cout << "ConcurrentBatchFilter::update removeFactorIndices " << std::endl;
154  }
155  removeFactors(*removeFactorIndices);
156  }
157 
158  gttoc(augment_system);
159 
160  if(debug) std::cout << "ConcurrentBatchFilter::update Reordering System ..." << std::endl;
161 
162  // Reorder the system to ensure efficient optimization (and marginalization) performance
163  gttic(reorder);
164  reorder(keysToMove);
165  gttoc(reorder);
166 
167  if(debug) std::cout << "ConcurrentBatchFilter::update Optimizing System ..." << std::endl;
168 
169  // Optimize the factors using a modified version of L-M
170  gttic(optimize);
171  if(factors_.size() > 0) {
173  }
174  gttoc(optimize);
175 
176  if(debug) std::cout << "ConcurrentBatchFilter::update Moving Separator ..." << std::endl;
177 
178  gttic(move_separator);
179  if(keysToMove && keysToMove->size() > 0){
180  moveSeparator(*keysToMove);
181  }
182  gttoc(move_separator);
183 
184  if(debug) std::cout << "ConcurrentBatchFilter::update End" << std::endl;
185 
186  gttoc(update);
187 
188  return result;
189 }
190 
191 /* ************************************************************************* */
193 
194  gttic(presync);
195 
196  gttoc(presync);
197 }
198 
199 /* ************************************************************************* */
200 void ConcurrentBatchFilter::synchronize(const NonlinearFactorGraph& smootherSummarization, const Values& smootherSummarizationValues) {
201 
203 
204 // const bool debug = ISDEBUG("ConcurrentBatchFilter synchronize");
205  const bool debug = false;
206 
207  if(debug) std::cout << "ConcurrentBatchFilter::synchronize Begin" << std::endl;
208 
209  if(debug) { PrintNonlinearFactorGraph(smootherSummarization_, "ConcurrentBatchFilter::synchronize ", "Previous Smoother Summarization:", DefaultKeyFormatter); }
210 
211 #ifndef NDEBUG
212  std::set<Key> oldKeys = smootherSummarization_.keys();
213  std::set<Key> newKeys = smootherSummarization.keys();
214  assert(oldKeys.size() == newKeys.size());
215  assert(std::equal(oldKeys.begin(), oldKeys.end(), newKeys.begin()));
216 #endif
217 
218  // Update the smoother summarization on the old separator
219  smootherSummarization_ = smootherSummarization;
220 
221  if(debug) { PrintNonlinearFactorGraph(smootherSummarization_, "ConcurrentBatchFilter::synchronize ", "Updated Smoother Summarization:", DefaultKeyFormatter); }
222 
223  // Find the set of new separator keys
224  const KeySet newSeparatorKeys = separatorValues_.keySet();
225 
226  if(debug) { PrintKeys(newSeparatorKeys, "ConcurrentBatchFilter::synchronize ", "Current Separator Keys:"); }
227 
228  // Use the shortcut to calculate an updated marginal on the current separator
229  {
230  // Combine just the shortcut and the previousSmootherSummarization
234  Values values;
235  values.insert(smootherSummarizationValues);
236  for(const auto key: newSeparatorKeys) {
237  if(!values.exists(key)) {
238  values.insert(key, separatorValues_.at(key));
239  }
240  }
241  // Calculate the summarized factor on just the new separator keys
243 
244  // Remove the old factors on the separator and insert new
247 
248  // Clear the smoother shortcut
250  }
251 
252  if(debug) { PrintNonlinearFactorGraph(factors_, separatorSummarizationSlots_, "ConcurrentBatchFilter::synchronize ", "Current Separator Summarization:", DefaultKeyFormatter); }
253 
254  // Calculate the marginal on the new separator from the filter factors
255  // Note: This could also be done during each filter update so it would simply be available
256  {
257  // Calculate the summarized factor on just the new separator keys (from the filter side)
258  // Copy all of the factors from the filter, not including the smoother summarization
260  for(size_t slot = 0; slot < factors_.size(); ++slot) {
261  if(factors_.at(slot) && std::find(separatorSummarizationSlots_.begin(), separatorSummarizationSlots_.end(), slot) == separatorSummarizationSlots_.end()) {
262  factors.push_back(factors_.at(slot));
263  }
264  }
266  }
267 
268  if(debug) { PrintNonlinearFactorGraph(filterSummarization_, "ConcurrentBatchFilter::synchronize ", "Updated Filter Summarization:", DefaultKeyFormatter); }
269 
270  if(debug) std::cout << "ConcurrentBatchFilter::synchronize End" << std::endl;
271 
273 }
274 
275 /* ************************************************************************* */
276 void ConcurrentBatchFilter::getSummarizedFactors(NonlinearFactorGraph& filterSummarization, Values& filterSummarizationValues) {
277 
278  gttic(get_summarized_factors);
279 
280  // Copy the previous calculated smoother summarization factors into the output
281  filterSummarization.push_back(filterSummarization_);
282  filterSummarizationValues.insert(separatorValues_);
283 
284  gttoc(get_summarized_factors);
285 }
286 
287 /* ************************************************************************* */
289 
290  gttic(get_smoother_factors);
291 
292  // Copy the previous calculated smoother summarization factors into the output
293  smootherFactors.push_back(smootherFactors_);
294  smootherValues.insert(smootherValues_);
295 
296  gttoc(get_smoother_factors);
297 }
298 
299 /* ************************************************************************* */
301 
302  gttic(postsync);
303 
304  // Clear out the factors and values that were just sent to the smoother
307 
308  gttoc(postsync);
309 }
310 
311 /* ************************************************************************* */
313 
314  gttic(insert_factors);
315 
316  // create the output vector
317  std::vector<size_t> slots;
318  slots.reserve(factors.size());
319 
320  // Insert the factor into an existing hole in the factor graph, if possible
321  for(const NonlinearFactor::shared_ptr& factor: factors) {
322  size_t slot;
323  if(availableSlots_.size() > 0) {
324  slot = availableSlots_.front();
325  availableSlots_.pop();
326  factors_.replace(slot, factor);
327  } else {
328  slot = factors_.size();
329  factors_.push_back(factor);
330  }
331  slots.push_back(slot);
332  }
333 
334  gttoc(insert_factors);
335 
336  return slots;
337 }
338 
339 /* ************************************************************************* */
340 void ConcurrentBatchFilter::removeFactors(const std::vector<size_t>& slots) {
341 
342  gttic(remove_factors);
343 
344  // For each factor slot to delete...
345  for(size_t slot: slots) {
346 
347  // Remove the factor from the graph
348  factors_.remove(slot);
349 
350  // Mark the factor slot as available
351  availableSlots_.push(slot);
352  }
353 
354  gttoc(remove_factors);
355 }
356 
357 /* ************************************************************************* */
358 void ConcurrentBatchFilter::reorder(const std::optional<FastList<Key> >& keysToMove) {
359 
360  // COLAMD groups will be used to place marginalize keys in Group 0, and everything else in Group 1
361  if(keysToMove && keysToMove->size() > 0) {
362  ordering_ = Ordering::ColamdConstrainedFirst(factors_, KeyVector(keysToMove->begin(), keysToMove->end()));
363  }else{
365  }
366 
367 }
368 
369 /* ************************************************************************* */
371  VectorValues& delta, const Values& linearValues, const LevenbergMarquardtParams& parameters,
373 
374  // const bool debug = ISDEBUG("ConcurrentBatchFilter optimize");
375  const bool debug = false;
376 
377  if(debug) std::cout << "ConcurrentBatchFilter::optimize Begin" << std::endl;
378 
379  // Create output result structure
380  result.nonlinearVariables = theta.size() - linearValues.size();
381  result.linearVariables = linearValues.size();
382 
383  // Set optimization parameters
384  double lambda = parameters.lambdaInitial;
385  double lambdaFactor = parameters.lambdaFactor;
386  double lambdaUpperBound = parameters.lambdaUpperBound;
387  double lambdaLowerBound = 1.0e-10;
388  size_t maxIterations = parameters.maxIterations;
389  double relativeErrorTol = parameters.relativeErrorTol;
390  double absoluteErrorTol = parameters.absoluteErrorTol;
391  double errorTol = parameters.errorTol;
392 
393  // Create a Values that holds the current evaluation point
394  Values evalpoint = theta.retract(delta);
395  result.error = factors.error(evalpoint);
396 
397  // check if we're already close enough
398  if(result.error <= errorTol) {
399  if(debug) { std::cout << "Exiting, as error = " << result.error << " < " << errorTol << std::endl; }
400  }
401 
402  if(debug) {
403  std::cout << "linearValues: " << linearValues.size() << std::endl;
404  std::cout << "Initial error: " << result.error << std::endl;
405  }
406 
407  // Use a custom optimization loop so the linearization points can be controlled
408  double previousError;
409  VectorValues newDelta;
410  do {
411  previousError = result.error;
412 
413  // Do next iteration
414  gttic(optimizer_iteration);
415 
416  // Linearize graph around the linearization point
417  GaussianFactorGraph linearFactorGraph = *factors.linearize(theta);
418 
419  // Keep increasing lambda until we make make progress
420  while(true) {
421 
422  if(debug) { std::cout << "trying lambda = " << lambda << std::endl; }
423 
424  // Add prior factors at the current solution
425  gttic(damp);
426  GaussianFactorGraph dampedFactorGraph(linearFactorGraph);
427  dampedFactorGraph.reserve(linearFactorGraph.size() + delta.size());
428  double sigma = 1.0 / std::sqrt(lambda);
429 
430  // for each of the variables, add a prior at the current solution
431  for(const VectorValues::KeyValuePair& key_value: delta) {
432  size_t dim = key_value.second.size();
433  Matrix A = Matrix::Identity(dim,dim);
434  Vector b = key_value.second;
436  GaussianFactor::shared_ptr prior(new JacobianFactor(key_value.first, A, b, model));
437  dampedFactorGraph.push_back(prior);
438  }
439 
440  gttoc(damp);
441  result.lambdas++;
442 
443  gttic(solve);
444  // Solve Damped Gaussian Factor Graph
445  newDelta = dampedFactorGraph.optimize(ordering, parameters.getEliminationFunction());
446  // update the evalpoint with the new delta
447  evalpoint = theta.retract(newDelta);
448  gttoc(solve);
449 
450  // Evaluate the new nonlinear error
451  gttic(compute_error);
452  double error = factors.error(evalpoint);
453  gttoc(compute_error);
454 
455  if(debug) {
456  std::cout << "linear delta norm = " << newDelta.norm() << std::endl;
457  std::cout << "next error = " << error << std::endl;
458  }
459 
460  if(error < result.error) {
461  // Keep this change
462  // Update the error value
463  result.error = error;
464  // Update the linearization point
465  theta = evalpoint;
466  // Reset the deltas to zeros
467  delta.setZero();
468  // Put the linearization points and deltas back for specific variables
469  if(linearValues.size() > 0) {
470  theta.update(linearValues);
471  for(const auto key: linearValues.keys()) {
472  delta.at(key) = newDelta.at(key);
473  }
474  }
475 
476  // Decrease lambda for next time
477  lambda /= lambdaFactor;
478  if(lambda < lambdaLowerBound) {
479  lambda = lambdaLowerBound;
480  }
481  // End this lambda search iteration
482  break;
483  } else {
484  // Reject this change
485  if(lambda >= lambdaUpperBound) {
486  // The maximum lambda has been used. Print a warning and end the search.
487  std::cout << "Warning: Levenberg-Marquardt giving up because cannot decrease error with maximum lambda" << std::endl;
488  break;
489  } else {
490  // Increase lambda and continue searching
491  lambda *= lambdaFactor;
492  }
493  }
494  } // end while
495 
496  gttoc(optimizer_iteration);
497 
498  if(debug) { std::cout << "using lambda = " << lambda << std::endl; }
499 
500  result.iterations++;
501  } while(result.iterations < maxIterations &&
502  !checkConvergence(relativeErrorTol, absoluteErrorTol, errorTol, previousError, result.error, NonlinearOptimizerParams::SILENT));
503 
504  if(debug) { std::cout << "newError: " << result.error << std::endl; }
505 
506  if(debug) std::cout << "ConcurrentBatchFilter::optimize End" << std::endl;
507 }
508 
509 /* ************************************************************************* */
511  // In order to move the separator, we need to calculate the marginal information on the new
512  // separator from all of the factors on the smoother side (both the factors actually in the
513  // smoother and the ones to be transitioned to the smoother but stored in the filter).
514  // This is exactly the same operation that is performed by a fixed-lag smoother, calculating
515  // a marginal factor from the variables outside the smoother window.
516  //
517  // However, for the concurrent system, we would like to calculate this marginal in a particular
518  // way, such that an intermediate term is produced that provides a "shortcut" between the old
519  // separator (as defined in the smoother) and the new separator. This will allow us to quickly
520  // update the new separator with changes at the old separator (from the smoother)
521 
522  // TODO: This is currently not very efficient: multiple calls to graph.keys(), etc.
523 
524 // const bool debug = ISDEBUG("ConcurrentBatchFilter moveSeparator");
525  const bool debug = false;
526 
527  if(debug) std::cout << "ConcurrentBatchFilter::moveSeparator Begin" << std::endl;
528 
529  if(debug) { PrintKeys(keysToMove, "ConcurrentBatchFilter::moveSeparator ", "Keys To Move:", DefaultKeyFormatter); }
530 
531 
532  // Identify all of the new factors to be sent to the smoother (any factor involving keysToMove)
533  std::vector<size_t> removedFactorSlots;
534  VariableIndex variableIndex(factors_);
535  for(Key key: keysToMove) {
536  const auto& slots = variableIndex[key];
537  removedFactorSlots.insert(removedFactorSlots.end(), slots.begin(), slots.end());
538  }
539 
540  // Sort and remove duplicates
541  std::sort(removedFactorSlots.begin(), removedFactorSlots.end());
542  removedFactorSlots.erase(std::unique(removedFactorSlots.begin(), removedFactorSlots.end()), removedFactorSlots.end());
543  // Remove any linear/marginal factor that made it into the set
544  for(size_t index: separatorSummarizationSlots_) {
545  removedFactorSlots.erase(std::remove(removedFactorSlots.begin(), removedFactorSlots.end(), index), removedFactorSlots.end());
546  }
547 
548  // TODO: Make this compact
549  if(debug) {
550  std::cout << "ConcurrentBatchFilter::moveSeparator Removed Factor Slots: ";
551  for(size_t slot: removedFactorSlots) {
552  std::cout << slot << " ";
553  }
554  std::cout << std::endl;
555  }
556 
557  // Add these factors to a factor graph
558  NonlinearFactorGraph removedFactors;
559  for(size_t slot: removedFactorSlots) {
560  if(factors_.at(slot)) {
561  removedFactors.push_back(factors_.at(slot));
562  }
563  }
564 
565  if(debug) {
566  PrintNonlinearFactorGraph(removedFactors, "ConcurrentBatchFilter::synchronize ", "Removed Factors:", DefaultKeyFormatter);
567  PrintNonlinearFactorGraph(smootherShortcut_, "ConcurrentBatchFilter::synchronize ", "Old Shortcut:", DefaultKeyFormatter);
568  PrintKeys(smootherShortcut_.keys(), "ConcurrentBatchFilter::moveSeparator ", "Old Shortcut Keys:", DefaultKeyFormatter);
569  PrintKeys(separatorValues_.keys(), "ConcurrentBatchFilter::moveSeparator ", "Previous Separator Keys:", DefaultKeyFormatter);
570  }
571 
572  // Calculate the set of new separator keys: AffectedKeys + PreviousSeparatorKeys - KeysToMove
573  KeySet newSeparatorKeys = removedFactors.keys();
574  newSeparatorKeys.merge(separatorValues_.keySet());
575  for(Key key: keysToMove) {
576  newSeparatorKeys.erase(key);
577  }
578 
579  if(debug) { PrintKeys(newSeparatorKeys, "ConcurrentBatchFilter::synchronize ", "New Separator Keys:", DefaultKeyFormatter); }
580 
581  // Calculate the set of shortcut keys: NewSeparatorKeys + OldSeparatorKeys
582  KeySet shortcutKeys = newSeparatorKeys;
584  shortcutKeys.insert(key);
585  }
586 
587  if(debug) { PrintKeys(shortcutKeys, "ConcurrentBatchFilter::moveSeparator ", "Old Shortcut Keys:", DefaultKeyFormatter); }
588 
589  // Calculate a new shortcut
590  {
591  // Combine the previous shortcut factor with all of the new factors being sent to the smoother
593  graph.push_back(removedFactors);
595  Values values;
596  values.insert(smootherValues_);
597  values.insert(theta_);
598  // Calculate the summarized factor on the shortcut keys
600  }
601 
602  if(debug) {
603  PrintNonlinearFactorGraph(smootherShortcut_, "ConcurrentBatchFilter::synchronize ", "New Shortcut:", DefaultKeyFormatter);
604  PrintNonlinearFactorGraph(smootherSummarization_, "ConcurrentBatchFilter::synchronize ", "Smoother Summarization:", DefaultKeyFormatter);
605  PrintNonlinearFactorGraph(factors_, separatorSummarizationSlots_, "ConcurrentBatchFilter::synchronize ", "Current Separator Summarization:", DefaultKeyFormatter);
606  }
607 
608  // Calculate the new smoother summarization on the new separator using the shortcut
609  NonlinearFactorGraph separatorSummarization;
610  {
611  // Combine just the shortcut and the previousSmootherSummarization
615  Values values;
616  values.insert(smootherValues_);
617  values.insert(theta_);
618  // Calculate the summarized factor on just the new separator
619  separatorSummarization = internal::calculateMarginalFactors(graph, values, newSeparatorKeys, parameters_.getEliminationFunction());
620  }
621 
622  // Remove the previous marginal factors and insert the new marginal factors
623  removeFactors(separatorSummarizationSlots_);
624  separatorSummarizationSlots_ = insertFactors(separatorSummarization);
625 
626  if(debug) { PrintNonlinearFactorGraph(factors_, separatorSummarizationSlots_, "ConcurrentBatchFilter::synchronize ", "New Separator Summarization:", DefaultKeyFormatter); }
627 
628  // Update the separatorValues object (should only contain the new separator keys)
630  for(Key key: separatorSummarization.keys()) {
632  }
633 
634  // Remove the marginalized factors and add them to the smoother cache
635  smootherFactors_.push_back(removedFactors);
636  removeFactors(removedFactorSlots);
637 
638  // Add the linearization point of the moved variables to the smoother cache
639  for(Key key: keysToMove) {
641  }
642 
643  // Remove marginalized keys from values (and separator)
644  for(Key key: keysToMove) {
645  theta_.erase(key);
646  ordering_.erase(std::find(ordering_.begin(), ordering_.end(), key));
647  delta_.erase(key);
648  }
649 
650  if(debug) std::cout << "ConcurrentBatchFilter::moveSeparator End" << std::endl;
651 }
652 
653 /* ************************************************************************* */
654 }
bool equals(const ConcurrentFilter &rhs, double tol=1e-9) const override
const gtsam::Symbol key('X', 0)
void clear()
Definition: Values.h:298
static void optimize(const NonlinearFactorGraph &factors, Values &theta, const Ordering &ordering, VectorValues &delta, const Values &linearValues, const LevenbergMarquardtParams &parameters, Result &result)
A Levenberg-Marquardt Batch Filter that implements the Concurrent Filtering and Smoothing interface...
KeySet keys() const
void replace(size_t index, sharedFactor factor)
Definition: FactorGraph.h:396
NonlinearFactorGraph smootherSummarization_
The smoother summarization on the old separator sent by the smoother during the last synchronization...
Wrap Jacobian and Hessian linear factors to allow simple injection into a nonlinear graph...
Global debugging flags.
double error
The final factor graph error.
std::shared_ptr< This > shared_ptr
A shared_ptr to this class.
Point2 prior(const Point2 &x)
Prior on a single pose.
Definition: simulated2D.h:88
noiseModel::Diagonal::shared_ptr model
const ValueType at(Key j) const
Definition: Values-inl.h:204
void moveSeparator(const FastList< Key > &keysToMove)
IsDerived< DERIVEDFACTOR > push_back(std::shared_ptr< DERIVEDFACTOR > factor)
Add a factor directly using a shared_ptr.
Definition: FactorGraph.h:190
double lambdaFactor
The amount by which to multiply or divide lambda when adjusting lambda (default: 10.0)
void removeFactors(const std::vector< size_t > &slots)
Values separatorValues_
The linearization points of the separator variables. These should not be updated during optimization...
Eigen::MatrixXd Matrix
Definition: base/Matrix.h:39
leaf::MyValues values
KeyVector keys() const
Definition: Values.cpp:218
const GaussianFactorGraph factors
void update(Key j, const Value &val)
Definition: Values.cpp:169
virtual Result update(const NonlinearFactorGraph &newFactors=NonlinearFactorGraph(), const Values &newTheta=Values(), const std::optional< FastList< Key > > &keysToMove={}, const std::optional< std::vector< size_t > > &removeFactorIndices={})
void remove(size_t i)
Definition: FactorGraph.h:393
iterator insert(const std::pair< Key, Vector > &key_value)
void merge(const FastSet &other)
Definition: FastSet.h:121
std::queue< size_t > availableSlots_
The set of available factor graph slots caused by deleting factors.
size_t lambdas
The number of different L-M lambda factors that were tried during optimization.
Vector & at(Key j)
Definition: VectorValues.h:139
NonlinearFactorGraph graph
static const KeyFormatter DefaultKeyFormatter
Definition: Key.h:43
static enum @1107 ordering
double absoluteErrorTol
The maximum absolute error decrease to stop iterating (default 1e-5)
VectorValues optimize(const Eliminate &function=EliminationTraitsType::DefaultEliminate) const
static constexpr bool debug
Values retract(const VectorValues &delta) const
Definition: Values.cpp:98
std::shared_ptr< GaussianFactorGraph > linearize(const Values &linearizationPoint) const
Linearize a nonlinear factor graph.
static Ordering Colamd(const FACTOR_GRAPH &graph)
double relativeErrorTol
The maximum relative error decrease to stop iterating (default 1e-5)
bool checkConvergence(double relativeErrorTreshold, double absoluteErrorTreshold, double errorThreshold, double currentError, double newError, NonlinearOptimizerParams::Verbosity verbosity)
static void PrintLinearFactor(const GaussianFactor::shared_ptr &factor, const std::string &indent="", const KeyFormatter &keyFormatter=DefaultKeyFormatter)
static void PrintKeys(const Container &keys, const std::string &indent, const std::string &title, const KeyFormatter &keyFormatter=DefaultKeyFormatter)
Implementation of PrintKeys.
double errorTol
The maximum total error to stop iterating (default 0.0)
size_t size() const
Definition: FactorGraph.h:334
#define gttic(label)
Definition: timing.h:295
bool equals(const VectorValues &x, double tol=1e-9) const
Eigen::VectorXd Vector
Definition: Vector.h:38
Values result
VectorValues zeroVectors() const
Definition: Values.cpp:260
NonlinearFactorGraph smootherShortcut_
A set of conditional factors from the old separator to the current separator (recursively calculated ...
NonlinearFactorGraph calculateMarginalFactors(const NonlinearFactorGraph &graph, const Values &theta, const KeySet &remainingKeys, const GaussianFactorGraph::Eliminate &eliminateFunction)
size_t linearVariables
The number of variables that must keep a constant linearization point.
size_t nonlinearVariables
The number of variables that can be relinearized.
RealScalar s
static Ordering ColamdConstrainedFirst(const FACTOR_GRAPH &graph, const KeyVector &constrainFirst, bool forceOrder=false)
size_t size() const
Definition: Values.h:178
value_type KeyValuePair
Typedef to pair<Key, Vector>
Definition: VectorValues.h:85
bool equals(const Values &other, double tol=1e-9) const
Definition: Values.cpp:77
LevenbergMarquardtParams parameters_
LM parameters.
bool equals(const NonlinearFactorGraph &other, double tol=1e-9) const
std::shared_ptr< This > shared_ptr
shared_ptr to this class
double error(const Values &values) const
Values theta_
Current linearization point of all variables in the filter.
std::function< std::string(Key)> KeyFormatter
Typedef for a function to format a key, i.e. to convert it to a string.
Definition: Key.h:35
const G & b
Definition: Group.h:86
void reorder(const std::optional< FastList< Key > > &keysToMove={})
static ConjugateGradientParameters parameters
GaussianFactorGraph::Eliminate getEliminationFunction() const
std::shared_ptr< This > shared_ptr
shared_ptr to this class
cout<< "The eigenvalues of A are:"<< endl<< ces.eigenvalues()<< endl;cout<< "The matrix of eigenvectors, V, is:"<< endl<< ces.eigenvectors()<< endl<< endl;complex< float > lambda
size_t iterations
The number of optimizer iterations performed.
noiseModel::Diagonal::shared_ptr SharedDiagonal
Definition: NoiseModel.h:743
traits
Definition: chartTesting.h:28
GTSAM_EXPORT bool equals(const Ordering &other, double tol=1e-9) const
Definition: Ordering.cpp:296
static void PrintNonlinearFactorGraph(const NonlinearFactorGraph &factors, const std::string &indent="", const std::string &title="", const KeyFormatter &keyFormatter=DefaultKeyFormatter)
NonlinearFactorGraph smootherFactors_
A temporary holding place for the set of full nonlinear factors being sent to the smoother...
virtual void resize(size_t size)
Definition: FactorGraph.h:389
VectorValues delta_
The current set of linear deltas from the linearization point.
#define gttoc(label)
Definition: timing.h:296
const sharedFactor at(size_t i) const
Definition: FactorGraph.h:343
std::shared_ptr< This > shared_ptr
double norm() const
Ordering ordering_
The current ordering used to calculate the linear deltas.
void erase(Key var)
Definition: VectorValues.h:226
A Gaussian factor using the canonical parameters (information form)
static const double sigma
size_t size() const
Definition: VectorValues.h:127
void print(const std::string &s="Concurrent Batch Filter:\, const KeyFormatter &keyFormatter=DefaultKeyFormatter) const override
void insert(Key j, const Value &val)
Definition: Values.cpp:155
static double error
Definition: testRot3.cpp:37
void reserve(size_t size)
Definition: FactorGraph.h:186
NonlinearFactorGraph factors_
The set of all factors currently in the filter.
void getSmootherFactors(NonlinearFactorGraph &smootherFactors, Values &smootherValues) override
Jet< T, N > sqrt(const Jet< T, N > &f)
Definition: jet.h:418
const G double tol
Definition: Group.h:86
NonlinearFactorGraph filterSummarization_
A temporary holding place for calculated filter summarization factors to be sent to the smoother...
double lambdaUpperBound
The maximum lambda to try before assuming the optimization has failed (default: 1e5) ...
std::vector< size_t > separatorSummarizationSlots_
The slots in factor graph that correspond to the current smoother summarization on the current separa...
FastVector< Key > KeyVector
Define collection type once and for all - also used in wrappers.
Definition: Key.h:86
void synchronize(const NonlinearFactorGraph &smootherSummarization, const Values &smootherSummarizationValues) override
void erase(Key j)
Definition: Values.cpp:210
void getSummarizedFactors(NonlinearFactorGraph &filterSummarization, Values &filterSummarizationValues) override
bool exists(Key j) const
Definition: Values.cpp:93
bool equal(const T &obj1, const T &obj2, double tol)
Definition: Testable.h:85
std::uint64_t Key
Integer nonlinear key type.
Definition: types.h:102
KeySet keySet() const
Definition: Values.cpp:227
static void PrintLinearFactorGraph(const GaussianFactorGraph &factors, const std::string &indent="", const std::string &title="", const KeyFormatter &keyFormatter=DefaultKeyFormatter)
Timing utilities.
static void PrintNonlinearFactor(const NonlinearFactor::shared_ptr &factor, const std::string &indent="", const KeyFormatter &keyFormatter=DefaultKeyFormatter)
size_t maxIterations
The maximum iterations to stop iterating (default 100)
static shared_ptr Sigma(size_t dim, double sigma, bool smart=true)
Definition: NoiseModel.cpp:594
double lambdaInitial
The initial Levenberg-Marquardt damping term (default: 1e-5)
Values smootherValues_
A temporary holding place for the linearization points of all keys being sent to the smoother...
std::vector< size_t > insertFactors(const NonlinearFactorGraph &factors)


gtsam
Author(s):
autogenerated on Tue Jul 4 2023 02:34:03