| 
									
										
										
										
											2013-06-21 22:13:59 +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 | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |  * -------------------------------------------------------------------------- */ | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | /**
 | 
					
						
							| 
									
										
										
										
											2022-03-11 05:51:19 +08:00
										 |  |  |  * @file RangeISAMExample_plaza2.cpp | 
					
						
							| 
									
										
										
										
											2013-06-21 22:13:59 +08:00
										 |  |  |  * @brief A 2D Range SLAM example | 
					
						
							|  |  |  |  * @date June 20, 2013 | 
					
						
							| 
									
										
										
										
											2022-03-11 05:51:19 +08:00
										 |  |  |  * @author Frank Dellaert | 
					
						
							| 
									
										
										
										
											2013-06-21 22:13:59 +08:00
										 |  |  |  */ | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2022-03-11 05:51:19 +08:00
										 |  |  | // Both relative poses and recovered trajectory poses will be stored as Pose2.
 | 
					
						
							| 
									
										
										
										
											2013-06-21 22:13:59 +08:00
										 |  |  | #include <gtsam/geometry/Pose2.h>
 | 
					
						
							| 
									
										
										
										
											2022-03-11 05:51:19 +08:00
										 |  |  | using gtsam::Pose2; | 
					
						
							| 
									
										
										
										
											2013-06-21 22:13:59 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2022-03-11 05:51:19 +08:00
										 |  |  | // gtsam::Vectors are dynamic Eigen vectors, Vector3 is statically sized.
 | 
					
						
							|  |  |  | #include <gtsam/base/Vector.h>
 | 
					
						
							|  |  |  | using gtsam::Vector; | 
					
						
							|  |  |  | using gtsam::Vector3; | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | // Unknown landmarks are of type Point2 (which is just a 2D Eigen vector).
 | 
					
						
							|  |  |  | #include <gtsam/geometry/Point2.h>
 | 
					
						
							|  |  |  | using gtsam::Point2; | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | // 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>
 | 
					
						
							| 
									
										
										
										
											2022-03-11 05:51:19 +08:00
										 |  |  | using gtsam::Symbol; | 
					
						
							| 
									
										
										
										
											2013-06-21 22:13:59 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2022-03-11 05:51:19 +08:00
										 |  |  | // We want to use iSAM2 to solve the range-SLAM problem incrementally.
 | 
					
						
							| 
									
										
										
										
											2013-06-21 22:13:59 +08:00
										 |  |  | #include <gtsam/nonlinear/ISAM2.h>
 | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2022-03-11 05:51:19 +08:00
										 |  |  | // iSAM2 requires as input a set set of new factors to be added stored in a
 | 
					
						
							|  |  |  | // factor graph, and initial guesses for any new variables in the added factors.
 | 
					
						
							| 
									
										
										
										
											2013-06-21 22:13:59 +08:00
										 |  |  | #include <gtsam/nonlinear/NonlinearFactorGraph.h>
 | 
					
						
							|  |  |  | #include <gtsam/nonlinear/Values.h>
 | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2022-03-11 05:51:19 +08:00
										 |  |  | // We will use a non-linear solver to batch-initialize from the first 150 frames
 | 
					
						
							| 
									
										
										
										
											2013-06-21 22:13:59 +08:00
										 |  |  | #include <gtsam/nonlinear/LevenbergMarquardtOptimizer.h>
 | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2022-03-11 05:51:19 +08:00
										 |  |  | // Measurement functions are represented as 'factors'. Several common factors
 | 
					
						
							|  |  |  | // have been provided with the library for solving robotics SLAM problems:
 | 
					
						
							| 
									
										
										
										
											2015-07-13 03:06:55 +08:00
										 |  |  | #include <gtsam/sam/RangeFactor.h>
 | 
					
						
							| 
									
										
										
										
											2022-03-11 05:51:19 +08:00
										 |  |  | #include <gtsam/slam/BetweenFactor.h>
 | 
					
						
							| 
									
										
										
										
											2014-06-13 04:23:41 +08:00
										 |  |  | #include <gtsam/slam/dataset.h>
 | 
					
						
							| 
									
										
										
										
											2013-06-21 22:13:59 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2022-03-11 05:51:19 +08:00
										 |  |  | // Timing, with functions below, provides nice facilities to benchmark.
 | 
					
						
							|  |  |  | #include <gtsam/base/timing.h>
 | 
					
						
							|  |  |  | using gtsam::tictoc_print_; | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | // Standard headers, added last, so we know headers above work on their own.
 | 
					
						
							| 
									
										
										
										
											2013-06-21 22:13:59 +08:00
										 |  |  | #include <fstream>
 | 
					
						
							|  |  |  | #include <iostream>
 | 
					
						
							| 
									
										
										
										
											2022-03-11 06:28:18 +08:00
										 |  |  | #include <random>
 | 
					
						
							|  |  |  | #include <set>
 | 
					
						
							| 
									
										
										
										
											2022-03-11 05:51:19 +08:00
										 |  |  | #include <string>
 | 
					
						
							|  |  |  | #include <utility>
 | 
					
						
							|  |  |  | #include <vector>
 | 
					
						
							| 
									
										
										
										
											2013-06-21 22:13:59 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2013-06-22 08:49:00 +08:00
										 |  |  | namespace NM = gtsam::noiseModel; | 
					
						
							| 
									
										
										
										
											2013-06-21 22:13:59 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2022-03-20 03:19:25 +08:00
										 |  |  | // Data is second UWB ranging dataset, B2 or "plaza 2", from
 | 
					
						
							|  |  |  | // "Navigating with Ranging Radios: Five Data Sets with Ground Truth"
 | 
					
						
							|  |  |  | // by Joseph Djugash, Bradley Hamner, and Stephan Roth
 | 
					
						
							|  |  |  | // https://www.ri.cmu.edu/pub_files/2009/9/Final_5datasetsRangingRadios.pdf
 | 
					
						
							| 
									
										
										
										
											2013-06-21 22:13:59 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  | // load the odometry
 | 
					
						
							|  |  |  | // DR: Odometry Input (delta distance traveled and delta heading change)
 | 
					
						
							| 
									
										
										
										
											2022-03-11 06:28:18 +08:00
										 |  |  | //    Time (sec)  Delta Distance Traveled (m) Delta Heading (rad)
 | 
					
						
							| 
									
										
										
										
											2022-03-11 05:51:19 +08:00
										 |  |  | using TimedOdometry = std::pair<double, Pose2>; | 
					
						
							|  |  |  | std::list<TimedOdometry> readOdometry() { | 
					
						
							|  |  |  |   std::list<TimedOdometry> odometryList; | 
					
						
							|  |  |  |   std::string data_file = gtsam::findExampleDataFile("Plaza2_DR.txt"); | 
					
						
							|  |  |  |   std::ifstream is(data_file.c_str()); | 
					
						
							| 
									
										
										
										
											2013-06-21 22:13:59 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  |   while (is) { | 
					
						
							|  |  |  |     double t, distance_traveled, delta_heading; | 
					
						
							|  |  |  |     is >> t >> distance_traveled >> delta_heading; | 
					
						
							| 
									
										
										
										
											2022-03-11 05:51:19 +08:00
										 |  |  |     odometryList.emplace_back(t, Pose2(distance_traveled, 0, delta_heading)); | 
					
						
							| 
									
										
										
										
											2013-06-21 22:13:59 +08:00
										 |  |  |   } | 
					
						
							|  |  |  |   is.clear(); /* clears the end-of-file and error flags */ | 
					
						
							|  |  |  |   return odometryList; | 
					
						
							|  |  |  | } | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | // load the ranges from TD
 | 
					
						
							|  |  |  | //    Time (sec)  Sender / Antenna ID Receiver Node ID  Range (m)
 | 
					
						
							| 
									
										
										
										
											2022-03-11 05:51:19 +08:00
										 |  |  | using RangeTriple = boost::tuple<double, size_t, double>; | 
					
						
							|  |  |  | std::vector<RangeTriple> readTriples() { | 
					
						
							|  |  |  |   std::vector<RangeTriple> triples; | 
					
						
							|  |  |  |   std::string data_file = gtsam::findExampleDataFile("Plaza2_TD.txt"); | 
					
						
							|  |  |  |   std::ifstream is(data_file.c_str()); | 
					
						
							| 
									
										
										
										
											2013-06-21 22:13:59 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  |   while (is) { | 
					
						
							| 
									
										
										
										
											2022-03-20 03:19:25 +08:00
										 |  |  |     double t, range, sender, receiver; | 
					
						
							| 
									
										
										
										
											2013-06-21 22:13:59 +08:00
										 |  |  |     is >> t >> sender >> receiver >> range; | 
					
						
							| 
									
										
										
										
											2022-03-11 05:51:19 +08:00
										 |  |  |     triples.emplace_back(t, receiver, range); | 
					
						
							| 
									
										
										
										
											2013-06-21 22:13:59 +08:00
										 |  |  |   } | 
					
						
							|  |  |  |   is.clear(); /* clears the end-of-file and error flags */ | 
					
						
							|  |  |  |   return triples; | 
					
						
							|  |  |  | } | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | // main
 | 
					
						
							| 
									
										
										
										
											2022-03-11 05:51:19 +08:00
										 |  |  | int main(int argc, char** argv) { | 
					
						
							| 
									
										
										
										
											2013-06-21 22:13:59 +08:00
										 |  |  |   // load Plaza2 data
 | 
					
						
							| 
									
										
										
										
											2022-03-11 05:51:19 +08:00
										 |  |  |   std::list<TimedOdometry> odometry = readOdometry(); | 
					
						
							| 
									
										
										
										
											2022-03-20 03:19:25 +08:00
										 |  |  |   size_t M = odometry.size(); | 
					
						
							|  |  |  |   std::cout << "Read " << M << " odometry entries." << std::endl; | 
					
						
							| 
									
										
										
										
											2013-06-21 22:13:59 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2022-03-11 05:51:19 +08:00
										 |  |  |   std::vector<RangeTriple> triples = readTriples(); | 
					
						
							| 
									
										
										
										
											2013-06-21 22:13:59 +08:00
										 |  |  |   size_t K = triples.size(); | 
					
						
							| 
									
										
										
										
											2022-03-20 03:19:25 +08:00
										 |  |  |   std::cout << "Read " << K << " range triples." << std::endl; | 
					
						
							| 
									
										
										
										
											2013-06-21 22:13:59 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  |   // parameters
 | 
					
						
							| 
									
										
										
										
											2022-03-11 05:51:19 +08:00
										 |  |  |   size_t minK = | 
					
						
							|  |  |  |       150;  // minimum number of range measurements to process initially
 | 
					
						
							|  |  |  |   size_t incK = 25;  // minimum number of range measurements to process after
 | 
					
						
							| 
									
										
										
										
											2013-06-22 08:49:00 +08:00
										 |  |  |   bool robust = true; | 
					
						
							| 
									
										
										
										
											2013-06-21 22:13:59 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  |   // Set Noise parameters
 | 
					
						
							| 
									
										
										
										
											2022-03-11 05:51:19 +08:00
										 |  |  |   Vector priorSigmas = Vector3(1, 1, M_PI); | 
					
						
							| 
									
										
										
										
											2019-06-10 07:22:54 +08:00
										 |  |  |   Vector odoSigmas = Vector3(0.05, 0.01, 0.1); | 
					
						
							| 
									
										
										
										
											2022-03-11 05:51:19 +08:00
										 |  |  |   double sigmaR = 100;        // range standard deviation
 | 
					
						
							|  |  |  |   const NM::Base::shared_ptr  // all same type
 | 
					
						
							|  |  |  |       priorNoise = NM::Diagonal::Sigmas(priorSigmas),  // prior
 | 
					
						
							| 
									
										
										
										
											2022-03-11 06:28:18 +08:00
										 |  |  |       looseNoise = NM::Isotropic::Sigma(2, 1000),      // loose LM prior
 | 
					
						
							| 
									
										
										
										
											2022-03-11 05:51:19 +08:00
										 |  |  |       odoNoise = NM::Diagonal::Sigmas(odoSigmas),      // odometry
 | 
					
						
							|  |  |  |       gaussian = NM::Isotropic::Sigma(1, sigmaR),      // non-robust
 | 
					
						
							|  |  |  |       tukey = NM::Robust::Create(NM::mEstimator::Tukey::Create(15), | 
					
						
							|  |  |  |                                  gaussian),  // robust
 | 
					
						
							|  |  |  |       rangeNoise = robust ? tukey : gaussian; | 
					
						
							| 
									
										
										
										
											2013-06-21 22:13:59 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  |   // Initialize iSAM
 | 
					
						
							| 
									
										
										
										
											2022-03-11 05:51:19 +08:00
										 |  |  |   gtsam::ISAM2 isam; | 
					
						
							| 
									
										
										
										
											2013-06-21 22:13:59 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  |   // Add prior on first pose
 | 
					
						
							| 
									
										
										
										
											2022-03-11 05:51:19 +08:00
										 |  |  |   Pose2 pose0 = Pose2(-34.2086489999201, 45.3007639991120, M_PI - 2.021089); | 
					
						
							|  |  |  |   gtsam::NonlinearFactorGraph newFactors; | 
					
						
							| 
									
										
										
										
											2020-04-13 01:10:09 +08:00
										 |  |  |   newFactors.addPrior(0, pose0, priorNoise); | 
					
						
							| 
									
										
										
										
											2022-03-11 05:51:19 +08:00
										 |  |  |   gtsam::Values initial; | 
					
						
							| 
									
										
										
										
											2013-06-21 22:13:59 +08:00
										 |  |  |   initial.insert(0, pose0); | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2022-03-11 06:28:18 +08:00
										 |  |  |   // We will initialize landmarks randomly, and keep track of which landmarks we
 | 
					
						
							|  |  |  |   // already added with a set.
 | 
					
						
							|  |  |  |   std::mt19937_64 rng; | 
					
						
							| 
									
										
										
										
											2022-03-20 03:19:25 +08:00
										 |  |  |   std::normal_distribution<double> normal(0.0, 100.0); | 
					
						
							| 
									
										
										
										
											2022-03-11 06:28:18 +08:00
										 |  |  |   std::set<Symbol> initializedLandmarks; | 
					
						
							| 
									
										
										
										
											2013-06-21 22:13:59 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2013-06-22 08:49:00 +08:00
										 |  |  |   // set some loop variables
 | 
					
						
							| 
									
										
										
										
											2022-03-11 05:51:19 +08:00
										 |  |  |   size_t i = 1;  // step counter
 | 
					
						
							|  |  |  |   size_t k = 0;  // range measurement counter
 | 
					
						
							| 
									
										
										
										
											2013-06-22 08:49:00 +08:00
										 |  |  |   bool initialized = false; | 
					
						
							| 
									
										
										
										
											2013-06-21 22:13:59 +08:00
										 |  |  |   Pose2 lastPose = pose0; | 
					
						
							|  |  |  |   size_t countK = 0; | 
					
						
							| 
									
										
										
										
											2013-06-22 08:49:00 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  |   // Loop over odometry
 | 
					
						
							|  |  |  |   gttic_(iSAM); | 
					
						
							| 
									
										
										
										
											2022-03-11 05:51:19 +08:00
										 |  |  |   for (const TimedOdometry& timedOdometry : odometry) { | 
					
						
							|  |  |  |     //--------------------------------- odometry loop --------------------------
 | 
					
						
							| 
									
										
										
										
											2013-06-21 22:13:59 +08:00
										 |  |  |     double t; | 
					
						
							|  |  |  |     Pose2 odometry; | 
					
						
							|  |  |  |     boost::tie(t, odometry) = timedOdometry; | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |     // add odometry factor
 | 
					
						
							| 
									
										
										
										
											2022-03-11 05:51:19 +08:00
										 |  |  |     newFactors.emplace_shared<gtsam::BetweenFactor<Pose2>>(i - 1, i, odometry, | 
					
						
							|  |  |  |                                                            odoNoise); | 
					
						
							| 
									
										
										
										
											2013-06-21 22:13:59 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  |     // predict pose and add as initial estimate
 | 
					
						
							|  |  |  |     Pose2 predictedPose = lastPose.compose(odometry); | 
					
						
							|  |  |  |     lastPose = predictedPose; | 
					
						
							|  |  |  |     initial.insert(i, predictedPose); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |     // Check if there are range factors to be added
 | 
					
						
							|  |  |  |     while (k < K && t >= boost::get<0>(triples[k])) { | 
					
						
							|  |  |  |       size_t j = boost::get<1>(triples[k]); | 
					
						
							| 
									
										
										
										
											2022-03-11 06:28:18 +08:00
										 |  |  |       Symbol landmark_key('L', j); | 
					
						
							| 
									
										
										
										
											2013-06-21 22:13:59 +08:00
										 |  |  |       double range = boost::get<2>(triples[k]); | 
					
						
							| 
									
										
										
										
											2022-03-11 05:51:19 +08:00
										 |  |  |       newFactors.emplace_shared<gtsam::RangeFactor<Pose2, Point2>>( | 
					
						
							| 
									
										
										
										
											2022-03-11 06:28:18 +08:00
										 |  |  |           i, landmark_key, range, rangeNoise); | 
					
						
							|  |  |  |       if (initializedLandmarks.count(landmark_key) == 0) { | 
					
						
							| 
									
										
										
										
											2022-03-20 03:19:25 +08:00
										 |  |  |         std::cout << "adding landmark " << j << std::endl; | 
					
						
							| 
									
										
										
										
											2022-03-11 06:28:18 +08:00
										 |  |  |         double x = normal(rng), y = normal(rng); | 
					
						
							|  |  |  |         initial.insert(landmark_key, Point2(x, y)); | 
					
						
							|  |  |  |         initializedLandmarks.insert(landmark_key); | 
					
						
							|  |  |  |         // We also add a very loose prior on the landmark in case there is only
 | 
					
						
							|  |  |  |         // one sighting, which cannot fully determine the landmark.
 | 
					
						
							|  |  |  |         newFactors.emplace_shared<gtsam::PriorFactor<Point2>>( | 
					
						
							|  |  |  |             landmark_key, Point2(0, 0), looseNoise); | 
					
						
							|  |  |  |       } | 
					
						
							| 
									
										
										
										
											2013-06-21 22:13:59 +08:00
										 |  |  |       k = k + 1; | 
					
						
							|  |  |  |       countK = countK + 1; | 
					
						
							|  |  |  |     } | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |     // Check whether to update iSAM 2
 | 
					
						
							| 
									
										
										
										
											2013-06-22 08:49:00 +08:00
										 |  |  |     if ((k > minK) && (countK > incK)) { | 
					
						
							| 
									
										
										
										
											2022-03-11 05:51:19 +08:00
										 |  |  |       if (!initialized) {  // Do a full optimize for first minK ranges
 | 
					
						
							| 
									
										
										
										
											2022-03-20 03:19:25 +08:00
										 |  |  |         std::cout << "Initializing at time " << k << std::endl; | 
					
						
							| 
									
										
										
										
											2013-06-21 22:13:59 +08:00
										 |  |  |         gttic_(batchInitialization); | 
					
						
							| 
									
										
										
										
											2022-03-11 05:51:19 +08:00
										 |  |  |         gtsam::LevenbergMarquardtOptimizer batchOptimizer(newFactors, initial); | 
					
						
							| 
									
										
										
										
											2013-06-21 22:13:59 +08:00
										 |  |  |         initial = batchOptimizer.optimize(); | 
					
						
							|  |  |  |         gttoc_(batchInitialization); | 
					
						
							| 
									
										
										
										
											2013-06-22 08:49:00 +08:00
										 |  |  |         initialized = true; | 
					
						
							| 
									
										
										
										
											2013-06-21 22:13:59 +08:00
										 |  |  |       } | 
					
						
							|  |  |  |       gttic_(update); | 
					
						
							|  |  |  |       isam.update(newFactors, initial); | 
					
						
							|  |  |  |       gttoc_(update); | 
					
						
							|  |  |  |       gttic_(calculateEstimate); | 
					
						
							| 
									
										
										
										
											2022-03-11 05:51:19 +08:00
										 |  |  |       gtsam::Values result = isam.calculateEstimate(); | 
					
						
							| 
									
										
										
										
											2013-06-21 22:13:59 +08:00
										 |  |  |       gttoc_(calculateEstimate); | 
					
						
							|  |  |  |       lastPose = result.at<Pose2>(i); | 
					
						
							| 
									
										
										
										
											2022-03-11 05:51:19 +08:00
										 |  |  |       newFactors = gtsam::NonlinearFactorGraph(); | 
					
						
							|  |  |  |       initial = gtsam::Values(); | 
					
						
							| 
									
										
										
										
											2013-06-21 22:13:59 +08:00
										 |  |  |       countK = 0; | 
					
						
							|  |  |  |     } | 
					
						
							|  |  |  |     i += 1; | 
					
						
							| 
									
										
										
										
											2022-03-11 05:51:19 +08:00
										 |  |  |     //--------------------------------- odometry loop --------------------------
 | 
					
						
							|  |  |  |   }  // end for
 | 
					
						
							| 
									
										
										
										
											2013-06-21 22:13:59 +08:00
										 |  |  |   gttoc_(iSAM); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   // Print timings
 | 
					
						
							|  |  |  |   tictoc_print_(); | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2022-03-11 06:28:18 +08:00
										 |  |  |   // Print optimized landmarks:
 | 
					
						
							|  |  |  |   gtsam::Values finalResult = isam.calculateEstimate(); | 
					
						
							|  |  |  |   for (auto&& landmark_key : initializedLandmarks) { | 
					
						
							|  |  |  |     Point2 p = finalResult.at<Point2>(landmark_key); | 
					
						
							|  |  |  |     std::cout << landmark_key << ":" << p.transpose() << "\n"; | 
					
						
							|  |  |  |   } | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2013-06-21 22:13:59 +08:00
										 |  |  |   exit(0); | 
					
						
							|  |  |  | } |