33 using namespace gtsam;
46 0., 0., 1.).finished();
51 0., 0., 1.).finished();
61 Matrix Rhat = AtA.llt().matrixL().transpose();
75 xhat = Radapter.transpose().triangularView<
Eigen::Upper>().solve(b);
88 simpleGFG.
emplace_shared<
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);
89 simpleGFG.
emplace_shared<
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);
90 simpleGFG.
emplace_shared<
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);
98 std::map<Key,Vector>
lambda;
99 dummyPreconditioner.build(simpleGFG, keyInfo, lambda);
104 initial = (
Vector(6) << 0., 0., 0., 0., 0., 0.).finished();
113 Vector expectedAp = (
Vector(6) << 100400, -249074.074, -2080, 148148.148, -146480, 37962.963).finished();
117 Vector expectedb = (
Vector(6) << 100.0, -194.444, -20.0, 138.889, -120.0, -55.556).finished();
128 auto pcg = std::make_shared<PCGSolverParameters>();
129 pcg->preconditioner_ = std::make_shared<DummyPreconditionerParameters>();
148 auto pcg = std::make_shared<PCGSolverParameters>();
149 pcg->preconditioner_ =
150 std::make_shared<BlockJacobiPreconditionerParameters>();
169 auto pcg = std::make_shared<PCGSolverParameters>();
170 pcg->preconditioner_ = std::make_shared<SubgraphPreconditionerParameters>();
void rightPrecondition(const Vector &x, Vector &y) const
virtual const Values & optimize()
IsDerived< DERIVEDFACTOR > emplace_shared(Args &&... args)
Emplace a shared pointer to factor of given type.
static int runAllTests(TestResult &result)
void multiply(const Vector &x, Vector &y) const
A matrix or vector expression mapping an existing array of data.
Matrix2 transpose() const
#define DOUBLES_EQUAL(expected, actual, threshold)
NonlinearFactorGraph createReallyNonlinearFactorGraph()
bool assert_equal(const Matrix &expected, const Matrix &actual, double tol)
Rot2 R(Rot2::fromAngle(0.1))
static const SmartProjectionParams params
EIGEN_DONT_INLINE void llt(const Mat &A, const Mat &B, Mat &C)
#define EXPECT(condition)
A nonlinear optimizer that uses the Levenberg-Marquardt trust-region scheme.
Array< double, 1, 3 > e(1./3., 0.5, 2.)
void leftPrecondition(const Vector &x, Vector &y) const
Linear Factor Graph where all factors are Gaussians.
IterativeOptimizationParameters::shared_ptr iterativeParams
The container for iterativeOptimization parameters. used in CG Solvers.
double error(const Values &values) const
cout<< "The eigenvalues of A are:"<< endl<< ces.eigenvalues()<< endl;cout<< "The matrix of eigenvectors, V, is:"<< endl<< ces.eigenvectors()<< endl<< endl;complex< float > lambda
noiseModel::Diagonal::shared_ptr SharedDiagonal
Create small example with two poses and one landmark.
void insert(Key j, const Value &val)
Eigen::Matrix< double, Eigen::Dynamic, Eigen::Dynamic, Eigen::RowMajor > Matrix
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
void residual(const Vector &x, Vector &r) const
LinearSolverType linearSolverType
The type of linear solver to use in the nonlinear optimizer.
void getb(Vector &b) const