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(boost::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 = boost::dynamic_pointer_cast<JacobianFactor>(factor);
69  HessianFactor::shared_ptr hf = boost::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 boost::optional<FastList<Key> >& keysToMove, const boost::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_value: newTheta) {
143  ordering_.push_back(key_value.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  KeySet newSeparatorKeys;
225  for(const auto key_value: separatorValues_) {
226  newSeparatorKeys.insert(key_value.key);
227  }
228 
229  if(debug) { PrintKeys(newSeparatorKeys, "ConcurrentBatchFilter::synchronize ", "Current Separator Keys:"); }
230 
231  // Use the shortcut to calculate an updated marginal on the current separator
232  {
233  // Combine just the shortcut and the previousSmootherSummarization
237  Values values;
238  values.insert(smootherSummarizationValues);
239  for(const auto key_value: separatorValues_) {
240  if(!values.exists(key_value.key)) {
241  values.insert(key_value.key, key_value.value);
242  }
243  }
244  // Calculate the summarized factor on just the new separator keys
246 
247  // Remove the old factors on the separator and insert new
250 
251  // Clear the smoother shortcut
253  }
254 
255  if(debug) { PrintNonlinearFactorGraph(factors_, separatorSummarizationSlots_, "ConcurrentBatchFilter::synchronize ", "Current Separator Summarization:", DefaultKeyFormatter); }
256 
257  // Calculate the marginal on the new separator from the filter factors
258  // Note: This could also be done during each filter update so it would simply be available
259  {
260  // Calculate the summarized factor on just the new separator keys (from the filter side)
261  // Copy all of the factors from the filter, not including the smoother summarization
263  for(size_t slot = 0; slot < factors_.size(); ++slot) {
264  if(factors_.at(slot) && std::find(separatorSummarizationSlots_.begin(), separatorSummarizationSlots_.end(), slot) == separatorSummarizationSlots_.end()) {
265  factors.push_back(factors_.at(slot));
266  }
267  }
269  }
270 
271  if(debug) { PrintNonlinearFactorGraph(filterSummarization_, "ConcurrentBatchFilter::synchronize ", "Updated Filter Summarization:", DefaultKeyFormatter); }
272 
273  if(debug) std::cout << "ConcurrentBatchFilter::synchronize End" << std::endl;
274 
276 }
277 
278 /* ************************************************************************* */
279 void ConcurrentBatchFilter::getSummarizedFactors(NonlinearFactorGraph& filterSummarization, Values& filterSummarizationValues) {
280 
281  gttic(get_summarized_factors);
282 
283  // Copy the previous calculated smoother summarization factors into the output
284  filterSummarization.push_back(filterSummarization_);
285  filterSummarizationValues.insert(separatorValues_);
286 
287  gttoc(get_summarized_factors);
288 }
289 
290 /* ************************************************************************* */
292 
293  gttic(get_smoother_factors);
294 
295  // Copy the previous calculated smoother summarization factors into the output
296  smootherFactors.push_back(smootherFactors_);
297  smootherValues.insert(smootherValues_);
298 
299  gttoc(get_smoother_factors);
300 }
301 
302 /* ************************************************************************* */
304 
305  gttic(postsync);
306 
307  // Clear out the factors and values that were just sent to the smoother
310 
311  gttoc(postsync);
312 }
313 
314 /* ************************************************************************* */
316 
317  gttic(insert_factors);
318 
319  // create the output vector
320  std::vector<size_t> slots;
321  slots.reserve(factors.size());
322 
323  // Insert the factor into an existing hole in the factor graph, if possible
324  for(const NonlinearFactor::shared_ptr& factor: factors) {
325  size_t slot;
326  if(availableSlots_.size() > 0) {
327  slot = availableSlots_.front();
328  availableSlots_.pop();
329  factors_.replace(slot, factor);
330  } else {
331  slot = factors_.size();
332  factors_.push_back(factor);
333  }
334  slots.push_back(slot);
335  }
336 
337  gttoc(insert_factors);
338 
339  return slots;
340 }
341 
342 /* ************************************************************************* */
343 void ConcurrentBatchFilter::removeFactors(const std::vector<size_t>& slots) {
344 
345  gttic(remove_factors);
346 
347  // For each factor slot to delete...
348  for(size_t slot: slots) {
349 
350  // Remove the factor from the graph
351  factors_.remove(slot);
352 
353  // Mark the factor slot as available
354  availableSlots_.push(slot);
355  }
356 
357  gttoc(remove_factors);
358 }
359 
360 /* ************************************************************************* */
361 void ConcurrentBatchFilter::reorder(const boost::optional<FastList<Key> >& keysToMove) {
362 
363  // COLAMD groups will be used to place marginalize keys in Group 0, and everything else in Group 1
364  if(keysToMove && keysToMove->size() > 0) {
365  ordering_ = Ordering::ColamdConstrainedFirst(factors_, KeyVector(keysToMove->begin(), keysToMove->end()));
366  }else{
368  }
369 
370 }
371 
372 /* ************************************************************************* */
374  VectorValues& delta, const Values& linearValues, const LevenbergMarquardtParams& parameters,
376 
377  // const bool debug = ISDEBUG("ConcurrentBatchFilter optimize");
378  const bool debug = false;
379 
380  if(debug) std::cout << "ConcurrentBatchFilter::optimize Begin" << std::endl;
381 
382  // Create output result structure
383  result.nonlinearVariables = theta.size() - linearValues.size();
384  result.linearVariables = linearValues.size();
385 
386  // Set optimization parameters
387  double lambda = parameters.lambdaInitial;
388  double lambdaFactor = parameters.lambdaFactor;
389  double lambdaUpperBound = parameters.lambdaUpperBound;
390  double lambdaLowerBound = 1.0e-10;
391  size_t maxIterations = parameters.maxIterations;
392  double relativeErrorTol = parameters.relativeErrorTol;
393  double absoluteErrorTol = parameters.absoluteErrorTol;
394  double errorTol = parameters.errorTol;
395 
396  // Create a Values that holds the current evaluation point
397  Values evalpoint = theta.retract(delta);
398  result.error = factors.error(evalpoint);
399 
400  // check if we're already close enough
401  if(result.error <= errorTol) {
402  if(debug) { std::cout << "Exiting, as error = " << result.error << " < " << errorTol << std::endl; }
403  }
404 
405  if(debug) {
406  std::cout << "linearValues: " << linearValues.size() << std::endl;
407  std::cout << "Initial error: " << result.error << std::endl;
408  }
409 
410  // Use a custom optimization loop so the linearization points can be controlled
411  double previousError;
412  VectorValues newDelta;
413  do {
414  previousError = result.error;
415 
416  // Do next iteration
417  gttic(optimizer_iteration);
418 
419  // Linearize graph around the linearization point
420  GaussianFactorGraph linearFactorGraph = *factors.linearize(theta);
421 
422  // Keep increasing lambda until we make make progress
423  while(true) {
424 
425  if(debug) { std::cout << "trying lambda = " << lambda << std::endl; }
426 
427  // Add prior factors at the current solution
428  gttic(damp);
429  GaussianFactorGraph dampedFactorGraph(linearFactorGraph);
430  dampedFactorGraph.reserve(linearFactorGraph.size() + delta.size());
431  double sigma = 1.0 / std::sqrt(lambda);
432 
433  // for each of the variables, add a prior at the current solution
434  for(const VectorValues::KeyValuePair& key_value: delta) {
435  size_t dim = key_value.second.size();
436  Matrix A = Matrix::Identity(dim,dim);
437  Vector b = key_value.second;
439  GaussianFactor::shared_ptr prior(new JacobianFactor(key_value.first, A, b, model));
440  dampedFactorGraph.push_back(prior);
441  }
442 
443  gttoc(damp);
444  result.lambdas++;
445 
446  gttic(solve);
447  // Solve Damped Gaussian Factor Graph
448  newDelta = dampedFactorGraph.optimize(ordering, parameters.getEliminationFunction());
449  // update the evalpoint with the new delta
450  evalpoint = theta.retract(newDelta);
451  gttoc(solve);
452 
453  // Evaluate the new nonlinear error
454  gttic(compute_error);
455  double error = factors.error(evalpoint);
456  gttoc(compute_error);
457 
458  if(debug) {
459  std::cout << "linear delta norm = " << newDelta.norm() << std::endl;
460  std::cout << "next error = " << error << std::endl;
461  }
462 
463  if(error < result.error) {
464  // Keep this change
465  // Update the error value
466  result.error = error;
467  // Update the linearization point
468  theta = evalpoint;
469  // Reset the deltas to zeros
470  delta.setZero();
471  // Put the linearization points and deltas back for specific variables
472  if(linearValues.size() > 0) {
473  theta.update(linearValues);
474  for(const auto key_value: linearValues) {
475  delta.at(key_value.key) = newDelta.at(key_value.key);
476  }
477  }
478 
479  // Decrease lambda for next time
480  lambda /= lambdaFactor;
481  if(lambda < lambdaLowerBound) {
482  lambda = lambdaLowerBound;
483  }
484  // End this lambda search iteration
485  break;
486  } else {
487  // Reject this change
488  if(lambda >= lambdaUpperBound) {
489  // The maximum lambda has been used. Print a warning and end the search.
490  std::cout << "Warning: Levenberg-Marquardt giving up because cannot decrease error with maximum lambda" << std::endl;
491  break;
492  } else {
493  // Increase lambda and continue searching
494  lambda *= lambdaFactor;
495  }
496  }
497  } // end while
498 
499  gttoc(optimizer_iteration);
500 
501  if(debug) { std::cout << "using lambda = " << lambda << std::endl; }
502 
503  result.iterations++;
504  } while(result.iterations < maxIterations &&
505  !checkConvergence(relativeErrorTol, absoluteErrorTol, errorTol, previousError, result.error, NonlinearOptimizerParams::SILENT));
506 
507  if(debug) { std::cout << "newError: " << result.error << std::endl; }
508 
509  if(debug) std::cout << "ConcurrentBatchFilter::optimize End" << std::endl;
510 }
511 
512 /* ************************************************************************* */
514  // In order to move the separator, we need to calculate the marginal information on the new
515  // separator from all of the factors on the smoother side (both the factors actually in the
516  // smoother and the ones to be transitioned to the smoother but stored in the filter).
517  // This is exactly the same operation that is performed by a fixed-lag smoother, calculating
518  // a marginal factor from the variables outside the smoother window.
519  //
520  // However, for the concurrent system, we would like to calculate this marginal in a particular
521  // way, such that an intermediate term is produced that provides a "shortcut" between the old
522  // separator (as defined in the smoother) and the new separator. This will allow us to quickly
523  // update the new separator with changes at the old separator (from the smoother)
524 
525  // TODO: This is currently not very efficient: multiple calls to graph.keys(), etc.
526 
527 // const bool debug = ISDEBUG("ConcurrentBatchFilter moveSeparator");
528  const bool debug = false;
529 
530  if(debug) std::cout << "ConcurrentBatchFilter::moveSeparator Begin" << std::endl;
531 
532  if(debug) { PrintKeys(keysToMove, "ConcurrentBatchFilter::moveSeparator ", "Keys To Move:", DefaultKeyFormatter); }
533 
534 
535  // Identify all of the new factors to be sent to the smoother (any factor involving keysToMove)
536  std::vector<size_t> removedFactorSlots;
537  VariableIndex variableIndex(factors_);
538  for(Key key: keysToMove) {
539  const auto& slots = variableIndex[key];
540  removedFactorSlots.insert(removedFactorSlots.end(), slots.begin(), slots.end());
541  }
542 
543  // Sort and remove duplicates
544  std::sort(removedFactorSlots.begin(), removedFactorSlots.end());
545  removedFactorSlots.erase(std::unique(removedFactorSlots.begin(), removedFactorSlots.end()), removedFactorSlots.end());
546  // Remove any linear/marginal factor that made it into the set
547  for(size_t index: separatorSummarizationSlots_) {
548  removedFactorSlots.erase(std::remove(removedFactorSlots.begin(), removedFactorSlots.end(), index), removedFactorSlots.end());
549  }
550 
551  // TODO: Make this compact
552  if(debug) {
553  std::cout << "ConcurrentBatchFilter::moveSeparator Removed Factor Slots: ";
554  for(size_t slot: removedFactorSlots) {
555  std::cout << slot << " ";
556  }
557  std::cout << std::endl;
558  }
559 
560  // Add these factors to a factor graph
561  NonlinearFactorGraph removedFactors;
562  for(size_t slot: removedFactorSlots) {
563  if(factors_.at(slot)) {
564  removedFactors.push_back(factors_.at(slot));
565  }
566  }
567 
568  if(debug) {
569  PrintNonlinearFactorGraph(removedFactors, "ConcurrentBatchFilter::synchronize ", "Removed Factors:", DefaultKeyFormatter);
570  PrintNonlinearFactorGraph(smootherShortcut_, "ConcurrentBatchFilter::synchronize ", "Old Shortcut:", DefaultKeyFormatter);
571  PrintKeys(smootherShortcut_.keys(), "ConcurrentBatchFilter::moveSeparator ", "Old Shortcut Keys:", DefaultKeyFormatter);
572  PrintKeys(separatorValues_.keys(), "ConcurrentBatchFilter::moveSeparator ", "Previous Separator Keys:", DefaultKeyFormatter);
573  }
574 
575  // Calculate the set of new separator keys: AffectedKeys + PreviousSeparatorKeys - KeysToMove
576  KeySet newSeparatorKeys = removedFactors.keys();
577  for(const auto key_value: separatorValues_) {
578  newSeparatorKeys.insert(key_value.key);
579  }
580  for(Key key: keysToMove) {
581  newSeparatorKeys.erase(key);
582  }
583 
584  if(debug) { PrintKeys(newSeparatorKeys, "ConcurrentBatchFilter::synchronize ", "New Separator Keys:", DefaultKeyFormatter); }
585 
586  // Calculate the set of shortcut keys: NewSeparatorKeys + OldSeparatorKeys
587  KeySet shortcutKeys = newSeparatorKeys;
589  shortcutKeys.insert(key);
590  }
591 
592  if(debug) { PrintKeys(shortcutKeys, "ConcurrentBatchFilter::moveSeparator ", "Old Shortcut Keys:", DefaultKeyFormatter); }
593 
594  // Calculate a new shortcut
595  {
596  // Combine the previous shortcut factor with all of the new factors being sent to the smoother
598  graph.push_back(removedFactors);
600  Values values;
601  values.insert(smootherValues_);
602  values.insert(theta_);
603  // Calculate the summarized factor on the shortcut keys
605  }
606 
607  if(debug) {
608  PrintNonlinearFactorGraph(smootherShortcut_, "ConcurrentBatchFilter::synchronize ", "New Shortcut:", DefaultKeyFormatter);
609  PrintNonlinearFactorGraph(smootherSummarization_, "ConcurrentBatchFilter::synchronize ", "Smoother Summarization:", DefaultKeyFormatter);
610  PrintNonlinearFactorGraph(factors_, separatorSummarizationSlots_, "ConcurrentBatchFilter::synchronize ", "Current Separator Summarization:", DefaultKeyFormatter);
611  }
612 
613  // Calculate the new smoother summarization on the new separator using the shortcut
614  NonlinearFactorGraph separatorSummarization;
615  {
616  // Combine just the shortcut and the previousSmootherSummarization
620  Values values;
621  values.insert(smootherValues_);
622  values.insert(theta_);
623  // Calculate the summarized factor on just the new separator
624  separatorSummarization = internal::calculateMarginalFactors(graph, values, newSeparatorKeys, parameters_.getEliminationFunction());
625  }
626 
627  // Remove the previous marginal factors and insert the new marginal factors
628  removeFactors(separatorSummarizationSlots_);
629  separatorSummarizationSlots_ = insertFactors(separatorSummarization);
630 
631  if(debug) { PrintNonlinearFactorGraph(factors_, separatorSummarizationSlots_, "ConcurrentBatchFilter::synchronize ", "New Separator Summarization:", DefaultKeyFormatter); }
632 
633  // Update the separatorValues object (should only contain the new separator keys)
634  separatorValues_.clear();
635  for(Key key: separatorSummarization.keys()) {
636  separatorValues_.insert(key, theta_.at(key));
637  }
638 
639  // Remove the marginalized factors and add them to the smoother cache
640  smootherFactors_.push_back(removedFactors);
641  removeFactors(removedFactorSlots);
642 
643  // Add the linearization point of the moved variables to the smoother cache
644  for(Key key: keysToMove) {
646  }
647 
648  // Remove marginalized keys from values (and separator)
649  for(Key key: keysToMove) {
650  theta_.erase(key);
651  ordering_.erase(std::find(ordering_.begin(), ordering_.end(), key));
652  delta_.erase(key);
653  }
654 
655  if(debug) std::cout << "ConcurrentBatchFilter::moveSeparator End" << std::endl;
656 }
657 
658 /* ************************************************************************* */
659 }
bool equals(const ConcurrentFilter &rhs, double tol=1e-9) const override
size_t size() const
Definition: FactorGraph.h:306
void clear()
Definition: Values.h:311
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...
void replace(size_t index, sharedFactor factor)
Definition: FactorGraph.h:365
bool exists(Key j) const
Definition: Values.cpp:104
double norm() const
VectorValues optimize(const Eliminate &function=EliminationTraitsType::DefaultEliminate) const
NonlinearFactorGraph smootherSummarization_
The smoother summarization on the old separator sent by the smoother during the last synchronization...
GTSAM_EXPORT bool equals(const Ordering &other, double tol=1e-9) const
Definition: Ordering.cpp:287
Wrap Jacobian and Hessian linear factors to allow simple injection into a nonlinear graph...
Global debugging flags.
double error
The final factor graph error.
Point2 prior(const Point2 &x)
Prior on a single pose.
Definition: simulated2D.h:87
noiseModel::Diagonal::shared_ptr model
void insert(Key j, const Value &val)
Definition: Values.cpp:140
static enum @843 ordering
void moveSeparator(const FastList< Key > &keysToMove)
double lambdaFactor
The amount by which to multiply or divide lambda when adjusting lambda (default: 10.0)
KeySet keys() const
static const double sigma
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:43
leaf::MyValues values
EIGEN_DEVICE_FUNC const SqrtReturnType sqrt() const
size_t size() const
Definition: VectorValues.h:125
GaussianFactorGraph factors(list_of(factor1)(factor2)(factor3))
void remove(size_t i)
Definition: FactorGraph.h:362
Values retract(const VectorValues &delta) const
Definition: Values.cpp:109
std::queue< size_t > availableSlots_
The set of available factor graph slots caused by deleting factors.
IsDerived< DERIVEDFACTOR > push_back(boost::shared_ptr< DERIVEDFACTOR > factor)
Add a factor directly using a shared_ptr.
Definition: FactorGraph.h:166
size_t lambdas
The number of different L-M lambda factors that were tried during optimization.
Vector & at(Key j)
Definition: VectorValues.h:137
Rot2 theta
NonlinearFactorGraph graph
KeyVector keys() const
Definition: Values.cpp:191
static const KeyFormatter DefaultKeyFormatter
Definition: Key.h:43
bool equals(const Values &other, double tol=1e-9) const
Definition: Values.cpp:88
double absoluteErrorTol
The maximum absolute error decrease to stop iterating (default 1e-5)
static Ordering Colamd(const FACTOR_GRAPH &graph)
double relativeErrorTol
The maximum relative error decrease to stop iterating (default 1e-5)
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)
bool equals(const NonlinearFactorGraph &other, double tol=1e-9) const
#define gttic(label)
Definition: timing.h:280
FastVector< Key > KeyVector
Define collection type once and for all - also used in wrappers.
Definition: Key.h:86
bool checkConvergence(double relativeErrorTreshold, double absoluteErrorTreshold, double errorThreshold, double currentError, double newError, NonlinearOptimizerParams::Verbosity verbosity)
Eigen::VectorXd Vector
Definition: Vector.h:38
size_t size() const
Definition: Values.h:236
Values result
const ValueType at(Key j) const
Definition: Values-inl.h:342
virtual Result update(const NonlinearFactorGraph &newFactors=NonlinearFactorGraph(), const Values &newTheta=Values(), const boost::optional< FastList< Key > > &keysToMove=boost::none, const boost::optional< std::vector< size_t > > &removeFactorIndices=boost::none)
void print(const std::string &s="Concurrent Batch Filter:\n", const KeyFormatter &keyFormatter=DefaultKeyFormatter) const override
boost::shared_ptr< This > shared_ptr
boost::shared_ptr< This > shared_ptr
A shared_ptr to this class.
GaussianFactorGraph::Eliminate getEliminationFunction() const
void reorder(const boost::optional< FastList< Key > > &keysToMove=boost::none)
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
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.
static bool debug
size_t nonlinearVariables
The number of variables that can be relinearized.
RealScalar s
void erase(Key j)
Definition: Values.cpp:183
static Ordering ColamdConstrainedFirst(const FACTOR_GRAPH &graph, const KeyVector &constrainFirst, bool forceOrder=false)
bool equals(const VectorValues &x, double tol=1e-9) const
value_type KeyValuePair
Typedef to pair<Key, Vector>
Definition: VectorValues.h:85
LevenbergMarquardtParams parameters_
LM parameters.
Values theta_
Current linearization point of all variables in the filter.
const G & b
Definition: Group.h:83
boost::shared_ptr< This > shared_ptr
shared_ptr to this class
static ConjugateGradientParameters parameters
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.
const mpreal dim(const mpreal &a, const mpreal &b, mp_rnd_t r=mpreal::get_default_rnd())
Definition: mpreal.h:2201
noiseModel::Diagonal::shared_ptr SharedDiagonal
Definition: NoiseModel.h:736
traits
Definition: chartTesting.h:28
const sharedFactor at(size_t i) const
Definition: FactorGraph.h:315
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...
VectorValues delta_
The current set of linear deltas from the linearization point.
#define gttoc(label)
Definition: timing.h:281
Ordering ordering_
The current ordering used to calculate the linear deltas.
void erase(Key var)
Definition: VectorValues.h:216
A Gaussian factor using the canonical parameters (information form)
void resize(size_t size)
Definition: FactorGraph.h:358
static double error
Definition: testRot3.cpp:39
void update(Key j, const Value &val)
Definition: Values.cpp:161
void reserve(size_t size)
Definition: FactorGraph.h:162
NonlinearFactorGraph factors_
The set of all factors currently in the filter.
void getSmootherFactors(NonlinearFactorGraph &smootherFactors, Values &smootherValues) override
const G double tol
Definition: Group.h:83
double error(const Values &values) const
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...
boost::shared_ptr< This > shared_ptr
shared_ptr to this class
void synchronize(const NonlinearFactorGraph &smootherSummarization, const Values &smootherSummarizationValues) override
boost::shared_ptr< GaussianFactorGraph > linearize(const Values &linearizationPoint) const
Linearize a nonlinear factor graph.
void getSummarizedFactors(NonlinearFactorGraph &filterSummarization, Values &filterSummarizationValues) override
bool equal(const T &obj1, const T &obj2, double tol)
Definition: Testable.h:83
iterator insert(const std::pair< Key, Vector > &key_value)
std::uint64_t Key
Integer nonlinear key type.
Definition: types.h:61
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:567
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 Sat May 8 2021 02:41:49