24 using namespace gtsam;
29 static const size_t m = 3,
n = 3;
31 (
Matrix(m,
n) << 1.0, 0.0, 0.0, 0.0, 1.0, 0.0, 0.0, 0.0, 1.0).finished();
36 (
Matrix(m,
n) << 2.0, 0.0, 0.0, 0.0, 2.0, 0.0, 0.0, 0.0, 2.0).finished();
37 Matrix A11 = (
Matrix(m,
n) << -2.0, 0.0, 0.0, 0.0, -2.0, 0.0, 0.0, 0.0, -2.0)
43 (
Matrix(m,
n) << 3.0, 0.0, 0.0, 0.0, 3.0, 0.0, 0.0, 0.0, 3.0).finished();
48 gfg.
add(
X(1), A01, b0, noiseModel::Diagonal::Sigmas(s0,
true));
49 gfg.
add(
X(0), A10,
X(1), A11, b1, noiseModel::Diagonal::Sigmas(s1,
true));
50 gfg.
add(
X(1), A21, b2, noiseModel::Diagonal::Sigmas(s2,
true));
static int runAllTests(TestResult &result)
bool assert_equal(const Matrix &expected, const Matrix &actual, double tol)
void add(const GaussianFactor &factor)
#define EXPECT(condition)
Linear Factor Graph where all factors are Gaussians.
Maps global variable indices to slot indices.
TEST(HessianFactor, CombineAndEliminate)
#define EXPECT_LONGS_EQUAL(expected, actual)
A Gaussian factor using the canonical parameters (information form)
Eigen::Matrix< double, Eigen::Dynamic, Eigen::Dynamic, Eigen::RowMajor > Matrix