23 #include <boost/make_shared.hpp> 24 #include <boost/shared_ptr.hpp> 25 #include <boost/tuple/tuple.hpp> 28 using namespace gtsam;
40 graph.
addPrior(1, priorMean, priorNoise);
51 SharedDiagonal constraintUncertainty = noiseModel::Diagonal::Sigmas(
54 constraintUncertainty);
59 initialEstimate.insert(1, x1);
61 initialEstimate.insert(2, x2);
63 initialEstimate.insert(3, x3);
65 initialEstimate.insert(4, x4);
67 initialEstimate.insert(5, x5);
69 return boost::tie(graph, initialEstimate);
83 param.
verbosity = NonlinearOptimizerParams::SILENT;
noiseModel::Diagonal::shared_ptr odometryNoise
static int runAllTests(TestResult &result)
A non-templated config holding any types of Manifold-group elements.
Factor Graph consisting of non-linear factors.
boost::tuple< NonlinearFactorGraph, Values > generateProblem()
const Values & optimize() override
Verbosity verbosity
The printing verbosity during optimization (default SILENT)
Pose3 x2(Rot3::Ypr(0.0, 0.0, 0.0), l2)
NonlinearFactorGraph graph
#define EXPECT_DOUBLES_EQUAL(expected, actual, threshold)
void addPrior(Key key, const T &prior, const SharedNoiseModel &model=nullptr)
TEST(NonlinearConjugateGradientOptimizer, Optimize)
Pose2 priorMean(0.0, 0.0, 0.0)
Array< double, 1, 3 > e(1./3., 0.5, 2.)
Pose3 x3(Rot3::Ypr(M_PI/4.0, 0.0, 0.0), l2)
noiseModel::Diagonal::shared_ptr SharedDiagonal
noiseModel::Diagonal::shared_ptr priorNoise
double error(const Values &values) const
Simple non-linear optimizer that solves using non-preconditioned CG.
size_t maxIterations
The maximum iterations to stop iterating (default 100)