33 using namespace gtsam;
36 const Matrix26
F0 = Matrix26::Ones();
37 const Matrix26
F1 = 2 * Matrix26::Ones();
38 const Matrix26
F3 = 3 * Matrix26::Ones();
39 const vector<Matrix26, Eigen::aligned_allocator<Matrix26> >
FBlocks {
F0,
F1,
F3};
45 TEST( regularImplicitSchurFactor, creation ) {
48 E.block<2,2>(0, 0) = I_2x2;
49 E.block<2,3>(2, 0) = 2 * Matrix::Ones(2, 3);
50 Matrix3
P = (E.transpose() *
E).
inverse();
57 TEST( regularImplicitSchurFactor, addHessianMultiply ) {
60 E.block<2,2>(0, 0) = I_2x2;
61 E.block<2,3>(2, 0) = 2 * Matrix::Ones(2, 3);
62 E.block<2,2>(4, 1) = I_2x2;
63 Matrix3
P = (E.transpose() *
E).
inverse();
67 {1, Vector::Constant(6, 4)},
68 {2, Vector::Constant(6, 0)},
69 {3, Vector::Constant(6, 8)}};
72 {1, Vector::Constant(6, -40)},
73 {2, Vector::Constant(6, 0)},
74 {3, Vector::Constant(6, 279)}};
77 size_t M=4,
m = 3,
d = 6;
79 F <<
F0, Matrix::Zero(2,
d * 3), Matrix::Zero(2,
d),
F1, Matrix::Zero(2,
d*2), Matrix::Zero(2,
d * 3),
F3;
83 Vector x = xvalues.vector(keys2);
104 double*
y =
new double[24];
105 double* xdata = x.data();
108 std::fill(y, y + 24, 0);
122 double expectedError = 11875.083333333334;
155 std::fill(y, y + 24, 0);
165 expectedVV.
insert(0,-3.5*Vector::Ones(6));
166 expectedVV.
insert(1,10*Vector::Ones(6)/3);
167 expectedVV.
insert(3,-19.5*Vector::Ones(6));
190 std::fill(y, y + 24, 0);
202 TEST(regularImplicitSchurFactor, hessianDiagonal)
215 E.block<2,3>(0, 0) << 1,2,3,4,5,6;
216 E.block<2,3>(2, 0) << 1,2,3,4,5,6;
217 E.block<2,3>(4, 0) << 0.5,1,2,3,4,5;
218 Matrix3
P = (E.transpose() *
E).
inverse();
223 expected.
insert(0, 1.195652*Vector::Ones(6));
224 expected.
insert(1, 4.782608*Vector::Ones(6));
225 expected.
insert(3, 7.043478*Vector::Ones(6));
231 Matrix FtE0 =
F0.transpose() * E.block<2,3>(0, 0);
232 Matrix FtE1 =
F1.transpose() * E.block<2,3>(2, 0);
233 Matrix FtE3 =
F3.transpose() * E.block<2,3>(4, 0);
242 Matrix E0 = E.block<2,3>(0, 0);
253 Matrix M1b = F0t*(E0*P*E0.transpose()*
F0);
254 Matrix M2b = F0t*E0*P*E0.transpose()*
F0;
const Matrix & getPointCovariance() const
double errorJF(const VectorValues &x) const
Matrix< RealScalar, Dynamic, Dynamic > M
static int runAllTests(TestResult &result)
double error(const VectorValues &c) const override
TEST(regularImplicitSchurFactor, creation)
noiseModel::Diagonal::shared_ptr model
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)
EIGEN_DONT_INLINE Scalar zero()
bool assert_equal(const Matrix &expected, const Matrix &actual, double tol)
A factor with a quadratic error function - a Gaussian.
void hessianDiagonal(double *d) const override
add the contribution of this factor to the diagonal of the hessian d(output) = d(input) + deltaHessia...
void multiplyHessianAdd(double alpha, const VectorValues &x, VectorValues &y) const override
iterator insert(const std::pair< Key, Vector > &key_value)
#define EXPECT_DOUBLES_EQUAL(expected, actual, threshold)
EIGEN_DEVICE_FUNC const InverseReturnType inverse() const
double error(const VectorValues &x) const override
VectorValues gradientAtZero() const override
Expose base class gradientAtZero.
M1<< 1, 2, 3, 4, 5, 6, 7, 8, 9, 10, 11, 12;Map< MatrixXf > M2(M1.data(), 6, 2)
#define EXPECT(condition)
Array< double, 1, 3 > e(1./3., 0.5, 2.)
Calibrated camera for which only pose is unknown.
#define LONGS_EQUAL(expected, actual)
noiseModel::Diagonal::shared_ptr SharedDiagonal
std::vector< MatrixZD, Eigen::aligned_allocator< MatrixZD > > FBlocks
A subclass of GaussianFactor specialized to structureless SFM.
VectorValues gradientAtZero() const override
Matrix information() const override
Compute full information matrix
std::map< Key, Matrix > hessianBlockDiagonal() const override
Return the block diagonal of the Hessian for this factor.
FastVector< Key > KeyVector
Define collection type once and for all - also used in wrappers.
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
Eigen::Matrix< double, Eigen::Dynamic, 1 > Vector
Matrix augmentedInformation() const override
Compute full augmented information matrix
std::map< Key, Matrix > hessianBlockDiagonal() const override
Return the block diagonal of the Hessian for this factor.
void hessianDiagonal(double *d) const override
Raw memory access version of hessianDiagonal.