20 template<
class CAMERA>
32 typedef typename CAMERA::Measurement Z;
36 typedef Eigen::Matrix<double, ZDim, D>
MatrixZD;
39 const std::vector<MatrixZD, Eigen::aligned_allocator<MatrixZD> >
FBlocks_;
52 const std::vector<
MatrixZD, Eigen::aligned_allocator<MatrixZD> >& FBlocks,
const Matrix& E,
const Matrix& P,
61 std::vector<MatrixZD, Eigen::aligned_allocator<MatrixZD> >& FBlocks()
const {
65 const Matrix& E()
const {
69 const Vector& b()
const {
73 const Matrix& getPointCovariance()
const {
79 DefaultKeyFormatter)
const {
80 std::cout <<
" RegularImplicitSchurFactor " << std::endl;
82 for (
size_t pos = 0; pos <
size(); ++pos) {
83 std::cout <<
"Fblock:\n" <<
FBlocks_[pos] << std::endl;
86 std::cout <<
"E:\n" <<
E_ << std::endl;
87 std::cout <<
"b:\n" <<
b_.transpose() << std::endl;
92 const This* f = dynamic_cast<const This*>(&lf);
95 for (
size_t k = 0; k <
FBlocks_.size(); ++k) {
113 throw std::runtime_error(
114 "RegularImplicitSchurFactor::updateHessian non implemented");
117 throw std::runtime_error(
118 "RegularImplicitSchurFactor::augmentedJacobian non implemented");
121 virtual std::pair<Matrix, Vector>
jacobian()
const {
122 throw std::runtime_error(
123 "RegularImplicitSchurFactor::jacobian non implemented");
124 return std::make_pair(Matrix(), Vector());
139 int m = this->
keys_.size();
141 return augmented.block(0, 0, M, M);
149 for (
size_t k = 0; k <
size(); ++k) {
155 Eigen::Matrix<double, D, 3> FtE = Fj.transpose()
158 Eigen::Matrix<double, D, 1> dj;
159 for (
int k = 0; k <
D; ++k) {
161 dj(k) = Fj.col(k).squaredNorm();
178 typedef Eigen::Matrix<double, D, 1> DVector;
179 typedef Eigen::Map<DVector> DMap;
181 for (
size_t pos = 0; pos <
size(); ++pos) {
187 Eigen::Matrix<double, D, 3> FtE = Fj.transpose()
191 for (
int k = 0; k <
D; ++k) {
192 dj(k) = Fj.col(k).squaredNorm();
196 DMap(d +
D * j) += dj;
202 std::map<Key, Matrix> blocks;
204 for (
size_t pos = 0; pos <
size(); ++pos) {
213 const Matrix23& Ej =
E_.block<
ZDim, 3>(
ZDim * pos, 0);
214 blocks[j] = Fj.transpose()
227 return boost::make_shared<RegularImplicitSchurFactor<CAMERA> >(
keys_,
229 throw std::runtime_error(
230 "RegularImplicitSchurFactor::clone non implemented");
237 return boost::make_shared<RegularImplicitSchurFactor<CAMERA> >(
keys_,
239 throw std::runtime_error(
240 "RegularImplicitSchurFactor::negate non implemented");
245 void multiplyHessianAdd(
const Matrix& F,
const Matrix& E,
246 const Matrix& PointCovariance,
double alpha,
const Vector& x, Vector& y) {
248 Vector d1 = E.transpose() *
e1;
249 Vector d2 = PointCovariance * d1;
251 Vector e3 = alpha * (
e1 - e2);
252 y += F.transpose() * e3;
255 typedef std::vector<Vector2, Eigen::aligned_allocator<Vector2>> Error2s;
265 for (
size_t k = 0; k <
size(); k++)
266 d1 +=
E_.block<
ZDim, 3>(
ZDim * k, 0).transpose()
273 for (
size_t k = 0; k <
size(); k++)
294 for (
size_t k = 0; k <
size(); ++k)
299 for (
size_t k = 0; k <
size(); ++k)
300 result +=
dot(
e1[k], e2[k]);
302 double f =
b_.squaredNorm();
303 return 0.5 * (result + f);
316 for (
size_t k = 0; k <
size(); ++k)
321 for (
size_t k = 0; k <
size(); ++k)
322 result +=
dot(e2[k], e2[k]);
335 for (
size_t k = 0; k <
size(); k++)
336 d1 +=
E_.block<
ZDim, 3>(
ZDim * k, 0).transpose() *
e1[k];
342 for (
size_t k = 0; k <
size(); k++)
347 mutable Error2s
e1, e2;
356 typedef Eigen::Matrix<double, D, 1> DVector;
357 typedef Eigen::Map<DVector> DMap;
358 typedef Eigen::Map<const DVector> ConstDMap;
365 for (
size_t k = 0; k <
size(); ++k) {
373 for (
size_t k = 0; k <
size(); ++k) {
375 DMap(y +
D * key) +=
FBlocks_[k].transpose() * alpha * e2[k];
379 void multiplyHessianAdd(
double alpha,
const double* x,
double* y,
380 std::vector<size_t>
keys)
const {
395 for (
size_t k = 0; k <
size(); ++k)
401 for (
size_t k = 0; k <
size(); ++k) {
403 static const Vector
empty;
404 std::pair<VectorValues::iterator, bool> it = y.
tryInsert(key,
empty);
405 Vector& yi = it.first->second;
408 yi = Vector::Zero(
FBlocks_[k].cols());
409 yi +=
FBlocks_[k].transpose() * alpha * e2[k];
419 for (
size_t k = 0; k <
size(); ++k) {
420 static const Vector
empty;
422 std::pair<VectorValues::iterator, bool> it = y.
tryInsert(key,
empty);
423 Vector& yi = it.first->second;
435 for (
size_t k = 0; k <
size(); k++)
441 for (
size_t k = 0; k <
size(); ++k) {
456 typedef Eigen::Matrix<double, D, 1> DVector;
457 typedef Eigen::Map<DVector> DMap;
462 for (
size_t k = 0; k <
size(); k++)
466 for (
size_t k = 0; k <
size(); ++k) {
468 DMap(d +
D * j) += -
FBlocks_[k].transpose() * e2[k];
474 throw std::runtime_error(
475 "gradient for RegularImplicitSchurFactor is not implemented yet");
481 template<
class CAMERA>
484 template<
class CAMERA>
489 RegularImplicitSchurFactor<CAMERA> > {
virtual GaussianFactor::shared_ptr negate() const
Construct the corresponding anti-factor to negate information stored stored in this factor.
Definition: RegularImplicitSchurFactor.h:236
RegularImplicitSchurFactor()
Constructor.
Definition: RegularImplicitSchurFactor.h:47
void multiplyHessianAdd(double alpha, const VectorValues &x, VectorValues &y) const
Hessian-vector multiply, i.e.
Definition: RegularImplicitSchurFactor.h:387
double dot(const V1 &a, const V2 &b)
Dot product.
Definition: Vector.h:162
This is the base class for all factor types.
Definition: Factor.h:54
ptrdiff_t DenseIndex
The index type for Eigen objects.
Definition: types.h:63
virtual std::pair< Matrix, Vector > jacobian() const
Return the dense Jacobian and right-hand-side , with the noise models baked into A and b.
Definition: RegularImplicitSchurFactor.h:121
virtual Matrix augmentedJacobian() const
Return a dense Jacobian matrix, augmented with b with the noise models baked into A and b.
Definition: RegularImplicitSchurFactor.h:116
virtual void hessianDiagonal(double *d) const
add the contribution of this factor to the diagonal of the hessian d(output) = d(input) + deltaHessia...
Definition: RegularImplicitSchurFactor.h:175
static const int ZDim
Measurement dimension.
Definition: RegularImplicitSchurFactor.h:34
void multiplyHessianAdd(double alpha, const double *x, double *y) const
double* Hessian-vector multiply, i.e.
Definition: RegularImplicitSchurFactor.h:353
void projectError2(const Error2s &e1, Error2s &e2) const
Calculate corrected error Q*(e-ZDim*b) = (I - E*P*E')*(e-ZDim*b)
Definition: RegularImplicitSchurFactor.h:260
A set of cameras, all with their own calibration.
Definition: CameraSet.h:35
Error2s e1
Scratch space for multiplyHessianAdd.
Definition: RegularImplicitSchurFactor.h:347
bool equal_with_abs_tol(const Eigen::DenseBase< MATRIX > &A, const Eigen::DenseBase< MATRIX > &B, double tol=1e-9)
equals with a tolerance
Definition: Matrix.h:82
const std::vector< MatrixZD, Eigen::aligned_allocator< MatrixZD > > FBlocks_
All ZDim*D F blocks (one for each camera)
Definition: RegularImplicitSchurFactor.h:39
std::uint64_t Key
Integer nonlinear key type.
Definition: types.h:57
Eigen::Matrix< double, ZDim, D > MatrixZD
type of an F block
Definition: RegularImplicitSchurFactor.h:36
A helper that implements the traits interface for GTSAM types.
Definition: Testable.h:150
An abstract virtual base class for JacobianFactor and HessianFactor.
Definition: GaussianFactor.h:38
virtual bool empty() const
Test whether the factor is empty.
Definition: RegularImplicitSchurFactor.h:232
boost::shared_ptr< This > shared_ptr
shared_ptr to this class
Definition: RegularImplicitSchurFactor.h:25
boost::function< std::string(Key)> KeyFormatter
Typedef for a function to format a key, i.e. to convert it to a string.
Definition: Key.h:33
virtual DenseIndex getDim(const_iterator variable) const
Degrees of freedom of camera.
Definition: RegularImplicitSchurFactor.h:107
Eigen::SelfAdjointView< constBlock, Eigen::Upper > selfadjointView(DenseIndex I, DenseIndex J) const
Return the square sub-matrix that contains blocks(i:j, i:j).
Definition: SymmetricBlockMatrix.h:161
RegularImplicitSchurFactor.
Definition: RegularImplicitSchurFactor.h:21
Eigen::Matrix< double, D, D > MatrixDD
camera hessian
Definition: RegularImplicitSchurFactor.h:37
virtual void gradientAtZero(double *d) const
Calculate gradient, which is -F'Q*b, see paper - RAW MEMORY ACCESS.
Definition: RegularImplicitSchurFactor.h:453
size_t size() const
Definition: Factor.h:129
virtual Matrix information() const
Compute full information matrix
Definition: RegularImplicitSchurFactor.h:137
This class represents a collection of vector-valued variables associated each with a unique integer i...
Definition: VectorValues.h:73
const Matrix PointCovariance_
the 3*3 matrix P = inv(E'E) (2*2 if degenerate)
Definition: RegularImplicitSchurFactor.h:40
void print(const std::string &s="Factor", const KeyFormatter &formatter=DefaultKeyFormatter) const
print
Definition: Factor.cpp:29
virtual Matrix augmentedInformation() const
Compute full augmented information matrix
Definition: RegularImplicitSchurFactor.h:128
FastVector< Key > KeyVector
Define collection type once and for all - also used in wrappers.
Definition: Key.h:56
A manifold defines a space in which there is a notion of a linear tangent space that can be centered ...
Definition: concepts.h:30
virtual GaussianFactor::shared_ptr clone() const
Clone a factor (make a deep copy)
Definition: RegularImplicitSchurFactor.h:226
RegularImplicitSchurFactor(const KeyVector &keys, const std::vector< MatrixZD, Eigen::aligned_allocator< MatrixZD > > &FBlocks, const Matrix &E, const Matrix &P, const Vector &b)
Construct from blocks of F, E, inv(E'*E), and RHS vector b.
Definition: RegularImplicitSchurFactor.h:51
void print(const std::string &s="", const KeyFormatter &keyFormatter=DefaultKeyFormatter) const
print
Definition: RegularImplicitSchurFactor.h:78
virtual VectorValues hessianDiagonal() const
Return the diagonal of the Hessian for this factor.
Definition: RegularImplicitSchurFactor.h:145
virtual ~RegularImplicitSchurFactor()
Destructor.
Definition: RegularImplicitSchurFactor.h:58
static SymmetricBlockMatrix SchurComplement(const FBlocks &Fs, const Matrix &E, const Eigen::Matrix< double, N, N > &P, const Vector &b)
Do Schur complement, given Jacobian as Fs,E,P, return SymmetricBlockMatrix G = F' * F - F' * E * P * ...
Definition: CameraSet.h:149
Base class to create smart factors on poses or cameras.
Definition: SymmetricBlockMatrix.h:51
const KeyVector & keys() const
Access the factor's involved variable keys.
Definition: Factor.h:118
Global functions in a separate testing namespace.
Definition: chartTesting.h:28
KeyVector keys_
The keys involved in this factor.
Definition: Factor.h:72
virtual void updateHessian(const KeyVector &keys, SymmetricBlockMatrix *info) const
Update an information matrix by adding the information corresponding to this factor (used internally ...
Definition: RegularImplicitSchurFactor.h:111
void projectError(const Error2s &e1, Error2s &e2) const
Calculate corrected error Q*e = (I - E*P*E')*e.
Definition: RegularImplicitSchurFactor.h:330
iterator insert(const std::pair< Key, Vector > &key_value)
Insert a vector value with key j.
Definition: VectorValues.cpp:78
static const int D
Camera dimension.
Definition: RegularImplicitSchurFactor.h:33
virtual std::map< Key, Matrix > hessianBlockDiagonal() const
Return the block diagonal of the Hessian for this factor.
Definition: RegularImplicitSchurFactor.h:201
void multiplyHessianDummy(double alpha, const VectorValues &x, VectorValues &y) const
Dummy version to measure overhead of key access.
Definition: RegularImplicitSchurFactor.h:416
KeyVector::const_iterator const_iterator
Const iterator over keys.
Definition: Factor.h:67
const Vector b_
2m-dimensional RHS vector
Definition: RegularImplicitSchurFactor.h:42
bool equals(const GaussianFactor &lf, double tol) const
equals
Definition: RegularImplicitSchurFactor.h:91
std::pair< iterator, bool > tryInsert(Key j, const Vector &value)
insert that mimics the STL map insert - if the value already exists, the map is not modified and an i...
Definition: VectorValues.h:199
VectorValues gradientAtZero() const
Calculate gradient, which is -F'Q*b, see paper.
Definition: RegularImplicitSchurFactor.h:431
Vector gradient(Key key, const VectorValues &x) const
Gradient wrt a key at any values.
Definition: RegularImplicitSchurFactor.h:473
RegularImplicitSchurFactor This
Typedef to this class.
Definition: RegularImplicitSchurFactor.h:24
virtual double error(const VectorValues &x) const
Print for testable.
Definition: RegularImplicitSchurFactor.h:287
const Matrix E_
The 2m*3 E Jacobian with respect to the point.
Definition: RegularImplicitSchurFactor.h:41
Vector & at(Key j)
Read/write access to the vector value with key j, throws std::out_of_range if j does not exist,...
Definition: VectorValues.h:136
boost::shared_ptr< This > shared_ptr
shared_ptr to this class
Definition: GaussianFactor.h:42