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/nonlinear/ISAM2.h>
29 #include "examples/SFMdata.h"
30 
31 #include <functional>
32 
33 using namespace std;
34 using namespace gtsam;
35 
36 // Convenience for named keys
38 
39 /* ************************************************************************* */
40 TEST(DoglegOptimizer, ComputeBlend) {
41  // Create an arbitrary Bayes Net
44  0, Vector2(1.0,2.0), (Matrix(2, 2) << 3.0,4.0,0.0,6.0).finished(),
45  3, (Matrix(2, 2) << 7.0,8.0,9.0,10.0).finished(),
46  4, (Matrix(2, 2) << 11.0,12.0,13.0,14.0).finished());
48  1, Vector2(15.0,16.0), (Matrix(2, 2) << 17.0,18.0,0.0,20.0).finished(),
49  2, (Matrix(2, 2) << 21.0,22.0,23.0,24.0).finished(),
50  4, (Matrix(2, 2) << 25.0,26.0,27.0,28.0).finished());
52  2, Vector2(29.0,30.0), (Matrix(2, 2) << 31.0,32.0,0.0,34.0).finished(),
53  3, (Matrix(2, 2) << 35.0,36.0,37.0,38.0).finished());
55  3, Vector2(39.0,40.0), (Matrix(2, 2) << 41.0,42.0,0.0,44.0).finished(),
56  4, (Matrix(2, 2) << 45.0,46.0,47.0,48.0).finished());
58  4, Vector2(49.0,50.0), (Matrix(2, 2) << 51.0,52.0,0.0,54.0).finished());
59 
60  // Compute steepest descent point
62 
63  // Compute Newton's method point
64  VectorValues xn = gbn.optimize();
65 
66  // The Newton's method point should be more "adventurous", i.e. larger, than the steepest descent point
67  EXPECT(xu.vector().norm() < xn.vector().norm());
68 
69  // Compute blend
70  double Delta = 1.5;
71  VectorValues xb = DoglegOptimizerImpl::ComputeBlend(Delta, xu, xn);
72  DOUBLES_EQUAL(Delta, xb.vector().norm(), 1e-10);
73 }
74 
75 /* ************************************************************************* */
76 TEST(DoglegOptimizer, ComputeDoglegPoint) {
77  // Create an arbitrary Bayes Net
80  0, Vector2(1.0,2.0), (Matrix(2, 2) << 3.0,4.0,0.0,6.0).finished(),
81  3, (Matrix(2, 2) << 7.0,8.0,9.0,10.0).finished(),
82  4, (Matrix(2, 2) << 11.0,12.0,13.0,14.0).finished());
84  1, Vector2(15.0,16.0), (Matrix(2, 2) << 17.0,18.0,0.0,20.0).finished(),
85  2, (Matrix(2, 2) << 21.0,22.0,23.0,24.0).finished(),
86  4, (Matrix(2, 2) << 25.0,26.0,27.0,28.0).finished());
88  2, Vector2(29.0,30.0), (Matrix(2, 2) << 31.0,32.0,0.0,34.0).finished(),
89  3, (Matrix(2, 2) << 35.0,36.0,37.0,38.0).finished());
91  3, Vector2(39.0,40.0), (Matrix(2, 2) << 41.0,42.0,0.0,44.0).finished(),
92  4, (Matrix(2, 2) << 45.0,46.0,47.0,48.0).finished());
94  4, Vector2(49.0,50.0), (Matrix(2, 2) << 51.0,52.0,0.0,54.0).finished());
95 
96  // Compute dogleg point for different deltas
97 
98  double Delta1 = 0.5; // Less than steepest descent
99  VectorValues actual1 = DoglegOptimizerImpl::ComputeDoglegPoint(Delta1, gbn.optimizeGradientSearch(), gbn.optimize());
100  DOUBLES_EQUAL(Delta1, actual1.vector().norm(), 1e-5);
101 
102  double Delta2 = 1.5; // Between steepest descent and Newton's method
103  VectorValues expected2 = DoglegOptimizerImpl::ComputeBlend(Delta2, gbn.optimizeGradientSearch(), gbn.optimize());
104  VectorValues actual2 = DoglegOptimizerImpl::ComputeDoglegPoint(Delta2, gbn.optimizeGradientSearch(), gbn.optimize());
105  DOUBLES_EQUAL(Delta2, actual2.vector().norm(), 1e-5);
106  EXPECT(assert_equal(expected2, actual2));
107 
108  double Delta3 = 5.0; // Larger than Newton's method point
109  VectorValues expected3 = gbn.optimize();
110  VectorValues actual3 = DoglegOptimizerImpl::ComputeDoglegPoint(Delta3, gbn.optimizeGradientSearch(), gbn.optimize());
111  EXPECT(assert_equal(expected3, actual3));
112 }
113 
114 /* ************************************************************************* */
116  // really non-linear factor graph
118 
119  // config far from minimum
120  Point2 x0(3,0);
121  Values config;
122  config.insert(X(1), x0);
123 
124  double Delta = 1.0;
125  for(size_t it=0; it<10; ++it) {
126  auto linearized = fg.linearize(config);
127 
128  // Iterate assumes that linear error = nonlinear error at the linearization point, and this should be true
129  double nonlinearError = fg.error(config);
130  double linearError = linearized->error(config.zeroVectors());
131  DOUBLES_EQUAL(nonlinearError, linearError, 1e-5);
132 
133  auto gbn = linearized->eliminateSequential();
135  VectorValues dx_n = gbn->optimize();
136  DoglegOptimizerImpl::IterationResult result = DoglegOptimizerImpl::Iterate(
137  Delta, DoglegOptimizerImpl::SEARCH_EACH_ITERATION, dx_u, dx_n, *gbn, fg,
138  config, fg.error(config));
139  Delta = result.delta;
140  EXPECT(result.f_error < fg.error(config)); // Check that error decreases
141 
142  Values newConfig(config.retract(result.dx_d));
143  config = newConfig;
144  DOUBLES_EQUAL(fg.error(config), result.f_error, 1e-5); // Check that error is correctly filled in
145  }
146 }
147 
148 /* ************************************************************************* */
150  // Create a pose-graph graph with a constraint on the first pose
152  const Pose2 origin(0, 0, 0), pose2(2, 0, 0);
154  auto model = noiseModel::Diagonal::Sigmas(Vector3(0.2, 0.2, 0.1));
156 
157  // Create feasible initial estimate
158  Values initial;
159  initial.insert(1, origin); // feasible !
160  initial.insert(2, Pose2(2.3, 0.1, -0.2));
161 
162  // Optimize the initial values using DoglegOptimizer
164  params.setVerbosityDL("VERBOSITY");
165  DoglegOptimizer optimizer(graph, initial, params);
166  Values result = optimizer.optimize();
167 
168  // Check result
170 
171  // Create infeasible initial estimate
172  Values infeasible;
173  infeasible.insert(1, Pose2(0.1, 0, 0)); // infeasible !
174  infeasible.insert(2, Pose2(2.3, 0.1, -0.2));
175 
176  // Try optimizing with infeasible initial estimate
177  DoglegOptimizer optimizer2(graph, infeasible, params);
178 
179 #ifdef GTSAM_USE_TBB
180  CHECK_EXCEPTION(optimizer2.optimize(), std::exception);
181 #else
182  CHECK_EXCEPTION(optimizer2.optimize(), std::invalid_argument);
183 #endif
184 }
185 
186 /* ************************************************************************* */
195 TEST(DogLegOptimizer, VariableUpdate) {
196  // Make the typename short so it looks much cleaner
198 
199  // create a typedef to the camera type
201  // Define the camera calibration parameters
202  Cal3_S2::shared_ptr K(new Cal3_S2(50.0, 50.0, 0.0, 50.0, 50.0));
203 
204  // Define the camera observation noise model
205  noiseModel::Isotropic::shared_ptr measurementNoise =
206  noiseModel::Isotropic::Sigma(2, 1.0); // one pixel in u and v
207 
208  // Create the set of ground-truth landmarks and poses
209  vector<Point3> points = createPoints();
210  vector<Pose3> poses = createPoses();
211 
212  // Create a factor graph
214 
215  ISAM2DoglegParams doglegparams = ISAM2DoglegParams();
216  doglegparams.verbose = false;
217  ISAM2Params isam2_params;
218  isam2_params.evaluateNonlinearError = true;
219  isam2_params.relinearizeThreshold = 0.0;
220  isam2_params.enableRelinearization = true;
221  isam2_params.optimizationParams = doglegparams;
222  isam2_params.relinearizeSkip = 1;
223  ISAM2 isam2(isam2_params);
224 
225  // Simulated measurements from each camera pose, adding them to the factor
226  // graph
227  unordered_map<int, SmartFactor::shared_ptr> smart_factors;
228  for (size_t j = 0; j < points.size(); ++j) {
229  // every landmark represent a single landmark, we use shared pointer to init
230  // the factor, and then insert measurements.
231  SmartFactor::shared_ptr smartfactor(new SmartFactor(measurementNoise, K));
232 
233  for (size_t i = 0; i < poses.size(); ++i) {
234  // generate the 2D measurement
235  Camera camera(poses[i], K);
236  Point2 measurement = camera.project(points[j]);
237 
238  // call add() function to add measurement into a single factor, here we
239  // need to add:
240  // 1. the 2D measurement
241  // 2. the corresponding camera's key
242  // 3. camera noise model
243  // 4. camera calibration
244 
245  // add only first 3 measurements and update the later measurements
246  // incrementally
247  if (i < 3) smartfactor->add(measurement, i);
248  }
249 
250  // insert the smart factor in the graph
251  smart_factors[j] = smartfactor;
252  graph.push_back(smartfactor);
253  }
254 
255  // Add a prior on pose x0. This indirectly specifies where the origin is.
256  // 30cm std on x,y,z 0.1 rad on roll,pitch,yaw
257  noiseModel::Diagonal::shared_ptr noise = noiseModel::Diagonal::Sigmas(
258  (Vector(6) << Vector3::Constant(0.3), Vector3::Constant(0.1)).finished());
259  graph.emplace_shared<PriorFactor<Pose3> >(0, poses[0], noise);
260 
261  // Because the structure-from-motion problem has a scale ambiguity, the
262  // problem is still under-constrained. Here we add a prior on the second pose
263  // x1, so this will fix the scale by indicating the distance between x0 and
264  // x1. Because these two are fixed, the rest of the poses will be also be
265  // fixed.
267  noise); // add directly to graph
268 
269  // Create the initial estimate to the solution
270  // Intentionally initialize the variables off from the ground truth
271  Values initialEstimate;
272  Pose3 delta(Rot3::Rodrigues(-0.1, 0.2, 0.25), Point3(0.05, -0.10, 0.20));
273  for (size_t i = 0; i < 3; ++i)
274  initialEstimate.insert(i, poses[i].compose(delta));
275  // initialEstimate.print("Initial Estimates:\n");
276 
277  // Optimize the graph and print results
278  isam2.update(graph, initialEstimate);
279  Values result = isam2.calculateEstimate();
280  // result.print("Results:\n");
281 
282  // we add new measurements from this pose
283  size_t pose_idx = 3;
284 
285  // Now update existing smart factors with new observations
286  for (size_t j = 0; j < points.size(); ++j) {
287  SmartFactor::shared_ptr smartfactor = smart_factors[j];
288 
289  // add the 4th measurement
290  Camera camera(poses[pose_idx], K);
291  Point2 measurement = camera.project(points[j]);
292  smartfactor->add(measurement, pose_idx);
293  }
294 
295  graph.resize(0);
296  initialEstimate.clear();
297 
298  // update initial estimate for the new pose
299  initialEstimate.insert(pose_idx, poses[pose_idx].compose(delta));
300 
301  // this should break the system
302  isam2.update(graph, initialEstimate);
303  result = isam2.calculateEstimate();
304  EXPECT(std::find(result.keys().begin(), result.keys().end(), pose_idx) !=
305  result.keys().end());
306 }
307 
308 /* ************************************************************************* */
309 int main() { TestResult tr; return TestRegistry::runAllTests(tr); }
310 /* ************************************************************************* */
TestRegistry::runAllTests
static int runAllTests(TestResult &result)
Definition: TestRegistry.cpp:27
createPoses
std::vector< gtsam::Pose3 > createPoses(const gtsam::Pose3 &init=gtsam::Pose3(gtsam::Rot3::Ypr(M_PI/2, 0,-M_PI/2), gtsam::Point3(30, 0, 0)), const gtsam::Pose3 &delta=gtsam::Pose3(gtsam::Rot3::Ypr(0,-M_PI/4, 0), gtsam::Point3(sin(M_PI/4) *30, 0, 30 *(1-sin(M_PI/4)))), int steps=8)
Definition: SFMdata.h:56
gtsam::ISAM2Params
Definition: ISAM2Params.h:136
CHECK_EXCEPTION
#define CHECK_EXCEPTION(condition, exception_name)
Definition: Test.h:118
Pose2.h
2D Pose
gtsam::NonlinearOptimizer::optimize
virtual const Values & optimize()
Definition: NonlinearOptimizer.h:98
gtsam::ISAM2Params::enableRelinearization
bool enableRelinearization
Definition: ISAM2Params.h:175
gtsam::ISAM2
Definition: ISAM2.h:45
gtsam::Values::keys
KeyVector keys() const
Definition: Values.cpp:218
gtsam::GaussianBayesNet::optimizeGradientSearch
VectorValues optimizeGradientSearch() const
Definition: GaussianBayesNet.cpp:89
e
Array< double, 1, 3 > e(1./3., 0.5, 2.)
EXPECT
#define EXPECT(condition)
Definition: Test.h:150
gtsam::Vector2
Eigen::Vector2d Vector2
Definition: Vector.h:42
TestHarness.h
Camera
Definition: camera.h:36
TEST
TEST(DoglegOptimizer, ComputeBlend)
Definition: testDoglegOptimizer.cpp:40
initial
Values initial
Definition: OdometryOptimize.cpp:2
gtsam::PriorFactor
Definition: nonlinear/PriorFactor.h:30
createPoints
std::vector< gtsam::Point3 > createPoints()
Definition: SFMdata.h:39
gtsam::NonlinearFactorGraph::linearize
std::shared_ptr< GaussianFactorGraph > linearize(const Values &linearizationPoint) const
Linearize a nonlinear factor graph.
Definition: NonlinearFactorGraph.cpp:239
simple::pose2
static Pose3 pose2
Definition: testInitializePose3.cpp:58
X
#define X
Definition: icosphere.cpp:20
gtsam::Vector3
Eigen::Vector3d Vector3
Definition: Vector.h:43
vanilla::params
static const SmartProjectionParams params
Definition: smartFactorScenarios.h:69
result
Values result
Definition: OdometryOptimize.cpp:8
gtsam::NonlinearEquality
Definition: NonlinearEquality.h:43
gtsam::ISAM2Params::optimizationParams
OptimizationParams optimizationParams
Definition: ISAM2Params.h:151
gtsam::ISAM2DoglegParams
Definition: ISAM2Params.h:68
gtsam::DoglegOptimizer
Definition: DoglegOptimizer.h:68
gtsam::NonlinearFactorGraph::error
double error(const Values &values) const
Definition: NonlinearFactorGraph.cpp:170
ceres::Matrix
Eigen::Matrix< double, Eigen::Dynamic, Eigen::Dynamic, Eigen::RowMajor > Matrix
Definition: gtsam/3rdparty/ceres/eigen.h:42
gtsam::Values::at
const ValueType at(Key j) const
Definition: Values-inl.h:261
gtsam::Values::retract
Values retract(const VectorValues &delta) const
Definition: Values.cpp:98
gtsam::FactorGraph::resize
virtual void resize(size_t size)
Definition: FactorGraph.h:367
gtsam::ISAM2Params::relinearizeThreshold
RelinearizationThreshold relinearizeThreshold
Definition: ISAM2Params.h:169
gtsam.examples.PlanarManipulatorExample.delta
def delta(g0, g1)
Definition: PlanarManipulatorExample.py:45
gtsam::VectorValues
Definition: VectorValues.h:74
j
std::ptrdiff_t j
Definition: tut_arithmetic_redux_minmax.cpp:2
BetweenFactor.h
gtsam::Pose3
Definition: Pose3.h:37
DOUBLES_EQUAL
#define DOUBLES_EQUAL(expected, actual, threshold)
Definition: Test.h:141
gtsam::SmartProjectionPoseFactor
Definition: SmartProjectionPoseFactor.h:45
gtsam::NonlinearFactorGraph
Definition: NonlinearFactorGraph.h:55
gtsam::GaussianConditional
Definition: GaussianConditional.h:40
x0
static Symbol x0('x', 0)
gtsam::GaussianBayesNet::optimize
VectorValues optimize() const
Definition: GaussianBayesNet.cpp:44
gtsam::Point2
Vector2 Point2
Definition: Point2.h:32
gtsam::Cal3_S2::shared_ptr
std::shared_ptr< Cal3_S2 > shared_ptr
Definition: Cal3_S2.h:39
SmartFactor
SmartProjectionPoseFactor< Cal3_S2 > SmartFactor
Definition: ISAM2Example_SmartFactor.cpp:22
NonlinearEquality.h
SmartProjectionPoseFactor.h
Smart factor on poses, assuming camera calibration is fixed.
sampling::gbn
static const GaussianBayesNet gbn
Definition: testGaussianBayesNet.cpp:171
model
noiseModel::Diagonal::shared_ptr model
Definition: doc/Code/Pose2SLAMExample.cpp:7
TestResult
Definition: TestResult.h:26
gtsam::DoglegParams
Definition: DoglegOptimizer.h:32
gtsam::ISAM2::calculateEstimate
Values calculateEstimate() const
Definition: ISAM2.cpp:785
ISAM2.h
Incremental update functionality (ISAM2) for BayesTree, with fluid relinearization.
gtsam::Values::zeroVectors
VectorValues zeroVectors() const
Definition: Values.cpp:260
gtsam
traits
Definition: chartTesting.h:28
gtsam::ISAM2::update
virtual ISAM2Result update(const NonlinearFactorGraph &newFactors=NonlinearFactorGraph(), const Values &newTheta=Values(), const FactorIndices &removeFactorIndices=FactorIndices(), const std::optional< FastMap< Key, int > > &constrainedKeys={}, const std::optional< FastList< Key > > &noRelinKeys={}, const std::optional< FastList< Key > > &extraReelimKeys={}, bool force_relinearize=false)
Definition: ISAM2.cpp:400
K
#define K
Definition: igam.h:8
gtsam::FactorGraph::push_back
IsDerived< DERIVEDFACTOR > push_back(std::shared_ptr< DERIVEDFACTOR > factor)
Add a factor directly using a shared_ptr.
Definition: FactorGraph.h:147
gtsam::Values
Definition: Values.h:65
gtsam::testing::compose
T compose(const T &t1, const T &t2)
Definition: lieProxies.h:39
std
Definition: BFloat16.h:88
gtsam::DoglegOptimizerImpl::IterationResult
Definition: DoglegOptimizerImpl.h:34
origin
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
Definition: gnuplot_common_settings.hh:45
gtsam::noiseModel::Diagonal::shared_ptr
std::shared_ptr< Diagonal > shared_ptr
Definition: NoiseModel.h:321
gtsam::Values::insert
void insert(Key j, const Value &val)
Definition: Values.cpp:155
Camera
PinholePose< Cal3_S2 > Camera
Definition: SFMExample_SmartFactor.cpp:38
gtsam::assert_equal
bool assert_equal(const Matrix &expected, const Matrix &actual, double tol)
Definition: Matrix.cpp:40
gtsam::Cal3_S2
The most common 5DOF 3D->2D calibration.
Definition: Cal3_S2.h:34
gtsam::Point3
Vector3 Point3
Definition: Point3.h:38
gtsam::example::createReallyNonlinearFactorGraph
NonlinearFactorGraph createReallyNonlinearFactorGraph()
Definition: smallExample.h:378
DoglegOptimizerImpl.h
Nonlinear factor graph optimizer using Powell's Dogleg algorithm (detail implementation)
initial
Definition: testScenarioRunner.cpp:148
main
int main()
Definition: testDoglegOptimizer.cpp:309
gtsam::noiseModel::Isotropic::shared_ptr
std::shared_ptr< Isotropic > shared_ptr
Definition: NoiseModel.h:559
DoglegOptimizer.h
gtsam::SmartProjectionPoseFactor::shared_ptr
std::shared_ptr< This > shared_ptr
shorthand for a smart pointer to a factor
Definition: SmartProjectionPoseFactor.h:59
camera
static const CalibratedCamera camera(kDefaultPose)
gtsam::ISAM2DoglegParams::verbose
bool verbose
Whether Dogleg prints iteration and convergence information.
Definition: ISAM2Params.h:77
gtsam::Constraint
Definition: Constraint.h:35
gtsam::PinholePose
Definition: PinholePose.h:239
graph
NonlinearFactorGraph graph
Definition: doc/Code/OdometryExample.cpp:2
gtsam::ISAM2Params::relinearizeSkip
int relinearizeSkip
Definition: ISAM2Params.h:171
smallExample.h
Create small example with two poses and one landmark.
SFMdata.h
Simple example for the structure-from-motion problems.
ceres::Vector
Eigen::Matrix< double, Eigen::Dynamic, 1 > Vector
Definition: gtsam/3rdparty/ceres/eigen.h:38
i
int i
Definition: BiCGSTAB_step_by_step.cpp:9
gtsam::ISAM2Params::evaluateNonlinearError
bool evaluateNonlinearError
Definition: ISAM2Params.h:178
measurement
static Point2 measurement(323.0, 240.0)
gtsam::GaussianBayesNet
Definition: GaussianBayesNet.h:35
gtsam::CalibratedCamera::project
Point2 project(const Point3 &point, OptionalJacobian< 2, 6 > Dcamera={}, OptionalJacobian< 2, 3 > Dpoint={}) const
Definition: CalibratedCamera.cpp:188
gtsam::FactorGraph::emplace_shared
IsDerived< DERIVEDFACTOR > emplace_shared(Args &&... args)
Emplace a shared pointer to factor of given type.
Definition: FactorGraph.h:153
gtsam::Pose2
Definition: Pose2.h:39
gtsam::VectorValues::vector
Vector vector() const
Definition: VectorValues.cpp:173
gtsam::BetweenFactor
Definition: BetweenFactor.h:40


gtsam
Author(s):
autogenerated on Sat Sep 28 2024 03:05:18