GncOptimizer.h
Go to the documentation of this file.
1 /* ----------------------------------------------------------------------------
2 
3  * GTSAM Copyright 2010, Georgia Tech Research Corporation,
4  * Atlanta, Georgia 30332-0415
5  * All Rights Reserved
6  * Authors: Frank Dellaert, et al. (see THANKS for the full author list)
7 
8  * See LICENSE for the license information
9 
10  * -------------------------------------------------------------------------- */
11 
27 #pragma once
28 
31 #include <boost/math/distributions/chi_squared.hpp>
32 
33 namespace gtsam {
34 /*
35  * Quantile of chi-squared distribution with given degrees of freedom at probability alpha.
36  * Equivalent to chi2inv in Matlab.
37  */
38 static double Chi2inv(const double alpha, const size_t dofs) {
39  boost::math::chi_squared_distribution<double> chi2(dofs);
40  return boost::math::quantile(chi2, alpha);
41 }
42 
43 /* ************************************************************************* */
44 template<class GncParameters>
45 class GncOptimizer {
46  public:
48  typedef typename GncParameters::OptimizerType BaseOptimizer;
49 
50  private:
53  GncParameters params_;
56 
57  public:
59  GncOptimizer(const NonlinearFactorGraph& graph, const Values& initialValues,
60  const GncParameters& params = GncParameters())
61  : state_(initialValues),
62  params_(params) {
63 
64  // make sure all noiseModels are Gaussian or convert to Gaussian
65  nfg_.resize(graph.size());
66  for (size_t i = 0; i < graph.size(); i++) {
67  if (graph[i]) {
68  NoiseModelFactor::shared_ptr factor = boost::dynamic_pointer_cast<
69  NoiseModelFactor>(graph[i]);
70  auto robust = boost::dynamic_pointer_cast<
71  noiseModel::Robust>(factor->noiseModel());
72  // if the factor has a robust loss, we remove the robust loss
73  nfg_[i] = robust ? factor-> cloneWithNewNoiseModel(robust->noise()) : factor;
74  }
75  }
76 
77  // set default barcSq_ (inlier threshold)
78  double alpha = 0.99; // with this (default) probability, inlier residuals are smaller than barcSq_
80  }
81 
88  void setInlierCostThresholds(const double inth) {
89  barcSq_ = inth * Vector::Ones(nfg_.size());
90  }
91 
96  void setInlierCostThresholds(const Vector& inthVec) {
97  barcSq_ = inthVec;
98  }
99 
104  barcSq_ = Vector::Ones(nfg_.size()); // initialize
105  for (size_t k = 0; k < nfg_.size(); k++) {
106  if (nfg_[k]) {
107  barcSq_[k] = 0.5 * Chi2inv(alpha, nfg_[k]->dim()); // 0.5 derives from the error definition in gtsam
108  }
109  }
110  }
111 
113  const NonlinearFactorGraph& getFactors() const { return nfg_; }
114 
116  const Values& getState() const { return state_; }
117 
119  const GncParameters& getParams() const { return params_;}
120 
122  const Vector& getWeights() const { return weights_;}
123 
125  const Vector& getInlierCostThresholds() const {return barcSq_;}
126 
128  bool equals(const GncOptimizer& other, double tol = 1e-9) const {
129  return nfg_.equals(other.getFactors())
130  && equal(weights_, other.getWeights())
131  && params_.equals(other.getParams())
132  && equal(barcSq_, other.getInlierCostThresholds());
133  }
134 
137  // start by assuming all measurements are inliers
138  weights_ = Vector::Ones(nfg_.size());
139  BaseOptimizer baseOptimizer(nfg_, state_);
140  Values result = baseOptimizer.optimize();
141  double mu = initializeMu();
142  double prev_cost = nfg_.error(result);
143  double cost = 0.0; // this will be updated in the main loop
144 
145  // handle the degenerate case that corresponds to small
146  // maximum residual errors at initialization
147  // For GM: if residual error is small, mu -> 0
148  // For TLS: if residual error is small, mu -> -1
149  if (mu <= 0) {
150  if (params_.verbosity >= GncParameters::Verbosity::SUMMARY) {
151  std::cout << "GNC Optimizer stopped because maximum residual at "
152  "initialization is small."
153  << std::endl;
154  }
155  if (params_.verbosity >= GncParameters::Verbosity::VALUES) {
156  result.print("result\n");
157  std::cout << "mu: " << mu << std::endl;
158  }
159  return result;
160  }
161 
162  size_t iter;
163  for (iter = 0; iter < params_.maxIterations; iter++) {
164 
165  // display info
166  if (params_.verbosity >= GncParameters::Verbosity::VALUES) {
167  std::cout << "iter: " << iter << std::endl;
168  result.print("result\n");
169  std::cout << "mu: " << mu << std::endl;
170  std::cout << "weights: " << weights_ << std::endl;
171  }
172  // weights update
173  weights_ = calculateWeights(result, mu);
174 
175  // variable/values update
176  NonlinearFactorGraph graph_iter = this->makeWeightedGraph(weights_);
177  BaseOptimizer baseOptimizer_iter(graph_iter, state_);
178  result = baseOptimizer_iter.optimize();
179 
180  // stopping condition
181  cost = graph_iter.error(result);
182  if (checkConvergence(mu, weights_, cost, prev_cost)) {
183  break;
184  }
185 
186  // update mu
187  mu = updateMu(mu);
188 
189  // get ready for next iteration
190  prev_cost = cost;
191 
192  // display info
193  if (params_.verbosity >= GncParameters::Verbosity::VALUES) {
194  std::cout << "previous cost: " << prev_cost << std::endl;
195  std::cout << "current cost: " << cost << std::endl;
196  }
197  }
198  // display info
199  if (params_.verbosity >= GncParameters::Verbosity::SUMMARY) {
200  std::cout << "final iterations: " << iter << std::endl;
201  std::cout << "final mu: " << mu << std::endl;
202  std::cout << "final weights: " << weights_ << std::endl;
203  std::cout << "previous cost: " << prev_cost << std::endl;
204  std::cout << "current cost: " << cost << std::endl;
205  }
206  return result;
207  }
208 
210  double initializeMu() const {
211 
212  double mu_init = 0.0;
213  // initialize mu to the value specified in Remark 5 in GNC paper.
214  switch (params_.lossType) {
215  case GncLossType::GM:
216  /* surrogate cost is convex for large mu. initialize as in remark 5 in GNC paper.
217  Since barcSq_ can be different for each factor, we compute the max of the quantity in remark 5 in GNC paper
218  */
219  for (size_t k = 0; k < nfg_.size(); k++) {
220  if (nfg_[k]) {
221  mu_init = std::max(mu_init, 2 * nfg_[k]->error(state_) / barcSq_[k]);
222  }
223  }
224  return mu_init; // initial mu
225  case GncLossType::TLS:
226  /* surrogate cost is convex for mu close to zero. initialize as in remark 5 in GNC paper.
227  degenerate case: 2 * rmax_sq - params_.barcSq < 0 (handled in the main loop)
228  according to remark mu = params_.barcSq / (2 * rmax_sq - params_.barcSq) = params_.barcSq/ excessResidual
229  however, if the denominator is 0 or negative, we return mu = -1 which leads to termination of the main GNC loop.
230  Since barcSq_ can be different for each factor, we look for the minimimum (positive) quantity in remark 5 in GNC paper
231  */
232  mu_init = std::numeric_limits<double>::infinity();
233  for (size_t k = 0; k < nfg_.size(); k++) {
234  if (nfg_[k]) {
235  double rk = nfg_[k]->error(state_);
236  mu_init = (2 * rk - barcSq_[k]) > 0 ? // if positive, update mu, otherwise keep same
237  std::min(mu_init, barcSq_[k] / (2 * rk - barcSq_[k]) ) : mu_init;
238  }
239  }
240  return mu_init > 0 && !std::isinf(mu_init) ? mu_init : -1; // if mu <= 0 or mu = inf, return -1,
241  // which leads to termination of the main gnc loop. In this case, all residuals are already below the threshold
242  // and there is no need to robustify (TLS = least squares)
243  default:
244  throw std::runtime_error(
245  "GncOptimizer::initializeMu: called with unknown loss type.");
246  }
247  }
248 
250  double updateMu(const double mu) const {
251  switch (params_.lossType) {
252  case GncLossType::GM:
253  // reduce mu, but saturate at 1 (original cost is recovered for mu -> 1)
254  return std::max(1.0, mu / params_.muStep);
255  case GncLossType::TLS:
256  // increases mu at each iteration (original cost is recovered for mu -> inf)
257  return mu * params_.muStep;
258  default:
259  throw std::runtime_error(
260  "GncOptimizer::updateMu: called with unknown loss type.");
261  }
262  }
263 
265  bool checkMuConvergence(const double mu) const {
266  bool muConverged = false;
267  switch (params_.lossType) {
268  case GncLossType::GM:
269  muConverged = std::fabs(mu - 1.0) < 1e-9; // mu=1 recovers the original GM function
270  break;
271  case GncLossType::TLS:
272  muConverged = false; // for TLS there is no stopping condition on mu (it must tend to infinity)
273  break;
274  default:
275  throw std::runtime_error(
276  "GncOptimizer::checkMuConvergence: called with unknown loss type.");
277  }
278  if (muConverged && params_.verbosity >= GncParameters::Verbosity::SUMMARY)
279  std::cout << "muConverged = true " << std::endl;
280  return muConverged;
281  }
282 
284  bool checkCostConvergence(const double cost, const double prev_cost) const {
285  bool costConverged = std::fabs(cost - prev_cost) / std::max(prev_cost, 1e-7)
286  < params_.relativeCostTol;
287  if (costConverged && params_.verbosity >= GncParameters::Verbosity::SUMMARY)
288  std::cout << "checkCostConvergence = true " << std::endl;
289  return costConverged;
290  }
291 
293  bool checkWeightsConvergence(const Vector& weights) const {
294  bool weightsConverged = false;
295  switch (params_.lossType) {
296  case GncLossType::GM:
297  weightsConverged = false; // for GM, there is no clear binary convergence for the weights
298  break;
299  case GncLossType::TLS:
300  weightsConverged = true;
301  for (int i = 0; i < weights.size(); i++) {
302  if (std::fabs(weights[i] - std::round(weights[i]))
303  > params_.weightsTol) {
304  weightsConverged = false;
305  break;
306  }
307  }
308  break;
309  default:
310  throw std::runtime_error(
311  "GncOptimizer::checkWeightsConvergence: called with unknown loss type.");
312  }
313  if (weightsConverged
314  && params_.verbosity >= GncParameters::Verbosity::SUMMARY)
315  std::cout << "weightsConverged = true " << std::endl;
316  return weightsConverged;
317  }
318 
320  bool checkConvergence(const double mu, const Vector& weights,
321  const double cost, const double prev_cost) const {
322  return checkCostConvergence(cost, prev_cost)
323  || checkWeightsConvergence(weights) || checkMuConvergence(mu);
324  }
325 
328  // make sure all noiseModels are Gaussian or convert to Gaussian
329  NonlinearFactorGraph newGraph;
330  newGraph.resize(nfg_.size());
331  for (size_t i = 0; i < nfg_.size(); i++) {
332  if (nfg_[i]) {
333  auto factor = boost::dynamic_pointer_cast<
334  NoiseModelFactor>(nfg_[i]);
335  auto noiseModel =
336  boost::dynamic_pointer_cast<noiseModel::Gaussian>(
337  factor->noiseModel());
338  if (noiseModel) {
339  Matrix newInfo = weights[i] * noiseModel->information();
340  auto newNoiseModel = noiseModel::Gaussian::Information(newInfo);
341  newGraph[i] = factor->cloneWithNewNoiseModel(newNoiseModel);
342  } else {
343  throw std::runtime_error(
344  "GncOptimizer::makeWeightedGraph: unexpected non-Gaussian noise model.");
345  }
346  }
347  }
348  return newGraph;
349  }
350 
352  Vector calculateWeights(const Values& currentEstimate, const double mu) {
353  Vector weights = Vector::Ones(nfg_.size());
354 
355  // do not update the weights that the user has decided are known inliers
356  std::vector<size_t> allWeights;
357  for (size_t k = 0; k < nfg_.size(); k++) {
358  allWeights.push_back(k);
359  }
360  std::vector<size_t> unknownWeights;
361  std::set_difference(allWeights.begin(), allWeights.end(),
362  params_.knownInliers.begin(),
363  params_.knownInliers.end(),
364  std::inserter(unknownWeights, unknownWeights.begin()));
365 
366  // update weights of known inlier/outlier measurements
367  switch (params_.lossType) {
368  case GncLossType::GM: { // use eq (12) in GNC paper
369  for (size_t k : unknownWeights) {
370  if (nfg_[k]) {
371  double u2_k = nfg_[k]->error(currentEstimate); // squared (and whitened) residual
372  weights[k] = std::pow(
373  (mu * barcSq_[k]) / (u2_k + mu * barcSq_[k]), 2);
374  }
375  }
376  return weights;
377  }
378  case GncLossType::TLS: { // use eq (14) in GNC paper
379  double upperbound = (mu + 1) / mu * barcSq_.maxCoeff();
380  double lowerbound = mu / (mu + 1) * barcSq_.minCoeff();
381  for (size_t k : unknownWeights) {
382  if (nfg_[k]) {
383  double u2_k = nfg_[k]->error(currentEstimate); // squared (and whitened) residual
384  if (u2_k >= upperbound) {
385  weights[k] = 0;
386  } else if (u2_k <= lowerbound) {
387  weights[k] = 1;
388  } else {
389  weights[k] = std::sqrt(barcSq_[k] * mu * (mu + 1) / u2_k)
390  - mu;
391  }
392  }
393  }
394  return weights;
395  }
396  default:
397  throw std::runtime_error(
398  "GncOptimizer::calculateWeights: called with unknown loss type.");
399  }
400  }
401 };
402 
403 }
double initializeMu() const
Initialize the gnc parameter mu such that loss is approximately convex (remark 5 in GNC paper)...
Definition: GncOptimizer.h:210
size_t size() const
Definition: FactorGraph.h:306
#define max(a, b)
Definition: datatypes.h:20
void setInlierCostThresholdsAtProbability(const double alpha)
Definition: GncOptimizer.h:103
Factor Graph consisting of non-linear factors.
static double Chi2inv(const double alpha, const size_t dofs)
Definition: GncOptimizer.h:38
#define min(a, b)
Definition: datatypes.h:19
double mu
Eigen::MatrixXd Matrix
Definition: base/Matrix.h:43
EIGEN_DEVICE_FUNC const SqrtReturnType sqrt() const
iterator iter(handle obj)
Definition: pytypes.h:1547
Values optimize()
Compute optimal solution using graduated non-convexity.
Definition: GncOptimizer.h:136
GncOptimizer(const NonlinearFactorGraph &graph, const Values &initialValues, const GncParameters &params=GncParameters())
Constructor.
Definition: GncOptimizer.h:59
#define isinf(X)
Definition: main.h:73
bool checkWeightsConvergence(const Vector &weights) const
Check convergence of weights to binary values.
Definition: GncOptimizer.h:293
Real fabs(const Real &a)
const Values & getState() const
Access a copy of the internal values.
Definition: GncOptimizer.h:116
NonlinearFactorGraph graph
const GncParameters & getParams() const
Access a copy of the parameters.
Definition: GncOptimizer.h:119
bool checkConvergence(const double mu, const Vector &weights, const double cost, const double prev_cost) const
Check for convergence between consecutive GNC iterations.
Definition: GncOptimizer.h:320
const NonlinearFactorGraph & getFactors() const
Access a copy of the internal factor graph.
Definition: GncOptimizer.h:113
bool equals(const GncOptimizer &other, double tol=1e-9) const
Equals.
Definition: GncOptimizer.h:128
EIGEN_DEVICE_FUNC const RoundReturnType round() const
bool equals(const NonlinearFactorGraph &other, double tol=1e-9) const
NonlinearFactorGraph makeWeightedGraph(const Vector &weights) const
Create a graph where each factor is weighted by the gnc weights.
Definition: GncOptimizer.h:327
Eigen::VectorXd Vector
Definition: Vector.h:38
static shared_ptr Information(const Matrix &M, bool smart=true)
Definition: NoiseModel.cpp:99
Values result
const Vector & getInlierCostThresholds() const
Get the inlier threshold.
Definition: GncOptimizer.h:125
bool checkMuConvergence(const double mu) const
Check if we have reached the value of mu for which the surrogate loss matches the original loss...
Definition: GncOptimizer.h:265
const Vector & getWeights() const
Access a copy of the GNC weights.
Definition: GncOptimizer.h:122
Vector weights_
Weights associated to each factor in GNC (this could be a local variable in optimize, but it is useful to make it accessible from outside).
Definition: GncOptimizer.h:54
RealScalar alpha
Array< double, 1, 3 > e(1./3., 0.5, 2.)
static SmartStereoProjectionParams params
boost::shared_ptr< This > shared_ptr
virtual Matrix information() const
Compute information matrix.
Definition: NoiseModel.h:259
bool checkCostConvergence(const double cost, const double prev_cost) const
Check convergence of relative cost differences.
Definition: GncOptimizer.h:284
Vector calculateWeights(const Values &currentEstimate, const double mu)
Calculate gnc weights.
Definition: GncOptimizer.h:352
const mpreal dim(const mpreal &a, const mpreal &b, mp_rnd_t r=mpreal::get_default_rnd())
Definition: mpreal.h:2201
traits
Definition: chartTesting.h:28
GncParameters::OptimizerType BaseOptimizer
For each parameter, specify the corresponding optimizer: e.g., GaussNewtonParams -> GaussNewtonOptimi...
Definition: GncOptimizer.h:48
void print(const std::string &str="", const KeyFormatter &keyFormatter=DefaultKeyFormatter) const
Definition: Values.cpp:77
double updateMu(const double mu) const
Update the gnc parameter mu to gradually increase nonconvexity.
Definition: GncOptimizer.h:250
NonlinearFactorGraph nfg_
Original factor graph to be solved by GNC.
Definition: GncOptimizer.h:51
void setInlierCostThresholds(const Vector &inthVec)
Definition: GncOptimizer.h:96
void resize(size_t size)
Definition: FactorGraph.h:358
static double error
Definition: testRot3.cpp:39
const G double tol
Definition: Group.h:83
double error(const Values &values) const
GncParameters params_
GNC parameters.
Definition: GncOptimizer.h:53
Jet< T, N > pow(const Jet< T, N > &f, double g)
Definition: jet.h:570
Vector barcSq_
Inlier thresholds. A factor is considered an inlier if factor.error() < barcSq_[i] (where i is the po...
Definition: GncOptimizer.h:55
bool equal(const T &obj1, const T &obj2, double tol)
Definition: Testable.h:83
Values state_
Initial values to be used at each iteration by GNC.
Definition: GncOptimizer.h:52
void setInlierCostThresholds(const double inth)
Definition: GncOptimizer.h:88


gtsam
Author(s):
autogenerated on Sat May 8 2021 02:42:09