ConcurrentBatchSmoother.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 
22 #include <gtsam/base/timing.h>
23 #include <gtsam/base/debug.h>
24 
25 namespace gtsam {
26 
27 /* ************************************************************************* */
28 void ConcurrentBatchSmoother::print(const std::string& s, const KeyFormatter& keyFormatter) const {
29  std::cout << s;
30  std::cout << " Factors:" << std::endl;
31  for(const NonlinearFactor::shared_ptr& factor: factors_) {
32  PrintNonlinearFactor(factor, " ", keyFormatter);
33  }
34  theta_.print("Values:\n");
35 }
36 
37 /* ************************************************************************* */
38 bool ConcurrentBatchSmoother::equals(const ConcurrentSmoother& rhs, double tol) const {
39  const ConcurrentBatchSmoother* smoother = dynamic_cast<const ConcurrentBatchSmoother*>(&rhs);
40  return smoother
41  && factors_.equals(smoother->factors_)
42  && theta_.equals(smoother->theta_)
43  && ordering_.equals(smoother->ordering_)
44  && delta_.equals(smoother->delta_)
46 }
47 
48 /* ************************************************************************* */
50  const boost::optional< std::vector<size_t> >& removeFactorIndices) {
51 
52  gttic(update);
53 
54  // Create the return result meta-data
55  Result result;
56 
57  // Update all of the internal variables with the new information
58  gttic(augment_system);
59  {
60  // Add the new variables to theta
61  theta_.insert(newTheta);
62 
63  // Add new variables to the end of the ordering
64  for(const auto key_value: newTheta) {
65  ordering_.push_back(key_value.key);
66  }
67 
68  // Augment Delta
69  delta_.insert(newTheta.zeroVectors());
70 
71  // Add the new factors to the graph, updating the variable index
72  insertFactors(newFactors);
73 
74  if(removeFactorIndices)
75  removeFactors(*removeFactorIndices);
76  }
77  gttoc(augment_system);
78 
79  if(factors_.size() > 0) {
80  // Reorder the system to ensure efficient optimization (and marginalization) performance
81  gttic(reorder);
82  reorder();
83  gttoc(reorder);
84 
85  // Optimize the factors using a modified version of L-M
86  gttic(optimize);
87  result = optimize();
88  gttoc(optimize);
89  }
90 
91  // TODO: The following code does considerable work, much of which could be redundant given the previous optimization step
92  // Refactor this code to reduce computational burden
93 
94  // Calculate the marginal on the separator from the smoother factors
95  if(separatorValues_.size() > 0) {
96  gttic(presync);
98  gttoc(presync);
99  }
100 
101  gttoc(update);
102 
103  return result;
104 }
105 
106 /* ************************************************************************* */
108 
109  gttic(presync);
110 
111  gttoc(presync);
112 }
113 
114 /* ************************************************************************* */
116 
117  gttic(get_summarized_factors);
118 
119  // Copy the previous calculated smoother summarization factors into the output
120  summarizedFactors.push_back(smootherSummarization_);
121 
122  // Copy the separator values into the output
123  separatorValues.insert(separatorValues_);
124 
125  gttoc(get_summarized_factors);
126 }
127 
128 /* ************************************************************************* */
129 void ConcurrentBatchSmoother::synchronize(const NonlinearFactorGraph& smootherFactors, const Values& smootherValues,
130  const NonlinearFactorGraph& summarizedFactors, const Values& separatorValues) {
131 
133 
134  // Remove the previous filter summarization from the graph
136 
137  // Insert new linpoints into the values, augment the ordering, and store new dims to augment delta
138  for(const auto key_value: smootherValues) {
139  std::pair<Values::iterator, bool> iter_inserted = theta_.tryInsert(key_value.key, key_value.value);
140  if(iter_inserted.second) {
141  // If the insert succeeded
142  ordering_.push_back(key_value.key);
143  delta_.insert(key_value.key, Vector::Zero(key_value.value.dim()));
144  } else {
145  // If the element already existed in theta_
146  iter_inserted.first->value = key_value.value;
147  }
148  }
149  for(const auto key_value: separatorValues) {
150  std::pair<Values::iterator, bool> iter_inserted = theta_.tryInsert(key_value.key, key_value.value);
151  if(iter_inserted.second) {
152  // If the insert succeeded
153  ordering_.push_back(key_value.key);
154  delta_.insert(key_value.key, Vector::Zero(key_value.value.dim()));
155  } else {
156  // If the element already existed in theta_
157  iter_inserted.first->value = key_value.value;
158  }
159  }
160 
161  // Insert the new smoother factors
162  insertFactors(smootherFactors);
163 
164  // Insert the new filter summarized factors
165  filterSummarizationSlots_ = insertFactors(summarizedFactors);
166 
167  // Update the list of root keys
168  separatorValues_ = separatorValues;
169 
171 }
172 
173 /* ************************************************************************* */
175 
176  gttic(postsync);
177 
178  gttoc(postsync);
179 }
180 
181 /* ************************************************************************* */
183 
184  gttic(insert_factors);
185 
186  // create the output vector
187  std::vector<size_t> slots;
188  slots.reserve(factors.size());
189 
190  // Insert the factor into an existing hole in the factor graph, if possible
191  for(const NonlinearFactor::shared_ptr& factor: factors) {
192  size_t slot;
193  if(availableSlots_.size() > 0) {
194  slot = availableSlots_.front();
195  availableSlots_.pop();
196  factors_.replace(slot, factor);
197  } else {
198  slot = factors_.size();
199  factors_.push_back(factor);
200  }
201  slots.push_back(slot);
202  }
203 
204  gttoc(insert_factors);
205 
206  return slots;
207 }
208 
209 /* ************************************************************************* */
210 void ConcurrentBatchSmoother::removeFactors(const std::vector<size_t>& slots) {
211 
212  gttic(remove_factors);
213 
214  // For each factor slot to delete...
215  for(size_t slot: slots) {
216 
217  // Remove the factor from the graph
218  factors_.remove(slot);
219 
220  // Mark the factor slot as available
221  availableSlots_.push(slot);
222  }
223 
224  gttoc(remove_factors);
225 }
226 
227 /* ************************************************************************* */
229 
230  // Recalculate the variable index
232 
233  KeyVector separatorKeys = separatorValues_.keys();
234  ordering_ = Ordering::ColamdConstrainedLast(variableIndex_, KeyVector(separatorKeys.begin(), separatorKeys.end()));
235 
236 }
237 
238 /* ************************************************************************* */
240 
241  // Create output result structure
242  Result result;
245 
246  // Pull out parameters we'll use
249 
250  // Create a Values that holds the current evaluation point
251  Values evalpoint = theta_.retract(delta_);
252  result.error = factors_.error(evalpoint);
253  if(result.error < parameters_.errorTol) {
254  return result;
255  }
256 
257  // Use a custom optimization loop so the linearization points can be controlled
258  double previousError;
259  VectorValues newDelta;
260  do {
261  previousError = result.error;
262 
263  // Do next iteration
264  gttic(optimizer_iteration);
265  {
266  // Linearize graph around the linearization point
267  GaussianFactorGraph linearFactorGraph = *factors_.linearize(theta_);
268 
269  // Keep increasing lambda until we make make progress
270  while(true) {
271  if (lmVerbosity >= LevenbergMarquardtParams::TRYLAMBDA)
272  std::cout << "trying lambda = " << lambda << std::endl;
273 
274  // Add prior factors at the current solution
275  gttic(damp);
276  GaussianFactorGraph dampedFactorGraph(linearFactorGraph);
277  dampedFactorGraph.reserve(linearFactorGraph.size() + delta_.size());
278  {
279  // for each of the variables, add a prior at the current solution
280  for(const VectorValues::KeyValuePair& key_value: delta_) {
281  size_t dim = key_value.second.size();
282  Matrix A = Matrix::Identity(dim,dim);
283  Vector b = key_value.second;
285  GaussianFactor::shared_ptr prior(new JacobianFactor(key_value.first, A, b, model));
286  dampedFactorGraph.push_back(prior);
287  }
288  }
289  gttoc(damp);
290  if (lmVerbosity >= LevenbergMarquardtParams::DAMPED)
291  dampedFactorGraph.print("damped");
292  result.lambdas++;
293 
294  gttic(solve);
295  // Solve Damped Gaussian Factor Graph
296  newDelta = dampedFactorGraph.optimize(ordering_, parameters_.getEliminationFunction());
297  // update the evalpoint with the new delta
298  evalpoint = theta_.retract(newDelta);
299  gttoc(solve);
300 
301  if (lmVerbosity >= LevenbergMarquardtParams::TRYLAMBDA)
302  std::cout << "linear delta norm = " << newDelta.norm() << std::endl;
303  if (lmVerbosity >= LevenbergMarquardtParams::TRYDELTA)
304  newDelta.print("delta");
305 
306  // Evaluate the new error
307  gttic(compute_error);
308  double error = factors_.error(evalpoint);
309  gttoc(compute_error);
310 
311  if (lmVerbosity >= LevenbergMarquardtParams::TRYLAMBDA)
312  std::cout << "next error = " << error << std::endl;
313 
314  if(error < result.error) {
315  // Keep this change
316  // Update the error value
317  result.error = error;
318  // Update the linearization point
319  theta_ = evalpoint;
320  // Reset the deltas to zeros
321  delta_.setZero();
322  // Put the linearization points and deltas back for specific variables
323  if(separatorValues_.size() > 0) {
325  for(const auto key_value: separatorValues_) {
326  delta_.at(key_value.key) = newDelta.at(key_value.key);
327  }
328  }
329 
330  // Decrease lambda for next time
331  lambda /= parameters_.lambdaFactor;
332  // End this lambda search iteration
333  break;
334  } else {
335  // Reject this change
336  if(lambda >= parameters_.lambdaUpperBound) {
337  // The maximum lambda has been used. Print a warning and end the search.
338  std::cout << "Warning: Levenberg-Marquardt giving up because cannot decrease error with maximum lambda" << std::endl;
339  break;
340  } else {
341  // Increase lambda and continue searching
342  lambda *= parameters_.lambdaFactor;
343  }
344  }
345  } // end while
346  }
347  gttoc(optimizer_iteration);
348 
349  if (lmVerbosity >= LevenbergMarquardtParams::LAMBDA)
350  std::cout << "using lambda = " << lambda << std::endl;
351 
352  result.iterations++;
353  } while(result.iterations < (size_t)parameters_.maxIterations &&
355 
356  return result;
357 }
358 
359 /* ************************************************************************* */
361 
362  // The smoother summarization factors are the resulting marginal factors on the separator
363  // variables that result from marginalizing out all of the other variables
364  // These marginal factors will be cached for later transmission to the filter using
365  // linear container factors
366 
367  // Create a nonlinear factor graph without the filter summarization factors
369  for(size_t slot: filterSummarizationSlots_) {
370  graph.remove(slot);
371  }
372 
373  // Get the set of separator keys
374  gtsam::KeySet separatorKeys;
375  for(const auto key_value: separatorValues_) {
376  separatorKeys.insert(key_value.key);
377  }
378 
379  // Calculate the marginal factors on the separator
381 }
382 
383 /* ************************************************************************* */
384 void ConcurrentBatchSmoother::PrintNonlinearFactor(const NonlinearFactor::shared_ptr& factor, const std::string& indent, const KeyFormatter& keyFormatter) {
385  std::cout << indent;
386  if(factor) {
387  if(boost::dynamic_pointer_cast<LinearContainerFactor>(factor)) {
388  std::cout << "l( ";
389  } else {
390  std::cout << "f( ";
391  }
392  for(Key key: *factor) {
393  std::cout << keyFormatter(key) << " ";
394  }
395  std::cout << ")" << std::endl;
396  } else {
397  std::cout << "{ nullptr }" << std::endl;
398  }
399 }
400 
401 /* ************************************************************************* */
402 void ConcurrentBatchSmoother::PrintLinearFactor(const GaussianFactor::shared_ptr& factor, const std::string& indent, const KeyFormatter& keyFormatter) {
403  std::cout << indent;
404  if(factor) {
405  std::cout << "g( ";
406  for(Key key: *factor) {
407  std::cout << keyFormatter(key) << " ";
408  }
409  std::cout << ")" << std::endl;
410  } else {
411  std::cout << "{ nullptr }" << std::endl;
412  }
413 }
414 
415 /* ************************************************************************* */
416 }
NonlinearFactorGraph smootherSummarization_
A temporary holding place for calculated smoother summarization.
size_t size() const
Definition: FactorGraph.h:306
static void PrintNonlinearFactor(const NonlinearFactor::shared_ptr &factor, const std::string &indent="", const KeyFormatter &keyFormatter=DefaultKeyFormatter)
bool equals(const ConcurrentSmoother &rhs, double tol=1e-9) const override
void replace(size_t index, sharedFactor factor)
Definition: FactorGraph.h:365
double norm() const
VectorValues optimize(const Eliminate &function=EliminationTraitsType::DefaultEliminate) const
GTSAM_EXPORT bool equals(const Ordering &other, double tol=1e-9) const
Definition: Ordering.cpp:287
size_t nonlinearVariables
The number of variables that can be relinearized.
virtual Result update(const NonlinearFactorGraph &newFactors=NonlinearFactorGraph(), const Values &newTheta=Values(), const boost::optional< std::vector< size_t > > &removeFactorIndices=boost::none)
Wrap Jacobian and Hessian linear factors to allow simple injection into a nonlinear graph...
Global debugging flags.
size_t lambdas
The number of different L-M lambda factors that were tried during optimization.
Point2 prior(const Point2 &x)
Prior on a single pose.
Definition: simulated2D.h:87
noiseModel::Diagonal::shared_ptr model
static void PrintLinearFactor(const GaussianFactor::shared_ptr &factor, const std::string &indent="", const KeyFormatter &keyFormatter=DefaultKeyFormatter)
void insert(Key j, const Value &val)
Definition: Values.cpp:140
void print(const std::string &s="Concurrent Batch Smoother:\n", const KeyFormatter &keyFormatter=DefaultKeyFormatter) const override
double lambdaFactor
The amount by which to multiply or divide lambda when adjusting lambda (default: 10.0)
Ordering ordering_
The current ordering used to calculate the linear deltas.
Eigen::MatrixXd Matrix
Definition: base/Matrix.h:43
Values separatorValues_
The linearization points of the separator variables. These should not be updated during optimization...
EIGEN_DEVICE_FUNC const SqrtReturnType sqrt() const
size_t size() const
Definition: VectorValues.h:125
GaussianFactorGraph factors(list_of(factor1)(factor2)(factor3))
VectorValues delta_
The current set of linear deltas from the linearization point.
void remove(size_t i)
Definition: FactorGraph.h:362
Values retract(const VectorValues &delta) const
Definition: Values.cpp:109
IsDerived< DERIVEDFACTOR > push_back(boost::shared_ptr< DERIVEDFACTOR > factor)
Add a factor directly using a shared_ptr.
Definition: FactorGraph.h:166
Vector & at(Key j)
Definition: VectorValues.h:137
NonlinearFactorGraph graph
KeyVector keys() const
Definition: Values.cpp:191
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)
double relativeErrorTol
The maximum relative error decrease to stop iterating (default 1e-5)
void getSummarizedFactors(NonlinearFactorGraph &summarizedFactors, Values &separatorValues) override
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
size_t iterations
The number of optimizer iterations performed.
double error
The final factor graph error.
boost::shared_ptr< This > shared_ptr
VariableIndex variableIndex_
The current variable index, which allows efficient factor lookup by variable.
GaussianFactorGraph::Eliminate getEliminationFunction() const
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 calculateMarginalFactors(const NonlinearFactorGraph &graph, const Values &theta, const KeySet &remainingKeys, const GaussianFactorGraph::Eliminate &eliminateFunction)
RealScalar s
bool equals(const VectorValues &x, double tol=1e-9) const
value_type KeyValuePair
Typedef to pair<Key, Vector>
Definition: VectorValues.h:85
std::vector< size_t > insertFactors(const NonlinearFactorGraph &factors)
LevenbergMarquardtParams parameters_
LM parameters.
Values theta_
Current linearization point of all variables in the smoother.
const G & b
Definition: Group.h:83
boost::shared_ptr< This > shared_ptr
shared_ptr to this class
size_t linearVariables
The number of variables that must keep a constant linearization point.
A Levenberg-Marquardt Batch Smoother that implements the Concurrent Filtering and Smoothing interface...
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
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
void print(const std::string &str="", const KeyFormatter &keyFormatter=DefaultKeyFormatter) const
Definition: Values.cpp:77
std::vector< size_t > filterSummarizationSlots_
The slots in factor graph that correspond to the current filter summarization factors.
virtual void print(const std::string &s="FactorGraph", const KeyFormatter &formatter=DefaultKeyFormatter) const
print out graph
NonlinearFactorGraph factors_
The set of all factors currently in the smoother.
void synchronize(const NonlinearFactorGraph &smootherFactors, const Values &smootherValues, const NonlinearFactorGraph &summarizedFactors, const Values &separatorValues) override
#define gttoc(label)
Definition: timing.h:281
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
void removeFactors(const std::vector< size_t > &slots)
const G double tol
Definition: Group.h:83
double error(const Values &values) const
void print(const std::string &str="VectorValues", const KeyFormatter &formatter=DefaultKeyFormatter) const
double lambdaUpperBound
The maximum lambda to try before assuming the optimization has failed (default: 1e5) ...
std::pair< iterator, bool > tryInsert(Key j, const Value &value)
Definition: Values.cpp:155
VerbosityLM verbosityLM
The verbosity level for Levenberg-Marquardt (default: SILENT), see also NonlinearOptimizerParams::ver...
boost::shared_ptr< GaussianFactorGraph > linearize(const Values &linearizationPoint) const
Linearize a nonlinear factor graph.
std::queue< size_t > availableSlots_
The set of available factor graph slots caused by deleting factors.
static Ordering ColamdConstrainedLast(const FACTOR_GRAPH &graph, const KeyVector &constrainLast, bool forceOrder=false)
iterator insert(const std::pair< Key, Vector > &key_value)
std::uint64_t Key
Integer nonlinear key type.
Definition: types.h:61
Timing utilities.
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)


gtsam
Author(s):
autogenerated on Sat May 8 2021 02:41:49