TimeOfArrivalExample.cpp 5.0 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159
  1. /* ----------------------------------------------------------------------------
  2. * GTSAM Copyright 2010-2020, 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 TimeOfArrivalExample.cpp
  10. * @brief Track a moving object "Time of Arrival" measurements at 4
  11. * microphones.
  12. * @author Frank Dellaert
  13. * @author Jay Chakravarty
  14. * @date March 2020
  15. */
  16. #include <gtsam/nonlinear/LevenbergMarquardtOptimizer.h>
  17. #include <gtsam/nonlinear/NonlinearFactorGraph.h>
  18. #include <gtsam/nonlinear/expressions.h>
  19. #include <gtsam_unstable/geometry/Event.h>
  20. #include <gtsam_unstable/slam/TOAFactor.h>
  21. #include <boost/format.hpp>
  22. #include <vector>
  23. using namespace std;
  24. using namespace gtsam;
  25. // units
  26. static const double ms = 1e-3;
  27. static const double cm = 1e-2;
  28. // Instantiate functor with speed of sound value
  29. static const TimeOfArrival kTimeOfArrival(330);
  30. /* ************************************************************************* */
  31. // Create microphones
  32. vector<Point3> defineMicrophones() {
  33. const double height = 0.5;
  34. vector<Point3> microphones;
  35. microphones.push_back(Point3(0, 0, height));
  36. microphones.push_back(Point3(403 * cm, 0, height));
  37. microphones.push_back(Point3(403 * cm, 403 * cm, height));
  38. microphones.push_back(Point3(0, 403 * cm, 2 * height));
  39. return microphones;
  40. }
  41. /* ************************************************************************* */
  42. // Create ground truth trajectory
  43. vector<Event> createTrajectory(size_t n) {
  44. vector<Event> trajectory;
  45. double timeOfEvent = 10;
  46. // simulate emitting a sound every second while moving on straight line
  47. for (size_t key = 0; key < n; key++) {
  48. trajectory.push_back(
  49. Event(timeOfEvent, 245 * cm + key * 1.0, 201.5 * cm, (212 - 45) * cm));
  50. timeOfEvent += 1;
  51. }
  52. return trajectory;
  53. }
  54. /* ************************************************************************* */
  55. // Simulate time-of-arrival measurements for a single event
  56. vector<double> simulateTOA(const vector<Point3>& microphones,
  57. const Event& event) {
  58. size_t K = microphones.size();
  59. vector<double> simulatedTOA(K);
  60. for (size_t i = 0; i < K; i++) {
  61. simulatedTOA[i] = kTimeOfArrival(event, microphones[i]);
  62. }
  63. return simulatedTOA;
  64. }
  65. /* ************************************************************************* */
  66. // Simulate time-of-arrival measurements for an entire trajectory
  67. vector<vector<double>> simulateTOA(const vector<Point3>& microphones,
  68. const vector<Event>& trajectory) {
  69. vector<vector<double>> simulatedTOA;
  70. for (auto event : trajectory) {
  71. simulatedTOA.push_back(simulateTOA(microphones, event));
  72. }
  73. return simulatedTOA;
  74. }
  75. /* ************************************************************************* */
  76. // create factor graph
  77. NonlinearFactorGraph createGraph(const vector<Point3>& microphones,
  78. const vector<vector<double>>& simulatedTOA) {
  79. NonlinearFactorGraph graph;
  80. // Create a noise model for the TOA error
  81. auto model = noiseModel::Isotropic::Sigma(1, 0.5 * ms);
  82. size_t K = microphones.size();
  83. size_t key = 0;
  84. for (auto toa : simulatedTOA) {
  85. for (size_t i = 0; i < K; i++) {
  86. graph.emplace_shared<TOAFactor>(key, microphones[i], toa[i], model);
  87. }
  88. key += 1;
  89. }
  90. return graph;
  91. }
  92. /* ************************************************************************* */
  93. // create initial estimate for n events
  94. Values createInitialEstimate(size_t n) {
  95. Values initial;
  96. Event zero;
  97. for (size_t key = 0; key < n; key++) {
  98. initial.insert(key, zero);
  99. }
  100. return initial;
  101. }
  102. /* ************************************************************************* */
  103. int main(int argc, char* argv[]) {
  104. // Create microphones
  105. auto microphones = defineMicrophones();
  106. size_t K = microphones.size();
  107. for (size_t i = 0; i < K; i++) {
  108. cout << "mic" << i << " = " << microphones[i] << endl;
  109. }
  110. // Create a ground truth trajectory
  111. const size_t n = 5;
  112. auto groundTruth = createTrajectory(n);
  113. // Simulate time-of-arrival measurements
  114. auto simulatedTOA = simulateTOA(microphones, groundTruth);
  115. for (size_t key = 0; key < n; key++) {
  116. for (size_t i = 0; i < K; i++) {
  117. cout << "z_" << key << i << " = " << simulatedTOA[key][i] / ms << " ms"
  118. << endl;
  119. }
  120. }
  121. // Create factor graph
  122. auto graph = createGraph(microphones, simulatedTOA);
  123. // Create initial estimate
  124. auto initialEstimate = createInitialEstimate(n);
  125. initialEstimate.print("Initial Estimate:\n");
  126. // Optimize using Levenberg-Marquardt optimization.
  127. LevenbergMarquardtParams params;
  128. params.setAbsoluteErrorTol(1e-10);
  129. params.setVerbosityLM("SUMMARY");
  130. LevenbergMarquardtOptimizer optimizer(graph, initialEstimate, params);
  131. Values result = optimizer.optimize();
  132. result.print("Final Result:\n");
  133. }
  134. /* ************************************************************************* */