BinaryJacobianFactor.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 
21 #pragma once
22 
25 #include <gtsam/base/timing.h>
26 
27 namespace gtsam {
28 
32 template<int M, int N1, int N2>
34 
39  const SharedDiagonal& model = SharedDiagonal()) :
40  JacobianFactor(key1, A1, key2, A2, b, model) {
41  }
42 
43  inline Key key1() const {
44  return keys_[0];
45  }
46  inline Key key2() const {
47  return keys_[1];
48  }
49 
50  // Fixed-size matrix update
51  void updateHessian(const KeyVector& infoKeys,
52  SymmetricBlockMatrix* info) const override {
53  gttic(updateHessian_BinaryJacobianFactor);
54  // Whiten the factor if it has a noise model
55  const SharedDiagonal& model = get_model();
56  if (model && !model->isUnit()) {
57  if (model->isConstrained())
58  throw std::invalid_argument(
59  "BinaryJacobianFactor::updateHessian: cannot update information with "
60  "constrained noise model");
61  BinaryJacobianFactor whitenedFactor(key1(), model->Whiten(getA(begin())),
62  key2(), model->Whiten(getA(end())), model->whiten(getb()));
63  whitenedFactor.updateHessian(infoKeys, info);
64  } else {
65  // First build an array of slots
66  DenseIndex slot1 = Slot(infoKeys, key1());
67  DenseIndex slot2 = Slot(infoKeys, key2());
68  DenseIndex slotB = info->nBlocks() - 1;
69 
70  const Matrix& Ab = Ab_.matrix();
73  Eigen::Block<const Matrix, M, 1> b(Ab, 0, N1 + N2);
74 
75  // We perform I += A'*A to the upper triangle
76  info->diagonalBlock(slot1).rankUpdate(A1.transpose());
77  info->updateOffDiagonalBlock(slot1, slot2, A1.transpose() * A2);
78  info->updateOffDiagonalBlock(slot1, slotB, A1.transpose() * b);
79  info->diagonalBlock(slot2).rankUpdate(A2.transpose());
80  info->updateOffDiagonalBlock(slot2, slotB, A2.transpose() * b);
81  info->updateDiagonalBlock(slotB, b.transpose() * b);
82  }
83  }
84 };
85 
86 template<int M, int N1, int N2>
87 struct traits<BinaryJacobianFactor<M, N1, N2> > : Testable<
88  BinaryJacobianFactor<M, N1, N2> > {
89 };
90 
91 } //namespace gtsam
Matrix< RealScalar, Dynamic, Dynamic > M
Definition: bench_gemm.cpp:38
Access to matrices via blocks of pre-defined sizes. Used in GaussianFactor and GaussianConditional.
noiseModel::Diagonal::shared_ptr model
constABlock getA() const
const Matrix & matrix() const
Eigen::MatrixXd Matrix
Definition: base/Matrix.h:43
const_iterator end() const
Definition: Factor.h:130
KeyVector keys_
The keys involved in this factor.
Definition: Factor.h:72
ptrdiff_t DenseIndex
The index type for Eigen objects.
Definition: types.h:67
else if n * info
#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
const constBVector getb() const
const_iterator begin() const
Definition: Factor.h:127
void updateDiagonalBlock(DenseIndex I, const XprType &xpr)
Increment the diagonal block by the values in xpr. Only reads the upper triangular part of xpr...
const G & b
Definition: Group.h:83
const SharedDiagonal & get_model() const
noiseModel::Diagonal::shared_ptr SharedDiagonal
Definition: NoiseModel.h:736
traits
Definition: chartTesting.h:28
void updateHessian(const KeyVector &infoKeys, SymmetricBlockMatrix *info) const override
Expression of a fixed-size or dynamic-size block.
Definition: Block.h:103
VerticalBlockMatrix Ab_
void updateOffDiagonalBlock(DenseIndex I, DenseIndex J, const XprType &xpr)
BinaryJacobianFactor(Key key1, const Eigen::Matrix< double, M, N1 > &A1, Key key2, const Eigen::Matrix< double, M, N2 > &A2, const Eigen::Matrix< double, M, 1 > &b, const SharedDiagonal &model=SharedDiagonal())
Constructor.
Eigen::SelfAdjointView< Block, Eigen::Upper > diagonalBlock(DenseIndex J)
Return the J&#39;th diagonal block as a self adjoint view.
The matrix class, also used for vectors and row-vectors.
DenseIndex nBlocks() const
Block count.
static DenseIndex Slot(const CONTAINER &keys, Key key)
std::uint64_t Key
Integer nonlinear key type.
Definition: types.h:61
Timing utilities.


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