HessianFactor.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 
19 
25 #include <gtsam/base/cholesky.h>
26 #include <gtsam/base/debug.h>
27 #include <gtsam/base/FastMap.h>
28 #include <gtsam/base/Matrix.h>
30 #include <gtsam/base/timing.h>
31 
32 #include <boost/format.hpp>
33 #include <boost/make_shared.hpp>
34 #include <boost/tuple/tuple.hpp>
35 #ifdef __GNUC__
36 #pragma GCC diagnostic push
37 #pragma GCC diagnostic ignored "-Wunused-variable"
38 #endif
39 #include <boost/bind.hpp>
40 #ifdef __GNUC__
41 #pragma GCC diagnostic pop
42 #endif
43 #include <boost/assign/list_of.hpp>
44 #include <boost/range/adaptor/transformed.hpp>
45 #include <boost/range/adaptor/map.hpp>
46 #include <boost/range/algorithm/copy.hpp>
47 
48 #include <sstream>
49 #include <limits>
50 
51 using namespace std;
52 using namespace boost::assign;
53 namespace br {
54 using namespace boost::range;
55 using namespace boost::adaptors;
56 }
57 
58 namespace gtsam {
59 
60 /* ************************************************************************* */
61 void HessianFactor::Allocate(const Scatter& scatter) {
62  gttic(HessianFactor_Allocate);
63 
64  // Allocate with dimensions for each variable plus 1 at the end for the information vector
65  const size_t n = scatter.size();
66  keys_.resize(n);
67  FastVector<DenseIndex> dims(n + 1);
68  DenseIndex slot = 0;
69  for(const SlotEntry& slotentry: scatter) {
70  keys_[slot] = slotentry.key;
71  dims[slot] = slotentry.dimension;
72  ++slot;
73  }
74  dims.back() = 1;
75  info_ = SymmetricBlockMatrix(dims);
76 }
77 
78 /* ************************************************************************* */
79 HessianFactor::HessianFactor(const Scatter& scatter) {
80  Allocate(scatter);
81 }
82 
83 /* ************************************************************************* */
84 HessianFactor::HessianFactor() :
85  info_(cref_list_of<1>(1)) {
86  assert(info_.rows() == 1);
87  constantTerm() = 0.0;
88 }
89 
90 /* ************************************************************************* */
91 HessianFactor::HessianFactor(Key j, const Matrix& G, const Vector& g, double f) :
92  GaussianFactor(cref_list_of<1>(j)), info_(cref_list_of<2>(G.cols())(1)) {
93  if (G.rows() != G.cols() || G.rows() != g.size())
94  throw invalid_argument(
95  "Attempting to construct HessianFactor with inconsistent matrix and/or vector dimensions");
96  info_.setDiagonalBlock(0, G);
97  linearTerm() = g;
98  constantTerm() = f;
99 }
100 
101 /* ************************************************************************* */
102 // error is 0.5*(x-mu)'*inv(Sigma)*(x-mu) = 0.5*(x'*G*x - 2*x'*G*mu + mu'*G*mu)
103 // where G = inv(Sigma), g = G*mu, f = mu'*G*mu = mu'*g
105  GaussianFactor(cref_list_of<1>(j)), info_(cref_list_of<2>(Sigma.cols())(1)) {
106  if (Sigma.rows() != Sigma.cols() || Sigma.rows() != mu.size())
107  throw invalid_argument(
108  "Attempting to construct HessianFactor with inconsistent matrix and/or vector dimensions");
109  info_.setDiagonalBlock(0, Sigma.inverse()); // G
110  linearTerm() = info_.diagonalBlock(0) * mu; // g
111  constantTerm() = mu.dot(linearTerm().col(0)); // f
112 }
113 
114 /* ************************************************************************* */
116  const Matrix& G12, const Vector& g1, const Matrix& G22, const Vector& g2,
117  double f) :
118  GaussianFactor(cref_list_of<2>(j1)(j2)), info_(
119  cref_list_of<3>(G11.cols())(G22.cols())(1)) {
120  info_.setDiagonalBlock(0, G11);
121  info_.setOffDiagonalBlock(0, 1, G12);
122  info_.setDiagonalBlock(1, G22);
123  linearTerm() << g1, g2;
124  constantTerm() = f;
125 }
126 
127 /* ************************************************************************* */
129  const Matrix& G12, const Matrix& G13, const Vector& g1, const Matrix& G22,
130  const Matrix& G23, const Vector& g2, const Matrix& G33, const Vector& g3,
131  double f) :
132  GaussianFactor(cref_list_of<3>(j1)(j2)(j3)), info_(
133  cref_list_of<4>(G11.cols())(G22.cols())(G33.cols())(1)) {
134  if (G11.rows() != G11.cols() || G11.rows() != G12.rows()
135  || G11.rows() != G13.rows() || G11.rows() != g1.size()
136  || G22.cols() != G12.cols() || G33.cols() != G13.cols()
137  || G22.cols() != g2.size() || G33.cols() != g3.size())
138  throw invalid_argument(
139  "Inconsistent matrix and/or vector dimensions in HessianFactor constructor");
140  info_.setDiagonalBlock(0, G11);
141  info_.setOffDiagonalBlock(0, 1, G12);
142  info_.setOffDiagonalBlock(0, 2, G13);
143  info_.setDiagonalBlock(1, G22);
144  info_.setOffDiagonalBlock(1, 2, G23);
145  info_.setDiagonalBlock(2, G33);
146  linearTerm() << g1, g2, g3;
147  constantTerm() = f;
148 }
149 
150 /* ************************************************************************* */
151 namespace {
152 DenseIndex _getSizeHF(const Vector& m) {
153  return m.size();
154 }
155 }
156 
157 /* ************************************************************************* */
159  const std::vector<Matrix>& Gs, const std::vector<Vector>& gs, double f) :
160  GaussianFactor(js), info_(gs | br::transformed(&_getSizeHF), true) {
161  // Get the number of variables
162  size_t variable_count = js.size();
163 
164  // Verify the provided number of entries in the vectors are consistent
165  if (gs.size() != variable_count
166  || Gs.size() != (variable_count * (variable_count + 1)) / 2)
167  throw invalid_argument(
168  "Inconsistent number of entries between js, Gs, and gs in HessianFactor constructor.\nThe number of keys provided \
169  in js must match the number of linear vector pieces in gs. The number of upper-diagonal blocks in Gs must be n*(n+1)/2");
170 
171  // Verify the dimensions of each provided matrix are consistent
172  // Note: equations for calculating the indices derived from the "sum of an arithmetic sequence" formula
173  for (size_t i = 0; i < variable_count; ++i) {
174  DenseIndex block_size = gs[i].size();
175  // Check rows
176  for (size_t j = 0; j < variable_count - i; ++j) {
177  size_t index = i * (2 * variable_count - i + 1) / 2 + j;
178  if (Gs[index].rows() != block_size) {
179  throw invalid_argument(
180  "Inconsistent matrix and/or vector dimensions in HessianFactor constructor");
181  }
182  }
183  // Check cols
184  for (size_t j = 0; j <= i; ++j) {
185  size_t index = j * (2 * variable_count - j + 1) / 2 + (i - j);
186  if (Gs[index].cols() != block_size) {
187  throw invalid_argument(
188  "Inconsistent matrix and/or vector dimensions in HessianFactor constructor");
189  }
190  }
191  }
192 
193  // Fill in the blocks
194  size_t index = 0;
195  for (size_t i = 0; i < variable_count; ++i) {
196  for (size_t j = i; j < variable_count; ++j) {
197  if (i == j) {
198  info_.setDiagonalBlock(i, Gs[index]);
199  } else {
200  info_.setOffDiagonalBlock(i, j, Gs[index]);
201  }
202  index++;
203  }
204  info_.setOffDiagonalBlock(i, variable_count, gs[i]);
205  }
206  constantTerm() = f;
207 }
208 
209 /* ************************************************************************* */
210 namespace {
211 void _FromJacobianHelper(const JacobianFactor& jf, SymmetricBlockMatrix& info) {
212  gttic(HessianFactor_fromJacobian);
213  const SharedDiagonal& jfModel = jf.get_model();
214  auto A = jf.matrixObject().full();
215  if (jfModel) {
216  if (jf.get_model()->isConstrained())
217  throw invalid_argument(
218  "Cannot construct HessianFactor from JacobianFactor with constrained noise model");
219 
220  auto D = (jfModel->invsigmas().array() * jfModel->invsigmas().array()).matrix().asDiagonal();
221 
222  info.setFullMatrix(A.transpose() * D * A);
223  } else {
224  info.setFullMatrix(A.transpose() * A);
225  }
226 }
227 }
228 
229 /* ************************************************************************* */
231  GaussianFactor(jf), info_(
232  SymmetricBlockMatrix::LikeActiveViewOf(jf.matrixObject())) {
233  _FromJacobianHelper(jf, info_);
234 }
235 
236 /* ************************************************************************* */
238  GaussianFactor(gf) {
239  // Copy the matrix data depending on what type of factor we're copying from
240  if (const JacobianFactor* jf = dynamic_cast<const JacobianFactor*>(&gf)) {
241  info_ = SymmetricBlockMatrix::LikeActiveViewOf(jf->matrixObject());
242  _FromJacobianHelper(*jf, info_);
243  } else if (const HessianFactor* hf = dynamic_cast<const HessianFactor*>(&gf)) {
244  info_ = hf->info_;
245  } else {
246  throw std::invalid_argument(
247  "In HessianFactor(const GaussianFactor& gf), gf is neither a JacobianFactor nor a HessianFactor");
248  }
249 }
250 
251 /* ************************************************************************* */
253  const Scatter& scatter) {
254  gttic(HessianFactor_MergeConstructor);
255 
256  Allocate(scatter);
257 
258  // Form A' * A
259  gttic(update);
260  info_.setZero();
261  for(const auto& factor: factors)
262  if (factor)
263  factor->updateHessian(keys_, &info_);
264  gttoc(update);
265 }
266 
267 /* ************************************************************************* */
268 void HessianFactor::print(const std::string& s,
269  const KeyFormatter& formatter) const {
270  cout << s << "\n";
271  cout << " keys: ";
272  for (const_iterator key = begin(); key != end(); ++key)
273  cout << formatter(*key) << "(" << getDim(key) << ") ";
274  cout << "\n";
276  "Augmented information matrix: ");
277 }
278 
279 /* ************************************************************************* */
280 bool HessianFactor::equals(const GaussianFactor& lf, double tol) const {
281  const HessianFactor* rhs = dynamic_cast<const HessianFactor*>(&lf);
282  if (!rhs || !Factor::equals(lf, tol))
283  return false;
285  tol);
286 }
287 
288 /* ************************************************************************* */
290  return info_.selfadjointView();
291 }
292 
293 /* ************************************************************************* */
296  return info_.selfadjointView(0, size());
297 }
298 
299 /* ************************************************************************* */
301  return informationView();
302 }
303 
304 /* ************************************************************************* */
306  for (DenseIndex j = 0; j < (DenseIndex)size(); ++j) {
307  auto result = d.emplace(keys_[j], info_.diagonal(j));
308  if(!result.second) {
309  // if emplace fails, it returns an iterator to the existing element, which we add to:
310  result.first->second += info_.diagonal(j);
311  }
312  }
313 }
314 
315 /* ************************************************************************* */
316 // Raw memory access version should be called in Regular Factors only currently
317 void HessianFactor::hessianDiagonal(double* d) const {
318  throw std::runtime_error(
319  "HessianFactor::hessianDiagonal raw memory access is allowed for Regular Factors only");
320 }
321 
322 /* ************************************************************************* */
323 map<Key, Matrix> HessianFactor::hessianBlockDiagonal() const {
324  map<Key, Matrix> blocks;
325  // Loop over all variables
326  for (DenseIndex j = 0; j < (DenseIndex) size(); ++j) {
327  // Get the diagonal block, and insert it
328  blocks.emplace(keys_[j], info_.diagonalBlock(j));
329  }
330  return blocks;
331 }
332 
333 /* ************************************************************************* */
335  return JacobianFactor(*this).augmentedJacobian();
336 }
337 
338 /* ************************************************************************* */
339 std::pair<Matrix, Vector> HessianFactor::jacobian() const {
340  return JacobianFactor(*this).jacobian();
341 }
342 
343 /* ************************************************************************* */
344 double HessianFactor::error(const VectorValues& c) const {
345  // error 0.5*(f - 2*x'*g + x'*G*x)
346  const double f = constantTerm();
347  if (empty()) {
348  return 0.5 * f;
349  }
350  double xtg = 0, xGx = 0;
351  // extract the relevant subset of the VectorValues
352  // NOTE may not be as efficient
353  const Vector x = c.vector(keys());
354  xtg = x.dot(linearTerm().col(0));
355  auto AtA = informationView();
356  xGx = x.transpose() * AtA * x;
357  return 0.5 * (f - 2.0 * xtg + xGx);
358 }
359 
360 /* ************************************************************************* */
362  SymmetricBlockMatrix* info) const {
363  gttic(updateHessian_HessianFactor);
364  assert(info);
365  // Apply updates to the upper triangle
366  DenseIndex nrVariablesInThisFactor = size(), nrBlocksInInfo = info->nBlocks() - 1;
367  vector<DenseIndex> slots(nrVariablesInThisFactor + 1);
368  // Loop over this factor's blocks with indices (i,j)
369  // For every block (i,j), we determine the block (I,J) in info.
370  for (DenseIndex j = 0; j <= nrVariablesInThisFactor; ++j) {
371  const bool rhs = (j == nrVariablesInThisFactor);
372  const DenseIndex J = rhs ? nrBlocksInInfo : Slot(infoKeys, keys_[j]);
373  slots[j] = J;
374  for (DenseIndex i = 0; i <= j; ++i) {
375  const DenseIndex I = slots[i]; // because i<=j, slots[i] is valid.
376 
377  if (i == j) {
378  assert(I == J);
380  } else {
381  assert(i < j);
382  assert(I != J);
384  }
385  }
386  }
387 }
388 
389 /* ************************************************************************* */
391  shared_ptr result = boost::make_shared<This>(*this);
392  // Negate the information matrix of the result
393  result->info_.negate();
394  return result;
395 }
396 
397 /* ************************************************************************* */
399  VectorValues& yvalues) const {
400 
401  // Create a vector of temporary y values, corresponding to rows i
402  vector<Vector> y;
403  y.reserve(size());
404  for (const_iterator it = begin(); it != end(); it++)
405  y.push_back(Vector::Zero(getDim(it)));
406 
407  // Accessing the VectorValues one by one is expensive
408  // So we will loop over columns to access x only once per column
409  // And fill the above temporary y values, to be added into yvalues after
410  for (DenseIndex j = 0; j < (DenseIndex) size(); ++j) {
411  // xj is the input vector
412  Vector xj = x.at(keys_[j]);
413  DenseIndex i = 0;
414  for (; i < j; ++i)
415  y[i] += info_.aboveDiagonalBlock(i, j) * xj;
416 
417  // blocks on the diagonal are only half
418  y[i] += info_.diagonalBlock(j) * xj;
419  // for below diagonal, we take transpose block from upper triangular part
420  for (i = j + 1; i < (DenseIndex) size(); ++i)
421  y[i] += info_.aboveDiagonalBlock(j, i).transpose() * xj;
422  }
423 
424  // copy to yvalues
425  for (DenseIndex i = 0; i < (DenseIndex) size(); ++i) {
426  bool didNotExist;
428  boost::tie(it, didNotExist) = yvalues.tryInsert(keys_[i], Vector());
429  if (didNotExist)
430  it->second = alpha * y[i]; // init
431  else
432  it->second += alpha * y[i]; // add
433  }
434 }
435 
436 /* ************************************************************************* */
438  VectorValues g;
439  size_t n = size();
440  for (size_t j = 0; j < n; ++j)
441  g.emplace(keys_[j], -info_.aboveDiagonalBlock(j, n));
442  return g;
443 }
444 
445 /* ************************************************************************* */
446 // Raw memory access version should be called in Regular Factors only currently
447 void HessianFactor::gradientAtZero(double* d) const {
448  throw std::runtime_error(
449  "HessianFactor::gradientAtZero raw memory access is allowed for Regular Factors only");
450 }
451 
452 /* ************************************************************************* */
454  const Factor::const_iterator it_i = find(key);
455  const DenseIndex I = std::distance(begin(), it_i);
456 
457  // Sum over G_ij*xj for all xj connecting to xi
458  Vector b = Vector::Zero(x.at(key).size());
459  for (Factor::const_iterator it_j = begin(); it_j != end(); ++it_j) {
460  const DenseIndex J = std::distance(begin(), it_j);
461 
462  // Obtain Gij from the Hessian factor
463  // Hessian factor only stores an upper triangular matrix, so be careful when i>j
464  const Matrix Gij = info_.block(I, J);
465  // Accumulate Gij*xj to gradf
466  b += Gij * x.at(*it_j);
467  }
468  // Subtract the linear term gi
469  b += -linearTerm(it_i);
470  return b;
471 }
472 
473 /* ************************************************************************* */
474 boost::shared_ptr<GaussianConditional> HessianFactor::eliminateCholesky(const Ordering& keys) {
475  gttic(HessianFactor_eliminateCholesky);
476 
478 
479  try {
480  // Do dense elimination
481  size_t nFrontals = keys.size();
482  assert(nFrontals <= size());
483  info_.choleskyPartial(nFrontals);
484 
485  // TODO(frank): pre-allocate GaussianConditional and write into it
486  const VerticalBlockMatrix Ab = info_.split(nFrontals);
487  conditional = boost::make_shared<GaussianConditional>(keys_, nFrontals, Ab);
488 
489  // Erase the eliminated keys in this factor
490  keys_.erase(begin(), begin() + nFrontals);
491  } catch (const CholeskyFailed&) {
492 #ifndef NDEBUG
493  cout << "Partial Cholesky on HessianFactor failed." << endl;
494  keys.print("Frontal keys ");
495  print("HessianFactor:");
496 #endif
497  throw IndeterminantLinearSystemException(keys.front());
498  }
499 
500  // Return result
501  return conditional;
502 }
503 
504 /* ************************************************************************* */
506  gttic(HessianFactor_solve);
507 
508  // Do Cholesky Factorization
509  const size_t n = size();
510  assert(size_t(info_.nBlocks()) == n + 1);
512  auto R = info_.triangularView(0, n);
513  auto eta = linearTerm();
514 
515  // Solve
516  const Vector solution = R.solve(eta);
517 
518  // Parse into VectorValues
520  std::size_t offset = 0;
521  for (DenseIndex j = 0; j < (DenseIndex)n; ++j) {
522  const DenseIndex dim = info_.getDim(j);
523  delta.emplace(keys_[j], solution.segment(offset, dim));
524  offset += dim;
525  }
526 
527  return delta;
528 }
529 
530 /* ************************************************************************* */
531 std::pair<boost::shared_ptr<GaussianConditional>, boost::shared_ptr<HessianFactor> >
534 
535  // Build joint factor
536  HessianFactor::shared_ptr jointFactor;
537  try {
538  Scatter scatter(factors, keys);
539  jointFactor = boost::make_shared<HessianFactor>(factors, scatter);
540  } catch (std::invalid_argument&) {
542  "EliminateCholesky was called with a request to eliminate variables that are not\n"
543  "involved in the provided factors.");
544  }
545 
546  // Do dense elimination
547  auto conditional = jointFactor->eliminateCholesky(keys);
548 
549  // Return result
550  return make_pair(conditional, jointFactor);
551 }
552 
553 /* ************************************************************************* */
554 std::pair<boost::shared_ptr<GaussianConditional>,
555  boost::shared_ptr<GaussianFactor> > EliminatePreferCholesky(
556  const GaussianFactorGraph& factors, const Ordering& keys) {
558 
559  // If any JacobianFactors have constrained noise models, we have to convert
560  // all factors to JacobianFactors. Otherwise, we can convert all factors
561  // to HessianFactors. This is because QR can handle constrained noise
562  // models but Cholesky cannot.
563  if (hasConstraints(factors))
564  return EliminateQR(factors, keys);
565  else
566  return EliminateCholesky(factors, keys);
567 }
568 
569 } // gtsam
void print(const Matrix &A, const string &s, ostream &stream)
Definition: Matrix.cpp:155
Matrix3f m
One SlotEntry stores the slot index for a variable, as well its dim.
Definition: Scatter.h:32
bool equals(const This &other, double tol=1e-9) const
check equality
Definition: Factor.cpp:42
SymmetricBlockMatrix::constBlock linearTerm() const
VectorValues gradientAtZero() const override
eta for Hessian
const VerticalBlockMatrix & matrixObject() const
VectorValues solve()
Solve the system A&#39;*A delta = A&#39;*b in-place, return delta as VectorValues.
Values::iterator iterator
Iterator over vector values.
Definition: VectorValues.h:81
Scalar * y
const_iterator find(Key key) const
find
Definition: Factor.h:121
def update(text)
Definition: relicense.py:46
Eigen::SelfAdjointView< SymmetricBlockMatrix::constBlock, Eigen::Upper > informationView() const
Return self-adjoint view onto the information matrix (NOT augmented).
Global debugging flags.
void setOffDiagonalBlock(DenseIndex I, DenseIndex J, const XprType &xpr)
Set an off-diagonal block. Only the upper triangular portion of xpr is evaluated. ...
bool equals(const GaussianFactor &lf, double tol=1e-9) const override
void multiplyHessianAdd(double alpha, const VectorValues &x, VectorValues &y) const override
JacobiRotation< float > G
double mu
int n
Eigen::MatrixXd Matrix
Definition: base/Matrix.h:43
A factor with a quadratic error function - a Gaussian.
Scalar Scalar * c
Definition: benchVecAdd.cpp:17
Rot2 R(Rot2::fromAngle(0.1))
const_iterator end() const
Definition: Factor.h:130
set noclip points set clip one set noclip two set bar set border lt lw set xdata set ydata set zdata set x2data set y2data set boxwidth set dummy y set format x g set format y g set format x2 g set format y2 g set format z g set angles radians set nogrid set key title set key left top Right noreverse box linetype linewidth samplen spacing width set nolabel set noarrow set nologscale set logscale x set set pointsize set encoding default set nopolar set noparametric set set set set surface set nocontour set clabel set mapping cartesian set nohidden3d set cntrparam order set cntrparam linear set cntrparam levels auto set cntrparam points set size set set xzeroaxis lt lw set x2zeroaxis lt lw set yzeroaxis lt lw set y2zeroaxis lt lw set tics in set ticslevel set tics set mxtics default set mytics default set mx2tics default set my2tics default set xtics border mirror norotate autofreq set ytics border mirror norotate autofreq set ztics border nomirror norotate autofreq set nox2tics set noy2tics set timestamp bottom norotate offset
std::pair< Matrix, Vector > jacobian() const override
Returns (dense) A,b pair associated with factor, bakes in the weights.
KeyVector keys_
The keys involved in this factor.
Definition: Factor.h:72
Definition: Half.h:150
size_t rows() const
GaussianFactorGraph factors(list_of(factor1)(factor2)(factor3))
VectorValues hessianDiagonal() const
Return the diagonal of the Hessian for this factor.
Vector & at(Key j)
Definition: VectorValues.h:137
std::pair< boost::shared_ptr< GaussianConditional >, boost::shared_ptr< GaussianFactor > > EliminatePreferCholesky(const GaussianFactorGraph &factors, const Ordering &keys)
static SymmetricBlockMatrix LikeActiveViewOf(const SymmetricBlockMatrix &other)
ptrdiff_t DenseIndex
The index type for Eigen objects.
Definition: types.h:67
void g(const string &key, int i)
Definition: testBTree.cpp:43
const KeyFormatter & formatter
std::pair< iterator, bool > tryInsert(Key j, const Vector &value)
Definition: VectorValues.h:207
Matrix augmentedInformation() const override
const SymmetricBlockMatrix & info() const
Return underlying information matrix.
double error(const VectorValues &c) const override
double constantTerm() const
void Allocate(const Scatter &scatter)
Allocate for given scatter pattern.
#define gttic(label)
Definition: timing.h:280
std::pair< boost::shared_ptr< GaussianConditional >, boost::shared_ptr< HessianFactor > > EliminateCholesky(const GaussianFactorGraph &factors, const Ordering &keys)
FastVector< Key > KeyVector
Define collection type once and for all - also used in wrappers.
Definition: Key.h:86
bool empty() const override
void setDiagonalBlock(DenseIndex I, const XprType &xpr)
Set a diagonal block. Only the upper triangular portion of xpr is evaluated.
Eigen::VectorXd Vector
Definition: Vector.h:38
Values result
const_iterator begin() const
Definition: Factor.h:127
Vector diagonal(DenseIndex J) const
Get the diagonal of the J&#39;th diagonal block.
boost::shared_ptr< This > shared_ptr
A shared_ptr to this class.
Matrix information() const override
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
Point2(* f)(const Point3 &, OptionalJacobian< 2, 3 >)
RealScalar alpha
Contains the HessianFactor class, a general quadratic factor.
RealScalar s
void updateDiagonalBlock(DenseIndex I, const XprType &xpr)
Increment the diagonal block by the values in xpr. Only reads the upper triangular part of xpr...
Expression of a selfadjoint matrix from a triangular part of a dense matrix.
Matrix augmentedJacobian() const override
Conditional Gaussian Base class.
Linear Factor Graph where all factors are Gaussians.
constBlock aboveDiagonalBlock(DenseIndex I, DenseIndex J) const
Get block above the diagonal (I, J).
boost::shared_ptr< GaussianConditional > eliminateCholesky(const Ordering &keys)
static const Matrix I
Definition: lago.cpp:35
JacobiRotation< float > J
Eigen::TriangularView< constBlock, Eigen::Upper > triangularView(DenseIndex I, DenseIndex J) const
Return the square sub-matrix that contains blocks(i:j, i:j) as a triangular view. ...
const G & b
Definition: Group.h:83
SymmetricBlockMatrix info_
The full augmented information matrix, s.t. the quadratic error is 0.5*[x -1]&#39;H[x -1]...
boost::shared_ptr< This > shared_ptr
shared_ptr to this class
GaussianFactor::shared_ptr negate() const override
Exceptions that may be thrown by linear solver components.
const SharedDiagonal & get_model() const
bool equal_with_abs_tol(const Eigen::DenseBase< MATRIX > &A, const Eigen::DenseBase< MATRIX > &B, double tol=1e-9)
Definition: base/Matrix.h:84
void print(const std::string &s="", const KeyFormatter &formatter=DefaultKeyFormatter) const override
void setFullMatrix(const XprType &xpr)
Set the entire active matrix. Only reads the upper triangular part of xpr.
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
Matrix block(DenseIndex I, DenseIndex J) const
VerticalBlockMatrix split(DenseIndex nFrontals)
A thin wrapper around std::map that uses boost&#39;s fast_pool_allocator.
bool hasConstraints(const GaussianFactorGraph &factors)
boost::shared_ptr< Factor > shared_ptr
A shared_ptr to this class.
Definition: Factor.h:60
size_t size() const
Definition: Factor.h:135
const KeyVector & keys() const
Access the factor&#39;s involved variable keys.
Definition: Factor.h:124
std::pair< Matrix, Vector > jacobian() const override
Return (dense) matrix associated with factor.
#define gttoc(label)
Definition: timing.h:281
void choleskyPartial(DenseIndex nFrontals)
void setZero()
Set the entire active matrix zero.
Pose3 g1(Rot3(), Point3(100.0, 0.0, 300.0))
Eigen::SelfAdjointView< constBlock, Eigen::Upper > selfadjointView(DenseIndex I, DenseIndex J) const
Return the square sub-matrix that contains blocks(i:j, i:j).
Matrix augmentedJacobian() const override
A Gaussian factor using the canonical parameters (information form)
std::vector< T, typename internal::FastDefaultVectorAllocator< T >::type > FastVector
Definition: FastVector.h:34
m col(1)
DenseIndex getDim(const_iterator variable) const override
void updateOffDiagonalBlock(DenseIndex I, DenseIndex J, const XprType &xpr)
Indicate Cholesky factorization failure.
void hessianDiagonalAdd(VectorValues &d) const override
Add the current diagonal to a VectorValues instance.
const G double tol
Definition: Group.h:83
DenseIndex getDim(DenseIndex block) const
Number of dimensions for variable on this diagonal block.
Eigen::SelfAdjointView< Block, Eigen::Upper > diagonalBlock(DenseIndex J)
Return the J&#39;th diagonal block as a self adjoint view.
KeyVector::const_iterator const_iterator
Const iterator over keys.
Definition: Factor.h:67
void updateHessian(const KeyVector &keys, SymmetricBlockMatrix *info) const override
Vector gradient(Key key, const VectorValues &x) const override
Map< Matrix< T, Dynamic, Dynamic, ColMajor >, 0, OuterStride<> > matrix(T *data, int rows, int cols, int stride)
boost::shared_ptr< This > shared_ptr
shared_ptr to this class
DenseIndex nBlocks() const
Block count.
std::pair< VectorValues::iterator, bool > emplace(Key j, Args &&...args)
Definition: VectorValues.h:183
set noclip points set clip one set noclip two set bar set border lt lw set xdata set ydata set zdata set x2data set y2data set boxwidth set dummy x
Pose3 g2(g1.expmap(h *V1_g1))
DenseIndex rows() const
Row size.
static DenseIndex Slot(const CONTAINER &keys, Key key)
std::pair< GaussianConditional::shared_ptr, JacobianFactor::shared_ptr > EliminateQR(const GaussianFactorGraph &factors, const Ordering &keys)
std::map< Key, Matrix > hessianBlockDiagonal() const override
Return the block diagonal of the Hessian for this factor.
std::uint64_t Key
Integer nonlinear key type.
Definition: types.h:61
std::ptrdiff_t j
Timing utilities.
GTSAM_EXPORT void print(const std::string &str="", const KeyFormatter &keyFormatter=DefaultKeyFormatter) const
Definition: Ordering.cpp:260
Efficient incomplete Cholesky on rank-deficient matrices, todo: constrained Cholesky.
Vector vector() const


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