2012-07-22 23:15:12 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								/* ----------------------------------------------------------------------------
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								 * GTSAM Copyright 2010, Georgia Tech Research Corporation,
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								 * Atlanta, Georgia 30332-0415
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								 * All Rights Reserved
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								 * Authors: Frank Dellaert, et al. (see THANKS for the full author list)
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								 * See LICENSE for the license information
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								 * -------------------------------------------------------------------------- */
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								/**
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								 * @file    VisualISAM2Example.cpp
							 | 
						
					
						
							
								
									
										
										
										
											2018-10-01 05:22:53 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								 * @brief   A visualSLAM example for the structure-from-motion problem on a
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								 * simulated dataset This version uses iSAM2 to solve the problem incrementally
							 | 
						
					
						
							
								
									
										
										
										
											2012-07-22 23:15:12 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								 * @author  Duy-Nguyen Ta
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								 */
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								/**
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								 * A structure-from-motion example with landmarks
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								 *  - The landmarks form a 10 meter cube
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								 *  - The robot rotates around the landmarks, always facing towards the cube
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								 */
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							
								
									
										
										
										
											2013-08-30 12:23:45 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								// For loading the data
							 | 
						
					
						
							
								
									
										
										
										
											2013-10-18 13:31:55 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								#include "SFMdata.h"
							 | 
						
					
						
							
								
									
										
										
										
											2013-08-30 12:23:45 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							
								
									
										
										
										
											2018-10-01 05:22:53 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								// Camera observations of landmarks will be stored as Point2 (x, y).
							 | 
						
					
						
							
								
									
										
										
										
											2012-07-22 23:15:12 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								#include <gtsam/geometry/Point2.h>
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							
								
									
										
										
										
											2018-10-01 05:22:53 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								// Each variable in the system (poses and landmarks) must be identified with a
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								// unique key. We can either use simple integer keys (1, 2, 3, ...) or symbols
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								// (X1, X2, L1). Here we will use Symbols
							 | 
						
					
						
							
								
									
										
										
										
											2013-08-19 23:32:16 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								#include <gtsam/inference/Symbol.h>
							 | 
						
					
						
							
								
									
										
										
										
											2012-07-22 23:15:12 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							
								
									
										
										
										
											2018-10-01 05:22:53 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								// We want to use iSAM2 to solve the structure-from-motion problem
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								// incrementally, so include iSAM2 here
							 | 
						
					
						
							
								
									
										
										
										
											2012-07-22 23:15:12 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								#include <gtsam/nonlinear/ISAM2.h>
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							
								
									
										
										
										
											2018-10-01 05:22:53 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								// iSAM2 requires as input a set of new factors to be added stored in a factor
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								// graph, and initial guesses for any new variables used in the added factors
							 | 
						
					
						
							
								
									
										
										
										
											2012-07-22 23:15:12 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								#include <gtsam/nonlinear/NonlinearFactorGraph.h>
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								#include <gtsam/nonlinear/Values.h>
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							
								
									
										
										
										
											2018-10-01 05:22:53 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								// In GTSAM, measurement functions are represented as 'factors'. Several common
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								// factors have been provided with the library for solving robotics/SLAM/Bundle
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								// Adjustment problems. Here we will use Projection factors to model the
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								// camera's landmark observations. Also, we will initialize the robot at some
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								// location using a Prior factor.
							 | 
						
					
						
							
								
									
										
										
										
											2013-06-21 22:13:59 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								#include <gtsam/slam/ProjectionFactor.h>
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							
								
									
										
										
										
											2012-07-22 23:15:12 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								#include <vector>
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								using namespace std;
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								using namespace gtsam;
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								/* ************************************************************************* */
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								int main(int argc, char* argv[]) {
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  // Define the camera calibration parameters
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  Cal3_S2::shared_ptr K(new Cal3_S2(50.0, 50.0, 0.0, 50.0, 50.0));
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							
								
									
										
										
										
											2018-10-01 05:22:53 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								  // Define the camera observation noise model, 1 pixel stddev
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  auto measurementNoise = noiseModel::Isotropic::Sigma(2, 1.0);
							 | 
						
					
						
							
								
									
										
										
										
											2012-07-22 23:15:12 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  // Create the set of ground-truth landmarks
							 | 
						
					
						
							
								
									
										
										
										
											2013-08-31 00:53:21 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								  vector<Point3> points = createPoints();
							 | 
						
					
						
							
								
									
										
										
										
											2012-07-22 23:15:12 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  // Create the set of ground-truth poses
							 | 
						
					
						
							
								
									
										
										
										
											2013-08-31 00:53:21 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								  vector<Pose3> poses = createPoses();
							 | 
						
					
						
							
								
									
										
										
										
											2012-07-22 23:15:12 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							
								
									
										
										
										
											2018-10-01 05:22:53 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								  // Create an iSAM2 object. Unlike iSAM1, which performs periodic batch steps
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  // to maintain proper linearization and efficient variable ordering, iSAM2
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  // performs partial relinearization/reordering at each step. A parameter
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  // structure is available that allows the user to set various properties, such
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  // as the relinearization threshold and type of linear solver. For this
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  // example, we we set the relinearization threshold small so the iSAM2 result
							 | 
						
					
						
							
								
									
										
										
										
											2012-07-22 23:15:12 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  // will approach the batch result.
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  ISAM2Params parameters;
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  parameters.relinearizeThreshold = 0.01;
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  parameters.relinearizeSkip = 1;
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  ISAM2 isam(parameters);
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  // Create a Factor Graph and Values to hold the new data
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  NonlinearFactorGraph graph;
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  Values initialEstimate;
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							
								
									
										
										
										
											2018-10-01 05:22:53 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								  // Loop over the poses, adding the observations to iSAM incrementally
							 | 
						
					
						
							
								
									
										
										
										
											2012-07-22 23:15:12 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  for (size_t i = 0; i < poses.size(); ++i) {
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								    // Add factors for each landmark observation
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								    for (size_t j = 0; j < points.size(); ++j) {
							 | 
						
					
						
							
								
									
										
										
										
											2020-02-22 08:42:55 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								      PinholeCamera<Cal3_S2> camera(poses[i], *K);
							 | 
						
					
						
							
								
									
										
										
										
											2012-07-22 23:15:12 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								      Point2 measurement = camera.project(points[j]);
							 | 
						
					
						
							
								
									
										
										
										
											2018-10-01 05:22:53 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								      graph.emplace_shared<GenericProjectionFactor<Pose3, Point3, Cal3_S2> >(
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								          measurement, measurementNoise, Symbol('x', i), Symbol('l', j), K);
							 | 
						
					
						
							
								
									
										
										
										
											2012-07-22 23:15:12 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								    }
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								    // Add an initial guess for the current pose
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								    // Intentionally initialize the variables off from the ground truth
							 | 
						
					
						
							
								
									
										
										
										
											2018-10-01 05:22:53 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								    static Pose3 kDeltaPose(Rot3::Rodrigues(-0.1, 0.2, 0.25),
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								                            Point3(0.05, -0.10, 0.20));
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								    initialEstimate.insert(Symbol('x', i), poses[i] * kDeltaPose);
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								    // If this is the first iteration, add a prior on the first pose to set the
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								    // coordinate frame and a prior on the first landmark to set the scale Also,
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								    // as iSAM solves incrementally, we must wait until each is observed at
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								    // least twice before adding it to iSAM.
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								    if (i == 0) {
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								      // Add a prior on pose x0, 30cm std on x,y,z and 0.1 rad on roll,pitch,yaw
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								      static auto kPosePrior = noiseModel::Diagonal::Sigmas(
							 | 
						
					
						
							
								
									
										
										
										
											2020-01-05 08:57:22 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								          (Vector(6) << Vector3::Constant(0.1), Vector3::Constant(0.3))
							 | 
						
					
						
							
								
									
										
										
										
											2018-10-01 05:22:53 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								              .finished());
							 | 
						
					
						
							
								
									
										
										
										
											2020-04-13 01:10:09 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								      graph.addPrior(Symbol('x', 0), poses[0], kPosePrior);
							 | 
						
					
						
							
								
									
										
										
										
											2012-07-22 23:15:12 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								      // Add a prior on landmark l0
							 | 
						
					
						
							
								
									
										
										
										
											2018-10-01 05:22:53 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								      static auto kPointPrior = noiseModel::Isotropic::Sigma(3, 0.1);
							 | 
						
					
						
							
								
									
										
										
										
											2020-04-13 01:10:09 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								      graph.addPrior(Symbol('l', 0), points[0], kPointPrior);
							 | 
						
					
						
							
								
									
										
										
										
											2012-07-22 23:15:12 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								      // Add initial guesses to all observed landmarks
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								      // Intentionally initialize the variables off from the ground truth
							 | 
						
					
						
							
								
									
										
										
										
											2018-10-01 05:22:53 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								      static Point3 kDeltaPoint(-0.25, 0.20, 0.15);
							 | 
						
					
						
							
								
									
										
										
										
											2012-07-22 23:15:12 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								      for (size_t j = 0; j < points.size(); ++j)
							 | 
						
					
						
							
								
									
										
										
										
											2018-10-01 05:22:53 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								        initialEstimate.insert<Point3>(Symbol('l', j), points[j] + kDeltaPoint);
							 | 
						
					
						
							
								
									
										
										
										
											2012-07-22 23:15:12 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								    } else {
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								      // Update iSAM with the new factors
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								      isam.update(graph, initialEstimate);
							 | 
						
					
						
							
								
									
										
										
										
											2018-10-01 05:22:53 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								      // Each call to iSAM2 update(*) performs one iteration of the iterative
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								      // nonlinear solver. If accuracy is desired at the expense of time,
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								      // update(*) can be called additional times to perform multiple optimizer
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								      // iterations every step.
							 | 
						
					
						
							
								
									
										
										
										
											2012-07-22 23:15:12 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								      isam.update();
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								      Values currentEstimate = isam.calculateEstimate();
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								      cout << "****************************************************" << endl;
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								      cout << "Frame " << i << ": " << endl;
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								      currentEstimate.print("Current estimate: ");
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								      // Clear the factor graph and values for the next iteration
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								      graph.resize(0);
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								      initialEstimate.clear();
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								    }
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  }
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  return 0;
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								}
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								/* ************************************************************************* */
							 |