| 
									
										
										
										
											2013-06-24 20:06:47 +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 SmartRangeExample_plaza2.cpp | 
					
						
							|  |  |  |  * @brief A 2D Range SLAM example | 
					
						
							|  |  |  |  * @date June 20, 2013 | 
					
						
							|  |  |  |  * @author FRank Dellaert | 
					
						
							|  |  |  |  */ | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | // Both relative poses and recovered trajectory poses will be stored as Pose2 objects
 | 
					
						
							|  |  |  | #include <gtsam/geometry/Pose2.h>
 | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | // 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>
 | 
					
						
							| 
									
										
										
										
											2013-06-24 20:06:47 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  | // We want to use iSAM2 to solve the range-SLAM problem incrementally
 | 
					
						
							|  |  |  | #include <gtsam/nonlinear/ISAM2.h>
 | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | // 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 used in the added factors
 | 
					
						
							|  |  |  | #include <gtsam/nonlinear/NonlinearFactorGraph.h>
 | 
					
						
							|  |  |  | #include <gtsam/nonlinear/Values.h>
 | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | // We will use a non-liear solver to batch-inituialize from the first 150 frames
 | 
					
						
							|  |  |  | #include <gtsam/nonlinear/LevenbergMarquardtOptimizer.h>
 | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | // In GTSAM, measurement functions are represented as 'factors'. Several common factors
 | 
					
						
							|  |  |  | // have been provided with the library for solving robotics SLAM problems.
 | 
					
						
							|  |  |  | #include <gtsam/slam/BetweenFactor.h>
 | 
					
						
							| 
									
										
										
										
											2015-07-13 03:06:55 +08:00
										 |  |  | #include <gtsam/sam/RangeFactor.h>
 | 
					
						
							| 
									
										
										
										
											2013-06-24 20:06:47 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2019-06-03 05:55:47 +08:00
										 |  |  | // To find data files, we can use `findExampleDataFile`, declared here:
 | 
					
						
							|  |  |  | #include <gtsam/slam/dataset.h>
 | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2013-06-24 20:06:47 +08:00
										 |  |  | // Standard headers, added last, so we know headers above work on their own
 | 
					
						
							|  |  |  | #include <fstream>
 | 
					
						
							|  |  |  | #include <iostream>
 | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | using namespace std; | 
					
						
							|  |  |  | using namespace gtsam; | 
					
						
							|  |  |  | namespace NM = gtsam::noiseModel; | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | // data available at http://www.frc.ri.cmu.edu/projects/emergencyresponse/RangeData/
 | 
					
						
							|  |  |  | // Datafile format (from http://www.frc.ri.cmu.edu/projects/emergencyresponse/RangeData/log.html)
 | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | // load the odometry
 | 
					
						
							|  |  |  | // DR: Odometry Input (delta distance traveled and delta heading change)
 | 
					
						
							|  |  |  | //    Time (sec)  Delta Dist. Trav. (m) Delta Heading (rad)
 | 
					
						
							|  |  |  | typedef pair<double, Pose2> TimedOdometry; | 
					
						
							|  |  |  | list<TimedOdometry> readOdometry() { | 
					
						
							|  |  |  |   list<TimedOdometry> odometryList; | 
					
						
							| 
									
										
										
										
											2019-06-03 05:55:47 +08:00
										 |  |  |   string drFile = findExampleDataFile("Plaza2_DR.txt"); | 
					
						
							|  |  |  |   ifstream is(drFile); | 
					
						
							|  |  |  |   if (!is) throw runtime_error("Plaza2_DR.txt file not found"); | 
					
						
							| 
									
										
										
										
											2013-06-24 20:06:47 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  |   while (is) { | 
					
						
							|  |  |  |     double t, distance_traveled, delta_heading; | 
					
						
							|  |  |  |     is >> t >> distance_traveled >> delta_heading; | 
					
						
							|  |  |  |     odometryList.push_back( | 
					
						
							|  |  |  |         TimedOdometry(t, Pose2(distance_traveled, 0, delta_heading))); | 
					
						
							|  |  |  |   } | 
					
						
							|  |  |  |   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)
 | 
					
						
							|  |  |  | typedef boost::tuple<double, size_t, double> RangeTriple; | 
					
						
							|  |  |  | vector<RangeTriple> readTriples() { | 
					
						
							|  |  |  |   vector<RangeTriple> triples; | 
					
						
							| 
									
										
										
										
											2019-06-03 05:55:47 +08:00
										 |  |  |   string tdFile = findExampleDataFile("Plaza2_TD.txt"); | 
					
						
							|  |  |  |   ifstream is(tdFile); | 
					
						
							|  |  |  |   if (!is) throw runtime_error("Plaza2_TD.txt file not found"); | 
					
						
							| 
									
										
										
										
											2013-06-24 20:06:47 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  |   while (is) { | 
					
						
							|  |  |  |     double t, sender, receiver, range; | 
					
						
							|  |  |  |     is >> t >> sender >> receiver >> range; | 
					
						
							|  |  |  |     triples.push_back(RangeTriple(t, receiver, range)); | 
					
						
							|  |  |  |   } | 
					
						
							|  |  |  |   is.clear(); /* clears the end-of-file and error flags */ | 
					
						
							|  |  |  |   return triples; | 
					
						
							|  |  |  | } | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | // main
 | 
					
						
							| 
									
										
										
										
											2013-06-26 01:13:02 +08:00
										 |  |  | int main(int argc, char** argv) { | 
					
						
							| 
									
										
										
										
											2013-06-24 20:06:47 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  |   // load Plaza1 data
 | 
					
						
							|  |  |  |   list<TimedOdometry> odometry = readOdometry(); | 
					
						
							|  |  |  | //  size_t M = odometry.size();
 | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   vector<RangeTriple> triples = readTriples(); | 
					
						
							|  |  |  |   size_t K = triples.size(); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   // parameters
 | 
					
						
							|  |  |  |   size_t incK = 50; // minimum number of range measurements to process after
 | 
					
						
							|  |  |  |   bool robust = false; | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   // Set Noise parameters
 | 
					
						
							| 
									
										
										
										
											2013-06-26 01:13:02 +08:00
										 |  |  |   Vector priorSigmas = Vector3(0.01, 0.01, 0.01); | 
					
						
							| 
									
										
										
										
											2013-06-24 20:06:47 +08:00
										 |  |  |   Vector odoSigmas = Vector3(0.05, 0.01, 0.2); | 
					
						
							|  |  |  |   double sigmaR = 100; // range standard deviation
 | 
					
						
							|  |  |  |   const NM::Base::shared_ptr // all same type
 | 
					
						
							|  |  |  |   priorNoise = NM::Diagonal::Sigmas(priorSigmas), //prior
 | 
					
						
							|  |  |  |   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; | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   // Initialize iSAM
 | 
					
						
							|  |  |  |   ISAM2 isam; | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   // Add prior on first pose
 | 
					
						
							| 
									
										
										
										
											2013-06-26 01:13:02 +08:00
										 |  |  |   Pose2 pose0 = Pose2(-34.2086489999201, 45.3007639991120, -2.02108900000000); | 
					
						
							| 
									
										
										
										
											2013-06-24 20:06:47 +08:00
										 |  |  |   NonlinearFactorGraph newFactors; | 
					
						
							| 
									
										
										
										
											2020-04-13 01:10:09 +08:00
										 |  |  |   newFactors.addPrior(0, pose0, priorNoise); | 
					
						
							| 
									
										
										
										
											2013-06-24 20:06:47 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  |   //  initialize points (Gaussian)
 | 
					
						
							|  |  |  |   Values initial; | 
					
						
							|  |  |  |   initial.insert(symbol('L', 1), Point2(-68.9265, 18.3778)); | 
					
						
							|  |  |  |   initial.insert(symbol('L', 6), Point2(-37.5805, 69.2278)); | 
					
						
							|  |  |  |   initial.insert(symbol('L', 0), Point2(-33.6205, 26.9678)); | 
					
						
							|  |  |  |   initial.insert(symbol('L', 5), Point2(1.7095, -5.8122)); | 
					
						
							|  |  |  |   Values landmarkEstimates = initial; // copy landmarks
 | 
					
						
							|  |  |  |   initial.insert(0, pose0); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   // set some loop variables
 | 
					
						
							|  |  |  |   size_t i = 1; // step counter
 | 
					
						
							|  |  |  |   size_t k = 0; // range measurement counter
 | 
					
						
							|  |  |  |   Pose2 lastPose = pose0; | 
					
						
							|  |  |  |   size_t countK = 0; | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   // Loop over odometry
 | 
					
						
							|  |  |  |   gttic_(iSAM); | 
					
						
							| 
									
										
										
										
											2016-05-21 11:41:41 +08:00
										 |  |  |   for(const TimedOdometry& timedOdometry: odometry) { | 
					
						
							| 
									
										
										
										
											2013-06-24 20:06:47 +08:00
										 |  |  |     //--------------------------------- odometry loop -----------------------------------------
 | 
					
						
							|  |  |  |     double t; | 
					
						
							|  |  |  |     Pose2 odometry; | 
					
						
							|  |  |  |     boost::tie(t, odometry) = timedOdometry; | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |     // add odometry factor
 | 
					
						
							| 
									
										
										
										
											2013-08-19 23:32:08 +08:00
										 |  |  |     newFactors.push_back( | 
					
						
							| 
									
										
										
										
											2013-06-26 01:13:02 +08:00
										 |  |  |         BetweenFactor<Pose2>(i - 1, i, odometry, | 
					
						
							|  |  |  |             NM::Diagonal::Sigmas(odoSigmas))); | 
					
						
							| 
									
										
										
										
											2013-06-24 20:06:47 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  |     // predict pose and add as initial estimate
 | 
					
						
							|  |  |  |     Pose2 predictedPose = lastPose.compose(odometry); | 
					
						
							|  |  |  |     lastPose = predictedPose; | 
					
						
							|  |  |  |     initial.insert(i, predictedPose); | 
					
						
							|  |  |  |     landmarkEstimates.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]); | 
					
						
							|  |  |  |       double range = boost::get<2>(triples[k]); | 
					
						
							| 
									
										
										
										
											2013-06-26 01:13:02 +08:00
										 |  |  |       RangeFactor<Pose2, Point2> factor(i, symbol('L', j), range, rangeNoise); | 
					
						
							| 
									
										
										
										
											2013-06-24 20:06:47 +08:00
										 |  |  |       // Throw out obvious outliers based on current landmark estimates
 | 
					
						
							| 
									
										
										
										
											2013-06-26 01:13:02 +08:00
										 |  |  |       Vector error = factor.unwhitenedError(landmarkEstimates); | 
					
						
							| 
									
										
										
										
											2019-09-19 03:24:09 +08:00
										 |  |  |       if (k <= 200 || std::abs(error[0]) < 5) | 
					
						
							| 
									
										
										
										
											2013-08-19 23:32:08 +08:00
										 |  |  |         newFactors.push_back(factor); | 
					
						
							| 
									
										
										
										
											2013-06-24 20:06:47 +08:00
										 |  |  |       k = k + 1; | 
					
						
							|  |  |  |       countK = countK + 1; | 
					
						
							|  |  |  |     } | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |     // Check whether to update iSAM 2
 | 
					
						
							|  |  |  |     if (countK > incK) { | 
					
						
							|  |  |  |       gttic_(update); | 
					
						
							|  |  |  |       isam.update(newFactors, initial); | 
					
						
							|  |  |  |       gttoc_(update); | 
					
						
							|  |  |  |       gttic_(calculateEstimate); | 
					
						
							|  |  |  |       Values result = isam.calculateEstimate(); | 
					
						
							|  |  |  |       gttoc_(calculateEstimate); | 
					
						
							|  |  |  |       lastPose = result.at<Pose2>(i); | 
					
						
							|  |  |  |       // update landmark estimates
 | 
					
						
							|  |  |  |       landmarkEstimates = Values(); | 
					
						
							|  |  |  |       landmarkEstimates.insert(symbol('L', 1), result.at(symbol('L', 1))); | 
					
						
							|  |  |  |       landmarkEstimates.insert(symbol('L', 6), result.at(symbol('L', 6))); | 
					
						
							|  |  |  |       landmarkEstimates.insert(symbol('L', 0), result.at(symbol('L', 0))); | 
					
						
							|  |  |  |       landmarkEstimates.insert(symbol('L', 5), result.at(symbol('L', 5))); | 
					
						
							|  |  |  |       newFactors = NonlinearFactorGraph(); | 
					
						
							|  |  |  |       initial = Values(); | 
					
						
							|  |  |  |       countK = 0; | 
					
						
							|  |  |  |     } | 
					
						
							|  |  |  |     i += 1; | 
					
						
							|  |  |  |     //--------------------------------- odometry loop -----------------------------------------
 | 
					
						
							| 
									
										
										
										
											2016-05-21 11:41:41 +08:00
										 |  |  |   } // end for
 | 
					
						
							| 
									
										
										
										
											2013-06-24 20:06:47 +08:00
										 |  |  |   gttoc_(iSAM); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   // Print timings
 | 
					
						
							|  |  |  |   tictoc_print_(); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   // Write result to file
 | 
					
						
							|  |  |  |   Values result = isam.calculateEstimate(); | 
					
						
							| 
									
										
										
										
											2019-06-03 05:55:47 +08:00
										 |  |  |   ofstream os2("rangeResultLM.txt"); | 
					
						
							| 
									
										
										
										
											2021-01-05 09:46:16 +08:00
										 |  |  |   for(const auto it: result.filter<Point2>()) | 
					
						
							| 
									
										
										
										
											2013-06-26 01:13:02 +08:00
										 |  |  |     os2 << it.key << "\t" << it.value.x() << "\t" << it.value.y() << "\t1" | 
					
						
							|  |  |  |         << endl; | 
					
						
							| 
									
										
										
										
											2019-06-03 05:55:47 +08:00
										 |  |  |   ofstream os("rangeResult.txt"); | 
					
						
							| 
									
										
										
										
											2021-01-05 09:46:16 +08:00
										 |  |  |   for(const auto it: result.filter<Pose2>()) | 
					
						
							| 
									
										
										
										
											2013-06-26 01:13:02 +08:00
										 |  |  |     os << it.key << "\t" << it.value.x() << "\t" << it.value.y() << "\t" | 
					
						
							|  |  |  |         << it.value.theta() << endl; | 
					
						
							| 
									
										
										
										
											2013-06-24 20:06:47 +08:00
										 |  |  |   exit(0); | 
					
						
							|  |  |  | } | 
					
						
							|  |  |  | 
 |