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 
24 using namespace std;
25 using namespace gtsam;
26 
27 // Generate a small PoseSLAM problem
28 std::tuple<NonlinearFactorGraph, Values> generateProblem() {
29 
30  // 1. Create graph container and add factors to it
32 
33  // 2a. Add Gaussian prior
34  Pose2 priorMean(0.0, 0.0, 0.0); // prior at origin
35  SharedDiagonal priorNoise = noiseModel::Diagonal::Sigmas(
36  Vector3(0.3, 0.3, 0.1));
37  graph.addPrior(1, priorMean, priorNoise);
38 
39  // 2b. Add odometry factors
40  SharedDiagonal odometryNoise = noiseModel::Diagonal::Sigmas(
41  Vector3(0.2, 0.2, 0.1));
42  graph.emplace_shared<BetweenFactor<Pose2>>(1, 2, Pose2(2.0, 0.0, 0.0), odometryNoise);
43  graph.emplace_shared<BetweenFactor<Pose2>>(2, 3, Pose2(2.0, 0.0, M_PI_2), odometryNoise);
44  graph.emplace_shared<BetweenFactor<Pose2>>(3, 4, Pose2(2.0, 0.0, M_PI_2), odometryNoise);
45  graph.emplace_shared<BetweenFactor<Pose2>>(4, 5, Pose2(2.0, 0.0, M_PI_2), odometryNoise);
46 
47  // 2c. Add pose constraint
48  SharedDiagonal constraintUncertainty = noiseModel::Diagonal::Sigmas(
49  Vector3(0.2, 0.2, 0.1));
50  graph.emplace_shared<BetweenFactor<Pose2>>(5, 2, Pose2(2.0, 0.0, M_PI_2),
51  constraintUncertainty);
52 
53  // 3. Create the data structure to hold the initialEstimate estimate to the solution
54  Values initialEstimate;
55  Pose2 x1(0.5, 0.0, 0.2);
56  initialEstimate.insert(1, x1);
57  Pose2 x2(2.3, 0.1, -0.2);
58  initialEstimate.insert(2, x2);
59  Pose2 x3(4.1, 0.1, M_PI_2);
60  initialEstimate.insert(3, x3);
61  Pose2 x4(4.0, 2.0, M_PI);
62  initialEstimate.insert(4, x4);
63  Pose2 x5(2.1, 2.1, -M_PI_2);
64  initialEstimate.insert(5, x5);
65 
66  return {graph, initialEstimate};
67 }
68 
69 /* ************************************************************************* */
71 const auto [graph, initialEstimate] = generateProblem();
72 // cout << "initial error = " << graph.error(initialEstimate) << endl;
73 
75  param.maxIterations = 500; /* requires a larger number of iterations to converge */
76  param.verbosity = NonlinearOptimizerParams::SILENT;
77 
78  NonlinearConjugateGradientOptimizer optimizer(graph, initialEstimate, param);
79  Values result = optimizer.optimize();
80 // cout << "cg final error = " << graph.error(result) << endl;
81 
82  EXPECT_DOUBLES_EQUAL(0.0, graph.error(result), 1e-4);
83 }
84 
85 /* ************************************************************************* */
86 int main() {
87  TestResult tr;
88  return TestRegistry::runAllTests(tr);
89 }
90 /* ************************************************************************* */
IsDerived< DERIVEDFACTOR > emplace_shared(Args &&... args)
Emplace a shared pointer to factor of given type.
Definition: FactorGraph.h:196
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.
#define M_PI
Definition: main.h:106
Verbosity verbosity
The printing verbosity during optimization (default SILENT)
Definition: BFloat16.h:88
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:161
void addPrior(Key key, const T &prior, const SharedNoiseModel &model=nullptr)
TEST(NonlinearConjugateGradientOptimizer, Optimize)
Values result
auto odometryNoise
Pose2 priorMean(0.0, 0.0, 0.0)
Array< double, 1, 3 > e(1./3., 0.5, 2.)
double error(const Values &values) const
Pose3 x3(Rot3::Ypr(M_PI/4.0, 0.0, 0.0), l2)
noiseModel::Diagonal::shared_ptr SharedDiagonal
Definition: NoiseModel.h:743
traits
Definition: chartTesting.h:28
auto priorNoise
Pose3 x1
Definition: testPose3.cpp:663
2D Pose
static string x4("x4")
Simple non-linear optimizer that solves using non-preconditioned CG.
std::tuple< NonlinearFactorGraph, Values > generateProblem()
size_t maxIterations
The maximum iterations to stop iterating (default 100)


gtsam
Author(s):
autogenerated on Tue Jul 4 2023 02:38:20