2 GTSAM Copyright 2010-2020, Georgia Tech Research Corporation, 
    3 Atlanta, Georgia 30332-0415 
    5 Authors: Frank Dellaert, et al. (see THANKS for the full author list) 
    7 See LICENSE for the license information 
    9 Track a moving object "Time of Arrival" measurements at 4 microphones. 
   10 Author: Frank Dellaert 
   14 from gtsam 
import (LevenbergMarquardtOptimizer, LevenbergMarquardtParams,
 
   15                    NonlinearFactorGraph, Point3, Values, noiseModel, Event, 
 
   17 from gtsam_unstable 
import TOAFactor
 
   28     """Create microphones.""" 
   31     microphones.append(
Point3(0, 0, height))
 
   32     microphones.append(
Point3(403 * CM, 0, height))
 
   33     microphones.append(
Point3(403 * CM, 403 * CM, height))
 
   34     microphones.append(
Point3(0, 403 * CM, 2 * height))
 
   39     """Create ground truth trajectory.""" 
   45             Event(timeOfEvent, 245 * CM + key * 1.0, 201.5 * CM, (212 - 45) * CM))
 
   52     """Simulate time-of-arrival measurements for a single event.""" 
   53     return [TIME_OF_ARRIVAL.measure(event, microphones[i])
 
   58     """Simulate time-of-arrival measurements for an entire trajectory.""" 
   60             for event 
in trajectory]
 
   64     """Create factor graph.""" 
   68     model = noiseModel.Isotropic.Sigma(1, 0.5 * MS)
 
   72     for toa 
in simulatedTOA:
 
   74             factor = TOAFactor(key, microphones[i], toa[i], model)
 
   75             graph.push_back(factor)
 
   82     """Create initial estimate for n events.""" 
   86         TOAFactor.InsertEvent(key, zero, initial)
 
   91     """Run example with 4 microphones and 5 events in a straight line.""" 
  101     for event 
in groundTruth:
 
  108             print(
"z_{}{} = {} ms".
format(key, i, simulatedTOA[key][i] / MS))
 
  116     print(initial_estimate)
 
  120     params.setAbsoluteErrorTol(1e-10)
 
  121     params.setVerbosityLM(
"SUMMARY")
 
  123     result = optimizer.optimize()
 
  124     print(
"Final Result:\n", result)
 
  127 if __name__ == 
'__main__':
 
  129     print(
"Example complete")