testDoglegOptimizer.cpp
Go to the documentation of this file.
1 /* ----------------------------------------------------------------------------
2 
3  * GTSAM Copyright 2010, Georgia Tech Research Corporation,
4  * Atlanta, Georgia 30332-0415
5  * All Rights Reserved
6  * Authors: Frank Dellaert, et al. (see THANKS for the full author list)
7 
8  * See LICENSE for the license information
9 
10  * -------------------------------------------------------------------------- */
11 
20 
21 #include <tests/smallExample.h>
22 #include <gtsam/geometry/Pose2.h>
27 #include <gtsam/inference/Symbol.h>
31 
32 #include <functional>
33 
34 using namespace std;
35 using namespace gtsam;
36 
37 // Convenience for named keys
40 
41 /* ************************************************************************* */
42 TEST(DoglegOptimizer, ComputeBlend) {
43  // Create an arbitrary Bayes Net
46  0, Vector2(1.0,2.0), (Matrix(2, 2) << 3.0,4.0,0.0,6.0).finished(),
47  3, (Matrix(2, 2) << 7.0,8.0,9.0,10.0).finished(),
48  4, (Matrix(2, 2) << 11.0,12.0,13.0,14.0).finished());
50  1, Vector2(15.0,16.0), (Matrix(2, 2) << 17.0,18.0,0.0,20.0).finished(),
51  2, (Matrix(2, 2) << 21.0,22.0,23.0,24.0).finished(),
52  4, (Matrix(2, 2) << 25.0,26.0,27.0,28.0).finished());
54  2, Vector2(29.0,30.0), (Matrix(2, 2) << 31.0,32.0,0.0,34.0).finished(),
55  3, (Matrix(2, 2) << 35.0,36.0,37.0,38.0).finished());
57  3, Vector2(39.0,40.0), (Matrix(2, 2) << 41.0,42.0,0.0,44.0).finished(),
58  4, (Matrix(2, 2) << 45.0,46.0,47.0,48.0).finished());
60  4, Vector2(49.0,50.0), (Matrix(2, 2) << 51.0,52.0,0.0,54.0).finished());
61 
62  // Compute steepest descent point
64 
65  // Compute Newton's method point
66  VectorValues xn = gbn.optimize();
67 
68  // The Newton's method point should be more "adventurous", i.e. larger, than the steepest descent point
69  EXPECT(xu.vector().norm() < xn.vector().norm());
70 
71  // Compute blend
72  double Delta = 1.5;
73  VectorValues xb = DoglegOptimizerImpl::ComputeBlend(Delta, xu, xn);
74  DOUBLES_EQUAL(Delta, xb.vector().norm(), 1e-10);
75 }
76 
77 /* ************************************************************************* */
78 TEST(DoglegOptimizer, ComputeDoglegPoint) {
79  // Create an arbitrary Bayes Net
82  0, Vector2(1.0,2.0), (Matrix(2, 2) << 3.0,4.0,0.0,6.0).finished(),
83  3, (Matrix(2, 2) << 7.0,8.0,9.0,10.0).finished(),
84  4, (Matrix(2, 2) << 11.0,12.0,13.0,14.0).finished());
86  1, Vector2(15.0,16.0), (Matrix(2, 2) << 17.0,18.0,0.0,20.0).finished(),
87  2, (Matrix(2, 2) << 21.0,22.0,23.0,24.0).finished(),
88  4, (Matrix(2, 2) << 25.0,26.0,27.0,28.0).finished());
90  2, Vector2(29.0,30.0), (Matrix(2, 2) << 31.0,32.0,0.0,34.0).finished(),
91  3, (Matrix(2, 2) << 35.0,36.0,37.0,38.0).finished());
93  3, Vector2(39.0,40.0), (Matrix(2, 2) << 41.0,42.0,0.0,44.0).finished(),
94  4, (Matrix(2, 2) << 45.0,46.0,47.0,48.0).finished());
96  4, Vector2(49.0,50.0), (Matrix(2, 2) << 51.0,52.0,0.0,54.0).finished());
97 
98  // Compute dogleg point for different deltas
99 
100  double Delta1 = 0.5; // Less than steepest descent
101  VectorValues actual1 = DoglegOptimizerImpl::ComputeDoglegPoint(Delta1, gbn.optimizeGradientSearch(), gbn.optimize());
102  DOUBLES_EQUAL(Delta1, actual1.vector().norm(), 1e-5);
103 
104  double Delta2 = 1.5; // Between steepest descent and Newton's method
105  VectorValues expected2 = DoglegOptimizerImpl::ComputeBlend(Delta2, gbn.optimizeGradientSearch(), gbn.optimize());
106  VectorValues actual2 = DoglegOptimizerImpl::ComputeDoglegPoint(Delta2, gbn.optimizeGradientSearch(), gbn.optimize());
107  DOUBLES_EQUAL(Delta2, actual2.vector().norm(), 1e-5);
108  EXPECT(assert_equal(expected2, actual2));
109 
110  double Delta3 = 5.0; // Larger than Newton's method point
111  VectorValues expected3 = gbn.optimize();
112  VectorValues actual3 = DoglegOptimizerImpl::ComputeDoglegPoint(Delta3, gbn.optimizeGradientSearch(), gbn.optimize());
113  EXPECT(assert_equal(expected3, actual3));
114 }
115 
116 /* ************************************************************************* */
118  // really non-linear factor graph
120 
121  // config far from minimum
122  Point2 x0(3,0);
123  Values config;
124  config.insert(X(1), x0);
125 
126  double Delta = 1.0;
127  for(size_t it=0; it<10; ++it) {
128  auto linearized = fg.linearize(config);
129 
130  // Iterate assumes that linear error = nonlinear error at the linearization point, and this should be true
131  double nonlinearError = fg.error(config);
132  double linearError = linearized->error(config.zeroVectors());
133  DOUBLES_EQUAL(nonlinearError, linearError, 1e-5);
134 
135  auto gbn = linearized->eliminateSequential();
137  VectorValues dx_n = gbn->optimize();
138  DoglegOptimizerImpl::IterationResult result = DoglegOptimizerImpl::Iterate(
139  Delta, DoglegOptimizerImpl::SEARCH_EACH_ITERATION, dx_u, dx_n, *gbn, fg,
140  config, fg.error(config));
141  Delta = result.delta;
142  EXPECT(result.f_error < fg.error(config)); // Check that error decreases
143 
144  Values newConfig(config.retract(result.dx_d));
145  config = newConfig;
146  DOUBLES_EQUAL(fg.error(config), result.f_error, 1e-5); // Check that error is correctly filled in
147  }
148 }
149 
150 /* ************************************************************************* */
152  // Create a pose-graph graph with a constraint on the first pose
154  const Pose2 origin(0, 0, 0), pose2(2, 0, 0);
156  auto model = noiseModel::Diagonal::Sigmas(Vector3(0.2, 0.2, 0.1));
158 
159  // Create feasible initial estimate
160  Values initial;
161  initial.insert(1, origin); // feasible !
162  initial.insert(2, Pose2(2.3, 0.1, -0.2));
163 
164  // Optimize the initial values using DoglegOptimizer
166  params.setVerbosityDL("VERBOSITY");
167  DoglegOptimizer optimizer(graph, initial, params);
168  Values result = optimizer.optimize();
169 
170  // Check result
171  EXPECT(assert_equal(pose2, result.at<Pose2>(2)));
172 
173  // Create infeasible initial estimate
174  Values infeasible;
175  infeasible.insert(1, Pose2(0.1, 0, 0)); // infeasible !
176  infeasible.insert(2, Pose2(2.3, 0.1, -0.2));
177 
178  // Try optimizing with infeasible initial estimate
179  DoglegOptimizer optimizer2(graph, infeasible, params);
180 
181 #ifdef GTSAM_USE_TBB
182  CHECK_EXCEPTION(optimizer2.optimize(), std::exception);
183 #else
184  CHECK_EXCEPTION(optimizer2.optimize(), std::invalid_argument);
185 #endif
186 }
187 
188 /* ************************************************************************* */
189 int main() { TestResult tr; return TestRegistry::runAllTests(tr); }
190 /* ************************************************************************* */
virtual const Values & optimize()
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
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 y set format x g set format y g set format x2 g set format y2 g set format z g set angles radians set nogrid set key title set key left top Right noreverse box linetype linewidth samplen spacing width set nolabel set noarrow set nologscale set logscale x set set pointsize set encoding default set nopolar set noparametric set set set set surface set nocontour set clabel set mapping cartesian set nohidden3d set cntrparam order set cntrparam linear set cntrparam levels auto set cntrparam points set size set origin
noiseModel::Diagonal::shared_ptr model
const ValueType at(Key j) const
Definition: Values-inl.h:204
#define DOUBLES_EQUAL(expected, actual, threshold)
Definition: Test.h:141
Vector2 Point2
Definition: Point2.h:32
TEST(DoglegOptimizer, ComputeBlend)
NonlinearFactorGraph createReallyNonlinearFactorGraph()
Definition: smallExample.h:378
bool assert_equal(const Matrix &expected, const Matrix &actual, double tol)
Definition: Matrix.cpp:40
Values initial
static const GaussianBayesNet gbn
MatrixXd L
Definition: LLT_example.cpp:6
Definition: BFloat16.h:88
Some functions to compute numerical derivatives.
#define CHECK_EXCEPTION(condition, exception_name)
Definition: Test.h:118
NonlinearFactorGraph graph
static const SmartProjectionParams params
Values retract(const VectorValues &delta) const
Definition: Values.cpp:98
std::shared_ptr< GaussianFactorGraph > linearize(const Values &linearizationPoint) const
Linearize a nonlinear factor graph.
VectorValues optimize() const
Nonlinear factor graph optimizer using Powell&#39;s Dogleg algorithm (detail implementation) ...
Values result
VectorValues zeroVectors() const
Definition: Values.cpp:260
#define EXPECT(condition)
Definition: Test.h:150
Array< double, 1, 3 > e(1./3., 0.5, 2.)
int main()
double error(const Values &values) const
traits
Definition: chartTesting.h:28
static Symbol x0('x', 0)
Eigen::Vector2d Vector2
Definition: Vector.h:42
void setVerbosityDL(const std::string &verbosityDL)
static Pose3 pose2
Create small example with two poses and one landmark.
Vector vector() const
VectorValues optimizeGradientSearch() const
void insert(Key j, const Value &val)
Definition: Values.cpp:155
Eigen::Matrix< double, Eigen::Dynamic, Eigen::Dynamic, Eigen::RowMajor > Matrix
2D Pose
#define X
Definition: icosphere.cpp:20
Gaussian Bayes Tree, the result of eliminating a GaussianJunctionTree.


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