timeIncremental.cpp 8.3 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262
  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 timeIncremental.cpp
  10. * @brief Overall timing tests for incremental solving
  11. * @author Richard Roberts
  12. */
  13. #include <gtsam/slam/dataset.h>
  14. #include <gtsam/slam/BetweenFactor.h>
  15. #include <gtsam/sam/BearingRangeFactor.h>
  16. #include <gtsam/geometry/Pose2.h>
  17. #include <gtsam/inference/Symbol.h>
  18. #include <gtsam/nonlinear/ISAM2.h>
  19. #include <gtsam/nonlinear/Marginals.h>
  20. #include <gtsam/base/timing.h>
  21. #include <fstream>
  22. #include <boost/archive/binary_oarchive.hpp>
  23. #include <boost/archive/binary_iarchive.hpp>
  24. #include <boost/serialization/export.hpp>
  25. #include <boost/range/adaptor/reversed.hpp>
  26. using namespace std;
  27. using namespace gtsam;
  28. using namespace gtsam::symbol_shorthand;
  29. typedef Pose2 Pose;
  30. typedef NoiseModelFactor1<Pose> NM1;
  31. typedef NoiseModelFactor2<Pose,Pose> NM2;
  32. typedef BearingRangeFactor<Pose,Point2> BR;
  33. //GTSAM_VALUE_EXPORT(Value);
  34. //GTSAM_VALUE_EXPORT(Pose);
  35. //GTSAM_VALUE_EXPORT(NonlinearFactor);
  36. //GTSAM_VALUE_EXPORT(NoiseModelFactor);
  37. //GTSAM_VALUE_EXPORT(NM1);
  38. //GTSAM_VALUE_EXPORT(NM2);
  39. //GTSAM_VALUE_EXPORT(BetweenFactor<Pose>);
  40. //GTSAM_VALUE_EXPORT(PriorFactor<Pose>);
  41. //GTSAM_VALUE_EXPORT(BR);
  42. //GTSAM_VALUE_EXPORT(noiseModel::Base);
  43. //GTSAM_VALUE_EXPORT(noiseModel::Isotropic);
  44. //GTSAM_VALUE_EXPORT(noiseModel::Gaussian);
  45. //GTSAM_VALUE_EXPORT(noiseModel::Diagonal);
  46. //GTSAM_VALUE_EXPORT(noiseModel::Unit);
  47. double chi2_red(const gtsam::NonlinearFactorGraph& graph, const gtsam::Values& config) {
  48. // Compute degrees of freedom (observations - variables)
  49. // In ocaml, +1 was added to the observations to account for the prior, but
  50. // the factor graph already includes a factor for the prior/equality constraint.
  51. // double dof = graph.size() - config.size();
  52. int graph_dim = 0;
  53. for(const boost::shared_ptr<gtsam::NonlinearFactor>& nlf: graph) {
  54. graph_dim += nlf->dim();
  55. }
  56. double dof = graph_dim - config.dim(); // kaess: changed to dim
  57. return 2. * graph.error(config) / dof; // kaess: added factor 2, graph.error returns half of actual error
  58. }
  59. int main(int argc, char *argv[]) {
  60. cout << "Loading data..." << endl;
  61. gttic_(Find_datafile);
  62. //string datasetFile = findExampleDataFile("w10000-odom");
  63. string datasetFile = findExampleDataFile("victoria_park");
  64. std::pair<NonlinearFactorGraph::shared_ptr, Values::shared_ptr> data =
  65. load2D(datasetFile);
  66. gttoc_(Find_datafile);
  67. NonlinearFactorGraph measurements = *data.first;
  68. Values initial = *data.second;
  69. cout << "Playing forward time steps..." << endl;
  70. ISAM2 isam2;
  71. size_t nextMeasurement = 0;
  72. for(size_t step=1; nextMeasurement < measurements.size(); ++step) {
  73. Values newVariables;
  74. NonlinearFactorGraph newFactors;
  75. // Collect measurements and new variables for the current step
  76. gttic_(Collect_measurements);
  77. if(step == 1) {
  78. // cout << "Initializing " << 0 << endl;
  79. newVariables.insert(0, Pose());
  80. // Add prior
  81. newFactors.addPrior(0, Pose(), noiseModel::Unit::Create(3));
  82. }
  83. while(nextMeasurement < measurements.size()) {
  84. NonlinearFactor::shared_ptr measurementf = measurements[nextMeasurement];
  85. if(BetweenFactor<Pose>::shared_ptr measurement =
  86. boost::dynamic_pointer_cast<BetweenFactor<Pose> >(measurementf))
  87. {
  88. // Stop collecting measurements that are for future steps
  89. if(measurement->key1() > step || measurement->key2() > step)
  90. break;
  91. // Require that one of the nodes is the current one
  92. if(measurement->key1() != step && measurement->key2() != step)
  93. throw runtime_error("Problem in data file, out-of-sequence measurements");
  94. // Add a new factor
  95. newFactors.push_back(measurement);
  96. // Initialize the new variable
  97. if(measurement->key1() == step && measurement->key2() == step-1) {
  98. if(step == 1)
  99. newVariables.insert(step, measurement->measured().inverse());
  100. else {
  101. Pose prevPose = isam2.calculateEstimate<Pose>(step-1);
  102. newVariables.insert(step, prevPose * measurement->measured().inverse());
  103. }
  104. // cout << "Initializing " << step << endl;
  105. } else if(measurement->key2() == step && measurement->key1() == step-1) {
  106. if(step == 1)
  107. newVariables.insert(step, measurement->measured());
  108. else {
  109. Pose prevPose = isam2.calculateEstimate<Pose>(step-1);
  110. newVariables.insert(step, prevPose * measurement->measured());
  111. }
  112. // cout << "Initializing " << step << endl;
  113. }
  114. }
  115. else if(BearingRangeFactor<Pose, Point2>::shared_ptr measurement =
  116. boost::dynamic_pointer_cast<BearingRangeFactor<Pose, Point2> >(measurementf))
  117. {
  118. Key poseKey = measurement->keys()[0], lmKey = measurement->keys()[1];
  119. // Stop collecting measurements that are for future steps
  120. if(poseKey > step)
  121. throw runtime_error("Problem in data file, out-of-sequence measurements");
  122. // Add new factor
  123. newFactors.push_back(measurement);
  124. // Initialize new landmark
  125. if(!isam2.getLinearizationPoint().exists(lmKey))
  126. {
  127. Pose pose = isam2.calculateEstimate<Pose>(poseKey);
  128. Rot2 measuredBearing = measurement->measured().bearing();
  129. double measuredRange = measurement->measured().range();
  130. newVariables.insert(lmKey,
  131. pose.transformFrom(measuredBearing.rotate(Point2(measuredRange, 0.0))));
  132. }
  133. }
  134. else
  135. {
  136. throw std::runtime_error("Unknown factor type read from data file");
  137. }
  138. ++ nextMeasurement;
  139. }
  140. gttoc_(Collect_measurements);
  141. // Update iSAM2
  142. gttic_(Update_ISAM2);
  143. isam2.update(newFactors, newVariables);
  144. gttoc_(Update_ISAM2);
  145. if(step % 100 == 0) {
  146. gttic_(chi2);
  147. Values estimate(isam2.calculateEstimate());
  148. double chi2 = chi2_red(isam2.getFactorsUnsafe(), estimate);
  149. cout << "chi2 = " << chi2 << endl;
  150. gttoc_(chi2);
  151. }
  152. tictoc_finishedIteration_();
  153. if(step % 1000 == 0) {
  154. cout << "Step " << step << endl;
  155. tictoc_print_();
  156. }
  157. }
  158. //try {
  159. // {
  160. // std::ofstream writerStream("incremental_init", ios::binary);
  161. // boost::archive::binary_oarchive writer(writerStream);
  162. // writer << isam2.calculateEstimate();
  163. // writerStream.close();
  164. // }
  165. // {
  166. // std::ofstream writerStream("incremental_graph", ios::binary);
  167. // boost::archive::binary_oarchive writer(writerStream);
  168. // writer << isam2.getFactorsUnsafe();
  169. // writerStream.close();
  170. // }
  171. //} catch(std::exception& e) {
  172. // cout << e.what() << endl;
  173. //}
  174. NonlinearFactorGraph graph;
  175. Values values;
  176. //{
  177. // std::ifstream readerStream("incremental_init", ios::binary);
  178. // boost::archive::binary_iarchive reader(readerStream);
  179. // reader >> values;
  180. //}
  181. //{
  182. // std::ifstream readerStream("incremental_graph", ios::binary);
  183. // boost::archive::binary_iarchive reader(readerStream);
  184. // reader >> graph;
  185. //}
  186. graph = isam2.getFactorsUnsafe();
  187. values = isam2.calculateEstimate();
  188. // Compute marginals
  189. try {
  190. Marginals marginals(graph, values);
  191. int i=0;
  192. for (Key key1: boost::adaptors::reverse(values.keys())) {
  193. int j=0;
  194. for (Key key2: boost::adaptors::reverse(values.keys())) {
  195. if(i != j) {
  196. gttic_(jointMarginalInformation);
  197. KeyVector keys(2);
  198. keys[0] = key1;
  199. keys[1] = key2;
  200. JointMarginal info = marginals.jointMarginalInformation(keys);
  201. gttoc_(jointMarginalInformation);
  202. tictoc_finishedIteration_();
  203. }
  204. ++j;
  205. if(j >= 50)
  206. break;
  207. }
  208. ++i;
  209. if(i >= 50)
  210. break;
  211. }
  212. tictoc_print_();
  213. for(Key key: values.keys()) {
  214. gttic_(marginalInformation);
  215. Matrix info = marginals.marginalInformation(key);
  216. gttoc_(marginalInformation);
  217. tictoc_finishedIteration_();
  218. ++i;
  219. }
  220. } catch(std::exception& e) {
  221. cout << e.what() << endl;
  222. }
  223. tictoc_print_();
  224. return 0;
  225. }