timing/DummyFactor.h
Go to the documentation of this file.
1 
7 #pragma once
8 
10 
11 namespace gtsam {
12 
16 template<typename CAMERA> //
17 class DummyFactor: public RegularImplicitSchurFactor<CAMERA> {
18 
19 public:
20 
22  typedef std::pair<Key, Matrix2D> KeyMatrix2D;
23 
25  }
26 
27  DummyFactor(const std::vector<KeyMatrix2D>& Fblocks, const Matrix& E,
28  const Matrix3& P, const Vector& b) :
29  RegularImplicitSchurFactor<CAMERA>(Fblocks, E, P, b) {
30  }
31 
32  virtual ~DummyFactor() {
33  }
34 
35 public:
36 
40  void multiplyHessian(double alpha, const VectorValues& x,
41  VectorValues& y) const {
42 
43  for(const KeyMatrix2D& Fi: this->Fblocks_) {
44  static const Vector empty;
45  Key key = Fi.first;
46  std::pair<VectorValues::iterator, bool> it = y.tryInsert(key, empty);
47  Vector& yi = it.first->second;
48  yi = x.at(key);
49  }
50  }
51 
52 };
53 // DummyFactor
54 
55 }
56 
DummyFactor(const std::vector< KeyMatrix2D > &Fblocks, const Matrix &E, const Matrix3 &P, const Vector &b)
std::pair< Key, Matrix2D > KeyMatrix2D
Scalar * y
Eigen::MatrixXd Matrix
Definition: base/Matrix.h:43
Vector & at(Key j)
Definition: VectorValues.h:137
std::pair< iterator, bool > tryInsert(Key j, const Vector &value)
Definition: VectorValues.h:207
Eigen::VectorXd Vector
Definition: Vector.h:38
void multiplyHessian(double alpha, const VectorValues &x, VectorValues &y) const
Dummy version to measure overhead of key access.
RealScalar alpha
Eigen::Matrix< double, 2, CAMERA::dimension > Matrix2D
traits
Definition: chartTesting.h:28
A new type of linear factor (GaussianFactor), which is subclass of GaussianFactor.
The matrix class, also used for vectors and row-vectors.
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
std::uint64_t Key
Integer nonlinear key type.
Definition: types.h:61


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