29 using namespace gtsam;
32 TEST( PCGsolver, verySimpleLinearSystem) {
42 simpleGFG +=
JacobianFactor(0, (
Matrix(2,2)<< 4, 1, 1, 3).finished(), (
Vector(2) << 1,2 ).finished(), noiseModel::Unit::Create(2));
46 exactSolution.
insert(0, (
Vector(2) << 1./11., 7./11.).finished());
57 pcg->setMaxIterations(500);
58 pcg->setEpsilon_abs(0.0);
59 pcg->setEpsilon_rel(0.0);
63 pcg->preconditioner_ = boost::make_shared<gtsam::DummyPreconditionerParameters>();
69 pcg->preconditioner_ = boost::make_shared<gtsam::BlockJacobiPreconditionerParameters>();
71 pcg->setMaxIterations(1500);
85 simpleGFG +=
JacobianFactor(2, (
Matrix(2,2)<< -10, 0, 0, -10).finished(), 0, (
Matrix(2,2)<< 10, 0, 0, 10).finished(), (
Vector(2) << 2, -1).finished(), unit2);
86 simpleGFG +=
JacobianFactor(2, (
Matrix(2,2)<< -5, 0, 0, -5).finished(), 1, (
Matrix(2,2)<< 5, 0, 0, 5).finished(), (
Vector(2) << 0, 1).finished(), unit2);
87 simpleGFG +=
JacobianFactor(0, (
Matrix(2,2)<< -5, 0, 0, -5).finished(), 1, (
Matrix(2,2)<< 5, 0, 0, 5).finished(), (
Vector(2) << -1, 1.5).finished(), unit2);
95 expectedSolution.
insert(0, (
Vector(2) << 0.100498, -0.196756).finished());
96 expectedSolution.
insert(2, (
Vector(2) << -0.0990413, -0.0980577).finished());
97 expectedSolution.
insert(1, (
Vector(2) << -0.0973252, 0.100582).finished());
108 pcg->setMaxIterations(500);
109 pcg->setEpsilon_abs(0.0);
110 pcg->setEpsilon_rel(0.0);
114 pcg->preconditioner_ = boost::make_shared<gtsam::DummyPreconditionerParameters>();
120 pcg->preconditioner_ = boost::make_shared<gtsam::BlockJacobiPreconditionerParameters>();
VectorValues optimize(const Eliminate &function=EliminationTraitsType::DefaultEliminate) const
static int runAllTests(TestResult &result)
A non-templated config holding any types of Manifold-group elements.
#define EXPECT(condition)
TEST(PCGsolver, verySimpleLinearSystem)
Array< double, 1, 3 > e(1./3., 0.5, 2.)
Linear Factor Graph where all factors are Gaussians.
static SharedNoiseModel unit2(noiseModel::Unit::Create(2))
noiseModel::Diagonal::shared_ptr SharedDiagonal
bool assert_equal(const Matrix &expected, const Matrix &actual, double tol)
boost::shared_ptr< PCGSolverParameters > shared_ptr
VectorValues optimize(const GaussianFactorGraph &gfg, const KeyInfo &keyInfo, const std::map< Key, Vector > &lambda, const VectorValues &initial) override
Eigen::Matrix< double, Eigen::Dynamic, Eigen::Dynamic, Eigen::RowMajor > Matrix
Eigen::Matrix< double, Eigen::Dynamic, 1 > Vector
iterator insert(const std::pair< Key, Vector > &key_value)