24 template<
class CAMERA>
43 const std::vector<MatrixZD, Eigen::aligned_allocator<MatrixZD> >
FBlocks_;
65 std::vector<MatrixZD, Eigen::aligned_allocator<MatrixZD> >&
FBlocks()
const {
84 std::cout <<
" RegularImplicitSchurFactor " << std::endl;
87 std::cout <<
"Fblock:\n" << FBlocks_[
pos] << std::endl;
89 std::cout <<
"PointCovariance:\n" << PointCovariance_ << std::endl;
90 std::cout <<
"E:\n" << E_ << std::endl;
91 std::cout <<
"b:\n" << b_.transpose() << std::endl;
96 const This*
f =
dynamic_cast<const This*
>(&lf);
99 for (
size_t k = 0; k < FBlocks_.size(); ++k) {
117 throw std::runtime_error(
118 "RegularImplicitSchurFactor::updateHessian non implemented");
121 throw std::runtime_error(
122 "RegularImplicitSchurFactor::augmentedJacobian non implemented");
125 std::pair<Matrix, Vector>
jacobian()
const override {
126 throw std::runtime_error(
127 "RegularImplicitSchurFactor::jacobian non implemented");
142 int m = this->
keys_.size();
144 return augmented.block(0, 0, M, M);
153 for (
size_t k = 0; k <
size(); ++k) {
158 const MatrixZD& Fj = FBlocks_[k];
160 * E_.block<
ZDim, 3>(ZDim * k, 0);
163 for (
int k = 0; k <
D; ++k) {
165 dj(k) = Fj.col(k).squaredNorm();
168 dj(k) -= FtE.row(k) * PointCovariance_ * FtE.row(k).transpose();
173 result.first->second += dj;
193 const MatrixZD& Fj = FBlocks_[
pos];
195 * E_.block<
ZDim, 3>(ZDim *
pos, 0);
198 for (
int k = 0; k <
D; ++k) {
199 dj(k) = Fj.col(k).squaredNorm();
201 dj(k) -= FtE.row(k) * PointCovariance_ * FtE.row(k).transpose();
203 DMap(d + D * j) += dj;
209 std::map<Key, Matrix> blocks;
214 const MatrixZD& Fj = FBlocks_[
pos];
220 const Matrix23& Ej = E_.block<
ZDim, 3>(ZDim *
pos, 0);
221 blocks[
j] = Fj.transpose()
222 * (Fj - Ej * PointCovariance_ * Ej.transpose() * Fj);
234 return boost::make_shared<RegularImplicitSchurFactor<CAMERA> >(
keys_,
236 throw std::runtime_error(
237 "RegularImplicitSchurFactor::clone non implemented");
245 return boost::make_shared<RegularImplicitSchurFactor<CAMERA> >(
keys_,
247 throw std::runtime_error(
248 "RegularImplicitSchurFactor::negate non implemented");
260 y += F.transpose() * e3;
263 typedef std::vector<Vector2, Eigen::aligned_allocator<Vector2>>
Error2s;
273 for (
size_t k = 0; k <
size(); k++)
274 d1 += E_.block<ZDim, 3>(ZDim * k, 0).transpose()
275 * (e1[k] - ZDim * b_.segment<ZDim>(k *
ZDim));
281 for (
size_t k = 0; k <
size(); k++)
282 e2[k] = e1[k] - ZDim * b_.segment<ZDim>(k * ZDim)
283 - E_.block<
ZDim, 3>(ZDim * k, 0) * d2;
302 for (
size_t k = 0; k <
size(); ++k)
307 for (
size_t k = 0; k <
size(); ++k)
310 double f = b_.squaredNorm();
311 return 0.5 * (result +
f);
324 for (
size_t k = 0; k <
size(); ++k)
325 e1[k] = FBlocks_[k] * x.
at(
keys_[k]) - b_.segment<ZDim>(k *
ZDim);
329 for (
size_t k = 0; k <
size(); ++k)
343 for (
size_t k = 0; k <
size(); k++)
344 d1 += E_.block<ZDim, 3>(ZDim * k, 0).transpose() * e1[k];
350 for (
size_t k = 0; k <
size(); k++)
351 e2[k] = e1[k] - E_.block<ZDim, 3>(ZDim * k, 0) *
d2;
373 for (
size_t k = 0; k <
size(); ++k) {
375 e1[k] = FBlocks_[k] * ConstDMap(x + D * key);
381 for (
size_t k = 0; k <
size(); ++k) {
383 DMap(y + D * key) += FBlocks_[k].transpose() * alpha * e2[k];
388 std::vector<size_t>
keys)
const {
402 for (
size_t k = 0; k <
size(); ++k)
403 e1[k] = FBlocks_[k] * x.
at(
keys_[k]);
408 for (
size_t k = 0; k <
size(); ++k) {
411 std::pair<VectorValues::iterator, bool> it = y.
tryInsert(key, empty);
412 Vector& yi = it.first->second;
415 yi = Vector::Zero(FBlocks_[k].
cols());
416 yi += FBlocks_[k].transpose() * alpha * e2[k];
426 for (
size_t k = 0; k <
size(); ++k) {
429 std::pair<VectorValues::iterator, bool> it = y.
tryInsert(key, empty);
430 Vector& yi = it.first->second;
442 for (
size_t k = 0; k <
size(); k++)
443 e1[k] = b_.segment<ZDim>(ZDim * k);
448 for (
size_t k = 0; k <
size(); ++k) {
450 g.
insert(key, -FBlocks_[k].transpose() * e2[k]);
469 for (
size_t k = 0; k <
size(); k++)
470 e1[k] = b_.segment<ZDim>(ZDim * k);
473 for (
size_t k = 0; k <
size(); ++k) {
475 DMap(d + D * j) += -FBlocks_[k].transpose() * e2[k];
481 throw std::runtime_error(
482 "gradient for RegularImplicitSchurFactor is not implemented yet");
488 template<
class CAMERA>
491 template<
class CAMERA>
496 RegularImplicitSchurFactor<CAMERA> > {
static const int D
Camera dimension.
Matrix< RealScalar, Dynamic, Dynamic > M
double errorJF(const VectorValues &x) const
void updateHessian(const KeyVector &keys, SymmetricBlockMatrix *info) const override
double dot(const V1 &a, const V2 &b)
void print(const std::string &s="", const KeyFormatter &keyFormatter=DefaultKeyFormatter) const override
print
A matrix or vector expression mapping an existing array of data.
static void multiplyHessianAdd(const Matrix &F, const Matrix &E, const Matrix &PointCovariance, double alpha, const Vector &x, Vector &y)
Base class to create smart factors on poses or cameras.
GaussianFactor::shared_ptr negate() const override
boost::shared_ptr< This > shared_ptr
shared_ptr to this class
void hessianDiagonal(double *d) const override
add the contribution of this factor to the diagonal of the hessian d(output) = d(input) + deltaHessia...
GaussianFactor::shared_ptr clone() const override
KeyVector keys_
The keys involved in this factor.
void hessianDiagonalAdd(VectorValues &d) const override
Add the diagonal of the Hessian for this factor to existing VectorValues.
VectorValues hessianDiagonal() const
Return the diagonal of the Hessian for this factor.
A set of cameras, all with their own calibration.
static const KeyFormatter DefaultKeyFormatter
ptrdiff_t DenseIndex
The index type for Eigen objects.
void g(const string &key, int i)
std::pair< iterator, bool > tryInsert(Key j, const Vector &value)
void multiplyHessianAdd(double alpha, const VectorValues &x, VectorValues &y) const override
Hessian-vector multiply, i.e. y += F'alpha(I - E*P*E')*F*x.
double error(const VectorValues &x) const override
Error2s e1
Scratch space for multiplyHessianAdd.
RegularImplicitSchurFactor This
Typedef to this class.
RegularImplicitSchurFactor()
Constructor.
Eigen::Matrix< double, D, D > MatrixDD
camera hessian
const Matrix E_
The 2m*3 E Jacobian with respect to the point.
FastVector< Key > KeyVector
Define collection type once and for all - also used in wrappers.
Eigen::Matrix< double, ZDim, D > MatrixZD
type of an F block
std::vector< Vector2, Eigen::aligned_allocator< Vector2 > > Error2s
STL compatible allocator to use with types requiring a non standrad alignment.
GenericMeasurement< Point2, Point2 > Measurement
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.
std::function< std::string(Key)> KeyFormatter
Typedef for a function to format a key, i.e. to convert it to a string.
Point2(* f)(const Point3 &, OptionalJacobian< 2, 3 >)
const Matrix PointCovariance_
the 3*3 matrix P = inv(E'E) (2*2 if degenerate)
void projectError2(const Error2s &e1, Error2s &e2) const
Calculate corrected error Q*(e-ZDim*b) = (I - E*P*E')*(e-ZDim*b)
virtual void print(const std::string &s="Factor", const KeyFormatter &formatter=DefaultKeyFormatter) const
print
void multiplyHessianAdd(double alpha, const double *x, double *y) const
double* Hessian-vector multiply, i.e. y += F'alpha(I - E*P*E')*F*x RAW memory access! Assumes keys st...
const std::vector< MatrixZD, Eigen::aligned_allocator< MatrixZD > > FBlocks_
All ZDim*D F blocks (one for each camera)
std::vector< MatrixZD, Eigen::aligned_allocator< MatrixZD > > & FBlocks() const
boost::shared_ptr< This > shared_ptr
shared_ptr to this class
bool equal_with_abs_tol(const Eigen::DenseBase< MATRIX > &A, const Eigen::DenseBase< MATRIX > &B, double tol=1e-9)
void gradientAtZero(double *d) const override
Matrix augmentedJacobian() const override
~RegularImplicitSchurFactor() override
Destructor.
void projectError(const Error2s &e1, Error2s &e2) const
Calculate corrected error Q*e = (I - E*P*E')*e.
Vector gradient(Key key, const VectorValues &x) const override
Gradient wrt a key at any values.
VectorValues gradientAtZero() const override
const KeyVector & keys() const
Access the factor's involved variable keys.
Matrix information() const override
Compute full information matrix
static const int ZDim
Measurement dimension.
bool empty() const override
Eigen::SelfAdjointView< constBlock, Eigen::Upper > selfadjointView(DenseIndex I, DenseIndex J) const
Return the square sub-matrix that contains blocks(i:j, i:j).
std::map< Key, Matrix > hessianBlockDiagonal() const override
Return the block diagonal of the Hessian for this factor.
void multiplyHessianAdd(double alpha, const double *x, double *y, std::vector< size_t > keys) const
void multiplyHessianDummy(double alpha, const VectorValues &x, VectorValues &y) const
Dummy version to measure overhead of key access.
bool equals(const GaussianFactor &lf, double tol) const override
equals
KeyVector::const_iterator const_iterator
Const iterator over keys.
The matrix class, also used for vectors and row-vectors.
std::pair< VectorValues::iterator, bool > emplace(Key j, Args &&...args)
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
iterator insert(const std::pair< Key, Vector > &key_value)
const Vector b_
2m-dimensional RHS vector
DenseIndex getDim(const_iterator variable) const override
Degrees of freedom of camera.
const Matrix & getPointCovariance() const
std::uint64_t Key
Integer nonlinear key type.
Matrix augmentedInformation() const override
Compute full augmented information matrix
std::pair< Matrix, Vector > jacobian() const override
static SymmetricBlockMatrix SchurComplement(const FBlocks &Fs, const Matrix &E, const Eigen::Matrix< double, N, N > &P, const Vector &b)