| 
									
										
										
										
											2014-12-10 21:24:10 +08:00
										 |  |  | /* ----------------------------------------------------------------------------
 | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |  * GTSAM Copyright 2010, Georgia Tech Research Corporation,  | 
					
						
							|  |  |  |  * Atlanta, Georgia 30332-0415 | 
					
						
							|  |  |  |  * All Rights Reserved | 
					
						
							|  |  |  |  * Authors: Frank Dellaert, et al. (see THANKS for the full author list) | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |  * See LICENSE for the license information | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |  * -------------------------------------------------------------------------- */ | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | /**
 | 
					
						
							|  |  |  |  *  @file  testTOAFactor.cpp | 
					
						
							|  |  |  |  *  @brief Unit tests for "Time of Arrival" factor | 
					
						
							|  |  |  |  *  @author Frank Dellaert | 
					
						
							|  |  |  |  *  @author Jay Chakravarty | 
					
						
							|  |  |  |  *  @date December 2014 | 
					
						
							|  |  |  |  */ | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2014-12-11 20:19:37 +08:00
										 |  |  | #include <gtsam_unstable/geometry/Event.h>
 | 
					
						
							| 
									
										
										
										
											2014-12-29 02:10:41 +08:00
										 |  |  | #include <gtsam/nonlinear/ExpressionFactorGraph.h>
 | 
					
						
							| 
									
										
										
										
											2014-12-11 02:14:18 +08:00
										 |  |  | #include <gtsam/nonlinear/LevenbergMarquardtOptimizer.h>
 | 
					
						
							| 
									
										
										
										
											2014-12-10 21:24:10 +08:00
										 |  |  | #include <gtsam/base/numericalDerivative.h>
 | 
					
						
							| 
									
										
										
										
											2014-12-11 05:50:41 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2014-12-10 21:24:10 +08:00
										 |  |  | #include <CppUnitLite/TestHarness.h>
 | 
					
						
							| 
									
										
										
										
											2014-12-11 05:50:41 +08:00
										 |  |  | #include <boost/format.hpp>
 | 
					
						
							| 
									
										
										
										
											2014-12-10 21:24:10 +08:00
										 |  |  | #include <boost/bind.hpp>
 | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | using namespace std; | 
					
						
							|  |  |  | using namespace gtsam; | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2014-12-12 14:31:33 +08:00
										 |  |  | // typedefs
 | 
					
						
							|  |  |  | typedef Eigen::Matrix<double, 1, 1> Vector1; | 
					
						
							|  |  |  | typedef Expression<double> Double_; | 
					
						
							|  |  |  | typedef Expression<Point3> Point3_; | 
					
						
							|  |  |  | typedef Expression<Event> Event_; | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | // units
 | 
					
						
							| 
									
										
										
										
											2014-12-11 02:00:52 +08:00
										 |  |  | static const double ms = 1e-3; | 
					
						
							| 
									
										
										
										
											2014-12-10 23:02:13 +08:00
										 |  |  | static const double cm = 1e-2; | 
					
						
							| 
									
										
										
										
											2014-12-12 14:31:33 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  | // Create a noise model for the TOA error
 | 
					
						
							| 
									
										
										
										
											2014-12-11 04:12:38 +08:00
										 |  |  | static SharedNoiseModel model(noiseModel::Isotropic::Sigma(1, 0.5 * ms)); | 
					
						
							| 
									
										
										
										
											2014-12-10 21:24:10 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2014-12-11 00:58:35 +08:00
										 |  |  | static const double timeOfEvent = 25; | 
					
						
							|  |  |  | static const Event exampleEvent(timeOfEvent, 1, 0, 0); | 
					
						
							|  |  |  | static const Point3 microphoneAt0; | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2014-12-10 23:02:13 +08:00
										 |  |  | //*****************************************************************************
 | 
					
						
							| 
									
										
										
										
											2014-12-11 20:19:37 +08:00
										 |  |  | TEST( TOAFactor, NewWay ) { | 
					
						
							| 
									
										
										
										
											2014-12-10 22:43:31 +08:00
										 |  |  |   Key key = 12; | 
					
						
							| 
									
										
										
										
											2014-12-12 14:31:33 +08:00
										 |  |  |   Event_ eventExpression(key); | 
					
						
							|  |  |  |   Point3_ microphoneConstant(microphoneAt0); // constant expression
 | 
					
						
							|  |  |  |   double measurement = 7; | 
					
						
							|  |  |  |   Double_ expression(&Event::toa, eventExpression, microphoneConstant); | 
					
						
							|  |  |  |   ExpressionFactor<double> factor(model, measurement, expression); | 
					
						
							| 
									
										
										
										
											2014-12-10 22:43:31 +08:00
										 |  |  | } | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | //*****************************************************************************
 | 
					
						
							|  |  |  | TEST( TOAFactor, WholeEnchilada ) { | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2014-12-11 02:00:52 +08:00
										 |  |  |   static const bool verbose = false; | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2014-12-10 22:43:31 +08:00
										 |  |  |   // Create microphones
 | 
					
						
							| 
									
										
										
										
											2014-12-11 02:00:52 +08:00
										 |  |  |   const double height = 0.5; | 
					
						
							| 
									
										
										
										
											2014-12-10 22:43:31 +08:00
										 |  |  |   vector<Point3> microphones; | 
					
						
							| 
									
										
										
										
											2014-12-11 02:00:52 +08:00
										 |  |  |   microphones.push_back(Point3(0, 0, height)); | 
					
						
							|  |  |  |   microphones.push_back(Point3(403 * cm, 0, height)); | 
					
						
							|  |  |  |   microphones.push_back(Point3(403 * cm, 403 * cm, height)); | 
					
						
							| 
									
										
										
										
											2014-12-12 14:31:33 +08:00
										 |  |  |   microphones.push_back(Point3(0, 403 * cm, 2 * height)); | 
					
						
							| 
									
										
										
										
											2014-12-10 22:43:31 +08:00
										 |  |  |   EXPECT_LONGS_EQUAL(4, microphones.size()); | 
					
						
							| 
									
										
										
										
											2014-12-11 20:45:15 +08:00
										 |  |  | //  microphones.push_back(Point3(200 * cm, 200 * cm, height));
 | 
					
						
							| 
									
										
										
										
											2014-12-10 22:43:31 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  |   // Create a ground truth point
 | 
					
						
							|  |  |  |   const double timeOfEvent = 0; | 
					
						
							| 
									
										
										
										
											2014-12-11 02:00:52 +08:00
										 |  |  |   Event groundTruthEvent(timeOfEvent, 245 * cm, 201.5 * cm, (212 - 45) * cm); | 
					
						
							| 
									
										
										
										
											2014-12-10 22:43:31 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2014-12-12 14:31:33 +08:00
										 |  |  |   // Simulate simulatedTOA
 | 
					
						
							| 
									
										
										
										
											2014-12-11 02:00:52 +08:00
										 |  |  |   size_t K = microphones.size(); | 
					
						
							| 
									
										
										
										
											2014-12-12 14:31:33 +08:00
										 |  |  |   vector<double> simulatedTOA(K); | 
					
						
							| 
									
										
										
										
											2014-12-11 02:00:52 +08:00
										 |  |  |   for (size_t i = 0; i < K; i++) { | 
					
						
							| 
									
										
										
										
											2014-12-12 14:31:33 +08:00
										 |  |  |     simulatedTOA[i] = groundTruthEvent.toa(microphones[i]); | 
					
						
							| 
									
										
										
										
											2014-12-11 02:00:52 +08:00
										 |  |  |     if (verbose) { | 
					
						
							|  |  |  |       cout << "mic" << i << " = " << microphones[i] << endl; | 
					
						
							| 
									
										
										
										
											2014-12-12 14:31:33 +08:00
										 |  |  |       cout << "z" << i << " = " << simulatedTOA[i] / ms << endl; | 
					
						
							| 
									
										
										
										
											2014-12-11 02:00:52 +08:00
										 |  |  |     } | 
					
						
							|  |  |  |   } | 
					
						
							| 
									
										
										
										
											2014-12-10 22:43:31 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  |   // Now, estimate using non-linear optimization
 | 
					
						
							| 
									
										
										
										
											2014-12-12 14:31:33 +08:00
										 |  |  |   ExpressionFactorGraph graph; | 
					
						
							| 
									
										
										
										
											2014-12-10 22:43:31 +08:00
										 |  |  |   Key key = 12; | 
					
						
							| 
									
										
										
										
											2014-12-12 14:31:33 +08:00
										 |  |  |   Event_ eventExpression(key); | 
					
						
							| 
									
										
										
										
											2014-12-11 02:00:52 +08:00
										 |  |  |   for (size_t i = 0; i < K; i++) { | 
					
						
							| 
									
										
										
										
											2014-12-12 14:31:33 +08:00
										 |  |  |     Point3_ microphone_i(microphones[i]); // constant expression
 | 
					
						
							|  |  |  |     Double_ predictTOA(&Event::toa, eventExpression, microphone_i); | 
					
						
							|  |  |  |     graph.addExpressionFactor(predictTOA, simulatedTOA[i], model); | 
					
						
							| 
									
										
										
										
											2014-12-10 22:43:31 +08:00
										 |  |  |   } | 
					
						
							| 
									
										
										
										
											2014-12-10 23:02:13 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  |   /// Print the graph
 | 
					
						
							| 
									
										
										
										
											2014-12-11 02:00:52 +08:00
										 |  |  |   if (verbose) | 
					
						
							|  |  |  |     GTSAM_PRINT(graph); | 
					
						
							| 
									
										
										
										
											2014-12-10 23:02:13 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  |   // Create initial estimate
 | 
					
						
							|  |  |  |   Values initialEstimate; | 
					
						
							| 
									
										
										
										
											2014-12-11 02:00:52 +08:00
										 |  |  |   //Event estimatedEvent(timeOfEvent -10, 200 * cm, 150 * cm, 350 * cm);
 | 
					
						
							| 
									
										
										
										
											2014-12-11 04:12:38 +08:00
										 |  |  |   Vector4 delta; | 
					
						
							|  |  |  |   delta << 0.1, 0.1, -0.1, 0.1; | 
					
						
							| 
									
										
										
										
											2014-12-11 02:00:52 +08:00
										 |  |  |   Event estimatedEvent = groundTruthEvent.retract(delta); | 
					
						
							| 
									
										
										
										
											2014-12-10 23:02:13 +08:00
										 |  |  |   initialEstimate.insert(key, estimatedEvent); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   // Print
 | 
					
						
							| 
									
										
										
										
											2014-12-11 02:00:52 +08:00
										 |  |  |   if (verbose) | 
					
						
							|  |  |  |     initialEstimate.print("Initial Estimate:\n"); | 
					
						
							| 
									
										
										
										
											2014-12-10 23:02:13 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  |   // Optimize using Levenberg-Marquardt optimization.
 | 
					
						
							|  |  |  |   LevenbergMarquardtParams params; | 
					
						
							| 
									
										
										
										
											2014-12-11 00:58:35 +08:00
										 |  |  |   params.setAbsoluteErrorTol(1e-10); | 
					
						
							| 
									
										
										
										
											2014-12-11 02:00:52 +08:00
										 |  |  |   if (verbose) | 
					
						
							|  |  |  |     params.setVerbosity("ERROR"); | 
					
						
							|  |  |  |   LevenbergMarquardtOptimizer optimizer(graph, initialEstimate, params); | 
					
						
							| 
									
										
										
										
											2014-12-10 23:02:13 +08:00
										 |  |  |   Values result = optimizer.optimize(); | 
					
						
							| 
									
										
										
										
											2014-12-11 02:00:52 +08:00
										 |  |  |   if (verbose) | 
					
						
							|  |  |  |     result.print("Final Result:\n"); | 
					
						
							| 
									
										
										
										
											2014-12-11 00:58:35 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  |   EXPECT(assert_equal(groundTruthEvent, result.at<Event>(key), 1e-6)); | 
					
						
							| 
									
										
										
										
											2014-12-10 22:43:31 +08:00
										 |  |  | } | 
					
						
							| 
									
										
										
										
											2014-12-10 21:24:10 +08:00
										 |  |  | //*****************************************************************************
 | 
					
						
							|  |  |  | int main() { | 
					
						
							|  |  |  |   TestResult tr; | 
					
						
							|  |  |  |   return TestRegistry::runAllTests(tr); | 
					
						
							|  |  |  | } | 
					
						
							|  |  |  | //*****************************************************************************
 | 
					
						
							|  |  |  | 
 |