35 using namespace gtsam;
46 expected{
key(3, 3),
key(2, 3),
key(1, 3),
key(3, 2),
key(2, 2),
54 double total_error = 0.;
55 for (
const GaussianFactor::shared_ptr& factor : fg)
56 total_error += factor->error(x);
101 auto Rc1 = *Ab1.eliminateSequential(ord);
113 const auto [
A,
b] =
Ab.jacobian(ordering);
114 const auto [
A1,
b1] = Ab1.jacobian(ordering);
115 const auto [A2,
b2] = Ab2.jacobian(ordering);
117 Matrix Abar(13 * 2, 9 * 2);
118 Abar.topRows(9 * 2) = Matrix::Identity(9 * 2, 9 * 2);
119 Abar.bottomRows(8) = A2.topRows(8) * R1.inverse();
141 const Vector expected_x1 = vec(xbar) + R1.inverse() * vec(y1);
153 const double alpha = 0.5;
155 for (
size_t i = 0;
i < 13;
i++) {
159 Vector ee1(13 * 2), ee2(13 * 2);
160 ee1 << Vector::Ones(9 * 2), Vector::Zero(4 * 2);
161 ee2 << Vector::Zero(9 * 2), Vector::Ones(4 * 2);
166 Vector expected_y = alpha * Abar.transpose() * ee1;
172 expected_y = alpha * Abar.transpose() * ee2;
177 Vector expected_g = Vector::Zero(18);
VectorValues zero() const
static int runAllTests(TestResult &result)
#define DOUBLES_EQUAL(expected, actual, threshold)
bool assert_equal(const Matrix &expected, const Matrix &actual, double tol)
double error(const VectorValues &y) const
Iterative methods, implementation.
Some functions to compute numerical derivatives.
V conjugateGradients(const S &Ab, V x, const ConjugateGradientParameters ¶meters, bool steepest)
Matrix< SCALARA, Dynamic, Dynamic, opt_A > A
static enum @1107 ordering
void g(const string &key, int i)
void transposeMultiplyAdd(double alpha, const Errors &e, VectorValues &y) const
static double error(const GaussianFactorGraph &fg, const VectorValues &x)
VectorValues optimize() const
Vector conjugateGradientDescent(const System &Ab, const Vector &x, const ConjugateGradientParameters ¶meters)
const MatrixNN & matrix() const
Return matrix.
#define EXPECT(condition)
Eigen::Triplet< double > T
Array< double, 1, 3 > e(1./3., 0.5, 2.)
Linear Factor Graph where all factors are Gaussians.
TEST(SubgraphPreconditioner, planarOrdering)
static ConjugateGradientParameters parameters
Matrix< Scalar, Dynamic, Dynamic > C
#define LONGS_EQUAL(expected, actual)
Ordering planarOrdering(size_t N)
std::pair< GaussianFactorGraph, VectorValues > planarGraph(size_t N)
Create small example with two poses and one landmark.
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
utility functions for loading datasets
static const Eigen::MatrixBase< Vector2 >::ConstantReturnType Z_2x1
VectorValues gradient(const VectorValues &y) const
std::pair< GaussianFactorGraph, GaussianFactorGraph > splitOffPlanarTree(size_t N, const GaussianFactorGraph &original)
VectorValues x(const VectorValues &y) const