SmartRangeExample_plaza2.cpp 7.4 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214
  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 SmartRangeExample_plaza2.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. // To find data files, we can use `findExampleDataFile`, declared here:
  33. #include <gtsam/slam/dataset.h>
  34. // Standard headers, added last, so we know headers above work on their own
  35. #include <fstream>
  36. #include <iostream>
  37. using namespace std;
  38. using namespace gtsam;
  39. namespace NM = gtsam::noiseModel;
  40. // data available at http://www.frc.ri.cmu.edu/projects/emergencyresponse/RangeData/
  41. // Datafile format (from http://www.frc.ri.cmu.edu/projects/emergencyresponse/RangeData/log.html)
  42. // load the odometry
  43. // DR: Odometry Input (delta distance traveled and delta heading change)
  44. // Time (sec) Delta Dist. Trav. (m) Delta Heading (rad)
  45. typedef pair<double, Pose2> TimedOdometry;
  46. list<TimedOdometry> readOdometry() {
  47. list<TimedOdometry> odometryList;
  48. string drFile = findExampleDataFile("Plaza2_DR.txt");
  49. ifstream is(drFile);
  50. if (!is) throw runtime_error("Plaza2_DR.txt file not found");
  51. while (is) {
  52. double t, distance_traveled, delta_heading;
  53. is >> t >> distance_traveled >> delta_heading;
  54. odometryList.push_back(
  55. TimedOdometry(t, Pose2(distance_traveled, 0, delta_heading)));
  56. }
  57. is.clear(); /* clears the end-of-file and error flags */
  58. return odometryList;
  59. }
  60. // load the ranges from TD
  61. // Time (sec) Sender / Antenna ID Receiver Node ID Range (m)
  62. typedef boost::tuple<double, size_t, double> RangeTriple;
  63. vector<RangeTriple> readTriples() {
  64. vector<RangeTriple> triples;
  65. string tdFile = findExampleDataFile("Plaza2_TD.txt");
  66. ifstream is(tdFile);
  67. if (!is) throw runtime_error("Plaza2_TD.txt file not found");
  68. while (is) {
  69. double t, sender, receiver, range;
  70. is >> t >> sender >> receiver >> range;
  71. triples.push_back(RangeTriple(t, receiver, range));
  72. }
  73. is.clear(); /* clears the end-of-file and error flags */
  74. return triples;
  75. }
  76. // main
  77. int main(int argc, char** argv) {
  78. // load Plaza1 data
  79. list<TimedOdometry> odometry = readOdometry();
  80. // size_t M = odometry.size();
  81. vector<RangeTriple> triples = readTriples();
  82. size_t K = triples.size();
  83. // parameters
  84. size_t incK = 50; // minimum number of range measurements to process after
  85. bool robust = false;
  86. // Set Noise parameters
  87. Vector priorSigmas = Vector3(0.01, 0.01, 0.01);
  88. Vector odoSigmas = Vector3(0.05, 0.01, 0.2);
  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, -2.02108900000000);
  100. NonlinearFactorGraph newFactors;
  101. newFactors.addPrior(0, pose0, priorNoise);
  102. // initialize points (Gaussian)
  103. Values initial;
  104. initial.insert(symbol('L', 1), Point2(-68.9265, 18.3778));
  105. initial.insert(symbol('L', 6), Point2(-37.5805, 69.2278));
  106. initial.insert(symbol('L', 0), Point2(-33.6205, 26.9678));
  107. initial.insert(symbol('L', 5), Point2(1.7095, -5.8122));
  108. Values landmarkEstimates = initial; // copy landmarks
  109. initial.insert(0, pose0);
  110. // set some loop variables
  111. size_t i = 1; // step counter
  112. size_t k = 0; // range measurement counter
  113. Pose2 lastPose = pose0;
  114. size_t countK = 0;
  115. // Loop over odometry
  116. gttic_(iSAM);
  117. for(const TimedOdometry& timedOdometry: odometry) {
  118. //--------------------------------- odometry loop -----------------------------------------
  119. double t;
  120. Pose2 odometry;
  121. boost::tie(t, odometry) = timedOdometry;
  122. // add odometry factor
  123. newFactors.push_back(
  124. BetweenFactor<Pose2>(i - 1, i, odometry,
  125. NM::Diagonal::Sigmas(odoSigmas)));
  126. // predict pose and add as initial estimate
  127. Pose2 predictedPose = lastPose.compose(odometry);
  128. lastPose = predictedPose;
  129. initial.insert(i, predictedPose);
  130. landmarkEstimates.insert(i, predictedPose);
  131. // Check if there are range factors to be added
  132. while (k < K && t >= boost::get<0>(triples[k])) {
  133. size_t j = boost::get<1>(triples[k]);
  134. double range = boost::get<2>(triples[k]);
  135. RangeFactor<Pose2, Point2> factor(i, symbol('L', j), range, rangeNoise);
  136. // Throw out obvious outliers based on current landmark estimates
  137. Vector error = factor.unwhitenedError(landmarkEstimates);
  138. if (k <= 200 || std::abs(error[0]) < 5)
  139. newFactors.push_back(factor);
  140. k = k + 1;
  141. countK = countK + 1;
  142. }
  143. // Check whether to update iSAM 2
  144. if (countK > incK) {
  145. gttic_(update);
  146. isam.update(newFactors, initial);
  147. gttoc_(update);
  148. gttic_(calculateEstimate);
  149. Values result = isam.calculateEstimate();
  150. gttoc_(calculateEstimate);
  151. lastPose = result.at<Pose2>(i);
  152. // update landmark estimates
  153. landmarkEstimates = Values();
  154. landmarkEstimates.insert(symbol('L', 1), result.at(symbol('L', 1)));
  155. landmarkEstimates.insert(symbol('L', 6), result.at(symbol('L', 6)));
  156. landmarkEstimates.insert(symbol('L', 0), result.at(symbol('L', 0)));
  157. landmarkEstimates.insert(symbol('L', 5), result.at(symbol('L', 5)));
  158. newFactors = NonlinearFactorGraph();
  159. initial = Values();
  160. countK = 0;
  161. }
  162. i += 1;
  163. //--------------------------------- odometry loop -----------------------------------------
  164. } // end for
  165. gttoc_(iSAM);
  166. // Print timings
  167. tictoc_print_();
  168. // Write result to file
  169. Values result = isam.calculateEstimate();
  170. ofstream os2("rangeResultLM.txt");
  171. for(const auto it: result.filter<Point2>())
  172. os2 << it.key << "\t" << it.value.x() << "\t" << it.value.y() << "\t1"
  173. << endl;
  174. ofstream os("rangeResult.txt");
  175. for(const auto it: result.filter<Pose2>())
  176. os << it.key << "\t" << it.value.x() << "\t" << it.value.y() << "\t"
  177. << it.value.theta() << endl;
  178. exit(0);
  179. }