testGradientDescentOptimizer.cpp
Go to the documentation of this file.
1 
18 #include <gtsam/nonlinear/Values.h>
19 #include <gtsam/geometry/Pose2.h>
20 
22 
23 #include <boost/make_shared.hpp>
24 #include <boost/shared_ptr.hpp>
25 #include <boost/tuple/tuple.hpp>
26 
27 using namespace std;
28 using namespace gtsam;
29 
30 // Generate a small PoseSLAM problem
31 boost::tuple<NonlinearFactorGraph, Values> generateProblem() {
32 
33  // 1. Create graph container and add factors to it
35 
36  // 2a. Add Gaussian prior
37  Pose2 priorMean(0.0, 0.0, 0.0); // prior at origin
38  SharedDiagonal priorNoise = noiseModel::Diagonal::Sigmas(
39  Vector3(0.3, 0.3, 0.1));
40  graph.addPrior(1, priorMean, priorNoise);
41 
42  // 2b. Add odometry factors
43  SharedDiagonal odometryNoise = noiseModel::Diagonal::Sigmas(
44  Vector3(0.2, 0.2, 0.1));
45  graph += BetweenFactor<Pose2>(1, 2, Pose2(2.0, 0.0, 0.0), odometryNoise);
46  graph += BetweenFactor<Pose2>(2, 3, Pose2(2.0, 0.0, M_PI_2), odometryNoise);
47  graph += BetweenFactor<Pose2>(3, 4, Pose2(2.0, 0.0, M_PI_2), odometryNoise);
48  graph += BetweenFactor<Pose2>(4, 5, Pose2(2.0, 0.0, M_PI_2), odometryNoise);
49 
50  // 2c. Add pose constraint
51  SharedDiagonal constraintUncertainty = noiseModel::Diagonal::Sigmas(
52  Vector3(0.2, 0.2, 0.1));
53  graph += BetweenFactor<Pose2>(5, 2, Pose2(2.0, 0.0, M_PI_2),
54  constraintUncertainty);
55 
56  // 3. Create the data structure to hold the initialEstimate estimate to the solution
57  Values initialEstimate;
58  Pose2 x1(0.5, 0.0, 0.2);
59  initialEstimate.insert(1, x1);
60  Pose2 x2(2.3, 0.1, -0.2);
61  initialEstimate.insert(2, x2);
62  Pose2 x3(4.1, 0.1, M_PI_2);
63  initialEstimate.insert(3, x3);
64  Pose2 x4(4.0, 2.0, M_PI);
65  initialEstimate.insert(4, x4);
66  Pose2 x5(2.1, 2.1, -M_PI_2);
67  initialEstimate.insert(5, x5);
68 
69  return boost::tie(graph, initialEstimate);
70 }
71 
72 /* ************************************************************************* */
74 
76  Values initialEstimate;
77 
78  boost::tie(graph, initialEstimate) = generateProblem();
79 // cout << "initial error = " << graph.error(initialEstimate) << endl;
80 
82  param.maxIterations = 500; /* requires a larger number of iterations to converge */
83  param.verbosity = NonlinearOptimizerParams::SILENT;
84 
85  NonlinearConjugateGradientOptimizer optimizer(graph, initialEstimate, param);
86  Values result = optimizer.optimize();
87 // cout << "cg final error = " << graph.error(result) << endl;
88 
89  EXPECT_DOUBLES_EQUAL(0.0, graph.error(result), 1e-4);
90 }
91 
92 /* ************************************************************************* */
93 int main() {
94  TestResult tr;
95  return TestRegistry::runAllTests(tr);
96 }
97 /* ************************************************************************* */
noiseModel::Diagonal::shared_ptr odometryNoise
static int runAllTests(TestResult &result)
Eigen::Vector3d Vector3
Definition: Vector.h:43
A non-templated config holding any types of Manifold-group elements.
Factor Graph consisting of non-linear factors.
boost::tuple< NonlinearFactorGraph, Values > generateProblem()
#define M_PI
Definition: main.h:78
Verbosity verbosity
The printing verbosity during optimization (default SILENT)
Definition: Half.h:150
Pose3 x2(Rot3::Ypr(0.0, 0.0, 0.0), l2)
static string x5("x5")
NonlinearFactorGraph graph
#define EXPECT_DOUBLES_EQUAL(expected, actual, threshold)
Definition: Test.h:162
void addPrior(Key key, const T &prior, const SharedNoiseModel &model=nullptr)
TEST(NonlinearConjugateGradientOptimizer, Optimize)
Values result
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
Definition: NoiseModel.h:736
traits
Definition: chartTesting.h:28
Pose3 x1
Definition: testPose3.cpp:588
noiseModel::Diagonal::shared_ptr priorNoise
double error(const Values &values) const
2D Pose
static string x4("x4")
Simple non-linear optimizer that solves using non-preconditioned CG.
size_t maxIterations
The maximum iterations to stop iterating (default 100)


gtsam
Author(s):
autogenerated on Sat May 8 2021 02:47:11