RangeISAMExample_plaza2.cpp 6.9 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205
  1. /* ----------------------------------------------------------------------------
  2. * GTSAM Copyright 2010, Georgia Tech Research Corporation,
  3. * Atlanta, Georgia 30332-0415
  4. * All Rights Reserved
  5. * Authors: Frank Dellaert, et al. (see THANKS for the full author list)
  6. * See LICENSE for the license information
  7. * -------------------------------------------------------------------------- */
  8. /**
  9. * @file RangeISAMExample_plaza1.cpp
  10. * @brief A 2D Range SLAM example
  11. * @date June 20, 2013
  12. * @author FRank Dellaert
  13. */
  14. // Both relative poses and recovered trajectory poses will be stored as Pose2 objects
  15. #include <gtsam/geometry/Pose2.h>
  16. // Each variable in the system (poses and landmarks) must be identified with a unique key.
  17. // We can either use simple integer keys (1, 2, 3, ...) or symbols (X1, X2, L1).
  18. // Here we will use Symbols
  19. #include <gtsam/inference/Symbol.h>
  20. // We want to use iSAM2 to solve the range-SLAM problem incrementally
  21. #include <gtsam/nonlinear/ISAM2.h>
  22. // iSAM2 requires as input a set set of new factors to be added stored in a factor graph,
  23. // and initial guesses for any new variables used in the added factors
  24. #include <gtsam/nonlinear/NonlinearFactorGraph.h>
  25. #include <gtsam/nonlinear/Values.h>
  26. // We will use a non-liear solver to batch-inituialize from the first 150 frames
  27. #include <gtsam/nonlinear/LevenbergMarquardtOptimizer.h>
  28. // In GTSAM, measurement functions are represented as 'factors'. Several common factors
  29. // have been provided with the library for solving robotics SLAM problems.
  30. #include <gtsam/slam/BetweenFactor.h>
  31. #include <gtsam/sam/RangeFactor.h>
  32. #include <gtsam/slam/dataset.h>
  33. // Standard headers, added last, so we know headers above work on their own
  34. #include <fstream>
  35. #include <iostream>
  36. using namespace std;
  37. using namespace gtsam;
  38. namespace NM = gtsam::noiseModel;
  39. // data available at http://www.frc.ri.cmu.edu/projects/emergencyresponse/RangeData/
  40. // Datafile format (from http://www.frc.ri.cmu.edu/projects/emergencyresponse/RangeData/log.html)
  41. // load the odometry
  42. // DR: Odometry Input (delta distance traveled and delta heading change)
  43. // Time (sec) Delta Dist. Trav. (m) Delta Heading (rad)
  44. typedef pair<double, Pose2> TimedOdometry;
  45. list<TimedOdometry> readOdometry() {
  46. list<TimedOdometry> odometryList;
  47. string data_file = findExampleDataFile("Plaza2_DR.txt");
  48. ifstream is(data_file.c_str());
  49. while (is) {
  50. double t, distance_traveled, delta_heading;
  51. is >> t >> distance_traveled >> delta_heading;
  52. odometryList.push_back(
  53. TimedOdometry(t, Pose2(distance_traveled, 0, delta_heading)));
  54. }
  55. is.clear(); /* clears the end-of-file and error flags */
  56. return odometryList;
  57. }
  58. // load the ranges from TD
  59. // Time (sec) Sender / Antenna ID Receiver Node ID Range (m)
  60. typedef boost::tuple<double, size_t, double> RangeTriple;
  61. vector<RangeTriple> readTriples() {
  62. vector<RangeTriple> triples;
  63. string data_file = findExampleDataFile("Plaza2_TD.txt");
  64. ifstream is(data_file.c_str());
  65. while (is) {
  66. double t, sender, range;
  67. size_t receiver;
  68. is >> t >> sender >> receiver >> range;
  69. triples.push_back(RangeTriple(t, receiver, range));
  70. }
  71. is.clear(); /* clears the end-of-file and error flags */
  72. return triples;
  73. }
  74. // main
  75. int main (int argc, char** argv) {
  76. // load Plaza2 data
  77. list<TimedOdometry> odometry = readOdometry();
  78. // size_t M = odometry.size();
  79. vector<RangeTriple> triples = readTriples();
  80. size_t K = triples.size();
  81. // parameters
  82. size_t minK = 150; // minimum number of range measurements to process initially
  83. size_t incK = 25; // minimum number of range measurements to process after
  84. bool groundTruth = false;
  85. bool robust = true;
  86. // Set Noise parameters
  87. Vector priorSigmas = Vector3(1,1,M_PI);
  88. Vector odoSigmas = Vector3(0.05, 0.01, 0.1);
  89. double sigmaR = 100; // range standard deviation
  90. const NM::Base::shared_ptr // all same type
  91. priorNoise = NM::Diagonal::Sigmas(priorSigmas), //prior
  92. odoNoise = NM::Diagonal::Sigmas(odoSigmas), // odometry
  93. gaussian = NM::Isotropic::Sigma(1, sigmaR), // non-robust
  94. tukey = NM::Robust::Create(NM::mEstimator::Tukey::Create(15), gaussian), //robust
  95. rangeNoise = robust ? tukey : gaussian;
  96. // Initialize iSAM
  97. ISAM2 isam;
  98. // Add prior on first pose
  99. Pose2 pose0 = Pose2(-34.2086489999201, 45.3007639991120,
  100. M_PI - 2.02108900000000);
  101. NonlinearFactorGraph newFactors;
  102. newFactors.addPrior(0, pose0, priorNoise);
  103. Values initial;
  104. initial.insert(0, pose0);
  105. // initialize points
  106. if (groundTruth) { // from TL file
  107. initial.insert(symbol('L', 1), Point2(-68.9265, 18.3778));
  108. initial.insert(symbol('L', 6), Point2(-37.5805, 69.2278));
  109. initial.insert(symbol('L', 0), Point2(-33.6205, 26.9678));
  110. initial.insert(symbol('L', 5), Point2(1.7095, -5.8122));
  111. } else { // drawn from sigma=1 Gaussian in matlab version
  112. initial.insert(symbol('L', 1), Point2(3.5784, 2.76944));
  113. initial.insert(symbol('L', 6), Point2(-1.34989, 3.03492));
  114. initial.insert(symbol('L', 0), Point2(0.725404, -0.0630549));
  115. initial.insert(symbol('L', 5), Point2(0.714743, -0.204966));
  116. }
  117. // set some loop variables
  118. size_t i = 1; // step counter
  119. size_t k = 0; // range measurement counter
  120. bool initialized = false;
  121. Pose2 lastPose = pose0;
  122. size_t countK = 0;
  123. // Loop over odometry
  124. gttic_(iSAM);
  125. for(const TimedOdometry& timedOdometry: odometry) {
  126. //--------------------------------- odometry loop -----------------------------------------
  127. double t;
  128. Pose2 odometry;
  129. boost::tie(t, odometry) = timedOdometry;
  130. // add odometry factor
  131. newFactors.push_back(BetweenFactor<Pose2>(i-1, i, odometry, odoNoise));
  132. // predict pose and add as initial estimate
  133. Pose2 predictedPose = lastPose.compose(odometry);
  134. lastPose = predictedPose;
  135. initial.insert(i, predictedPose);
  136. // Check if there are range factors to be added
  137. while (k < K && t >= boost::get<0>(triples[k])) {
  138. size_t j = boost::get<1>(triples[k]);
  139. double range = boost::get<2>(triples[k]);
  140. newFactors.push_back(RangeFactor<Pose2, Point2>(i, symbol('L', j), range,rangeNoise));
  141. k = k + 1;
  142. countK = countK + 1;
  143. }
  144. // Check whether to update iSAM 2
  145. if ((k > minK) && (countK > incK)) {
  146. if (!initialized) { // Do a full optimize for first minK ranges
  147. gttic_(batchInitialization);
  148. LevenbergMarquardtOptimizer batchOptimizer(newFactors, initial);
  149. initial = batchOptimizer.optimize();
  150. gttoc_(batchInitialization);
  151. initialized = true;
  152. }
  153. gttic_(update);
  154. isam.update(newFactors, initial);
  155. gttoc_(update);
  156. gttic_(calculateEstimate);
  157. Values result = isam.calculateEstimate();
  158. gttoc_(calculateEstimate);
  159. lastPose = result.at<Pose2>(i);
  160. newFactors = NonlinearFactorGraph();
  161. initial = Values();
  162. countK = 0;
  163. }
  164. i += 1;
  165. //--------------------------------- odometry loop -----------------------------------------
  166. } // end for
  167. gttoc_(iSAM);
  168. // Print timings
  169. tictoc_print_();
  170. exit(0);
  171. }