24 #include <boost/assign/list_of.hpp> 25 using boost::assign::list_of;
31 using namespace gtsam;
37 const Key x123 = 0, x45 = 1;
38 gfg.
add(x123, (
Matrix(2, 3) << 1, 2, 3, 5, 6, 7).finished(),
40 gfg.
add(x123, (
Matrix(2, 3) << 9, 10, 0, 0, 0, 0).finished(),
41 x45, (
Matrix(2, 2) << 11, 12, 14, 15.).finished(),
59 gfg.
add(x123, Matrix23::Zero(), Vector2::Zero(), model);
60 gfg.
add(2, Matrix21::Zero(), Vector2::Zero(), model);
Provides additional testing facilities for common data structures.
static int runAllTests(TestResult &result)
A versatible sparse matrix representation.
Utilities for creating Eigen sparse matrices (gtsam::SparseEigen)
noiseModel::Diagonal::shared_ptr model
static enum @843 ordering
Matrix augmentedJacobian(const Ordering &ordering) const
SparseEigen sparseJacobianEigen(const GaussianFactorGraph &gfg, const Ordering &ordering)
Constructs an Eigen-format SparseMatrix of a GaussianFactorGraph.
void add(const GaussianFactor &factor)
#define EXPECT(condition)
Linear Factor Graph where all factors are Gaussians.
noiseModel::Diagonal::shared_ptr SharedDiagonal
bool assert_equal(const Matrix &expected, const Matrix &actual, double tol)
#define EXPECT_LONGS_EQUAL(expected, actual)
TEST(SparseEigen, sparseJacobianEigen)
Eigen::Matrix< double, Eigen::Dynamic, Eigen::Dynamic, Eigen::RowMajor > Matrix
std::uint64_t Key
Integer nonlinear key type.