| 
									
										
										
										
											2014-12-10 21:24:10 +08:00
										 |  |  | /* ----------------------------------------------------------------------------
 | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2019-02-11 22:39:48 +08:00
										 |  |  |  * GTSAM Copyright 2010, Georgia Tech Research Corporation, | 
					
						
							| 
									
										
										
										
											2014-12-10 21:24:10 +08:00
										 |  |  |  * 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 | 
					
						
							|  |  |  |  */ | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | #include <gtsam/base/numericalDerivative.h>
 | 
					
						
							| 
									
										
										
										
											2020-03-18 02:34:11 +08:00
										 |  |  | #include <gtsam/nonlinear/LevenbergMarquardtOptimizer.h>
 | 
					
						
							|  |  |  | #include <gtsam/nonlinear/NonlinearFactorGraph.h>
 | 
					
						
							|  |  |  | #include <gtsam/nonlinear/expressions.h>
 | 
					
						
							|  |  |  | #include <gtsam_unstable/geometry/Event.h>
 | 
					
						
							|  |  |  | #include <gtsam_unstable/slam/TOAFactor.h>
 | 
					
						
							| 
									
										
										
										
											2014-12-11 05:50:41 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2014-12-10 21:24:10 +08:00
										 |  |  | #include <CppUnitLite/TestHarness.h>
 | 
					
						
							|  |  |  | #include <boost/bind.hpp>
 | 
					
						
							| 
									
										
										
										
											2020-03-18 02:34:11 +08:00
										 |  |  | #include <boost/format.hpp>
 | 
					
						
							| 
									
										
										
										
											2014-12-10 21:24:10 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  | using namespace std; | 
					
						
							|  |  |  | using namespace gtsam; | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2014-12-12 14:31:33 +08:00
										 |  |  | // typedefs
 | 
					
						
							|  |  |  | 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); | 
					
						
							| 
									
										
										
										
											2020-03-19 03:44:33 +08:00
										 |  |  | static const Point3 sensorAt0(0, 0, 0); | 
					
						
							| 
									
										
										
										
											2014-12-11 00:58:35 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2014-12-10 23:02:13 +08:00
										 |  |  | //*****************************************************************************
 | 
					
						
							| 
									
										
										
										
											2020-03-18 02:34:11 +08:00
										 |  |  | TEST(TOAFactor, NewWay) { | 
					
						
							| 
									
										
										
										
											2014-12-10 22:43:31 +08:00
										 |  |  |   Key key = 12; | 
					
						
							| 
									
										
										
										
											2014-12-12 14:31:33 +08:00
										 |  |  |   double measurement = 7; | 
					
						
							| 
									
										
										
										
											2020-03-19 03:44:33 +08:00
										 |  |  |   TOAFactor factor(key, sensorAt0, measurement, model); | 
					
						
							| 
									
										
										
										
											2014-12-10 22:43:31 +08:00
										 |  |  | } | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | //*****************************************************************************
 | 
					
						
							| 
									
										
										
										
											2020-03-18 02:34:11 +08:00
										 |  |  | TEST(TOAFactor, WholeEnchilada) { | 
					
						
							| 
									
										
										
										
											2020-03-19 03:44:33 +08:00
										 |  |  |   // Create sensors
 | 
					
						
							| 
									
										
										
										
											2014-12-11 02:00:52 +08:00
										 |  |  |   const double height = 0.5; | 
					
						
							| 
									
										
										
										
											2020-03-19 03:44:33 +08:00
										 |  |  |   vector<Point3> sensors; | 
					
						
							|  |  |  |   sensors.push_back(Point3(0, 0, height)); | 
					
						
							|  |  |  |   sensors.push_back(Point3(403 * cm, 0, height)); | 
					
						
							|  |  |  |   sensors.push_back(Point3(403 * cm, 403 * cm, height)); | 
					
						
							|  |  |  |   sensors.push_back(Point3(0, 403 * cm, 2 * height)); | 
					
						
							|  |  |  |   EXPECT_LONGS_EQUAL(4, sensors.size()); | 
					
						
							|  |  |  |   //  sensors.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
 | 
					
						
							| 
									
										
										
										
											2020-03-19 03:44:33 +08:00
										 |  |  |   size_t K = sensors.size(); | 
					
						
							| 
									
										
										
										
											2014-12-12 14:31:33 +08:00
										 |  |  |   vector<double> simulatedTOA(K); | 
					
						
							| 
									
										
										
										
											2020-03-18 02:34:11 +08:00
										 |  |  |   TimeOfArrival toa; | 
					
						
							| 
									
										
										
										
											2014-12-11 02:00:52 +08:00
										 |  |  |   for (size_t i = 0; i < K; i++) { | 
					
						
							| 
									
										
										
										
											2020-03-19 03:44:33 +08:00
										 |  |  |     simulatedTOA[i] = toa(groundTruthEvent, sensors[i]); | 
					
						
							| 
									
										
										
										
											2014-12-11 02:00:52 +08:00
										 |  |  |   } | 
					
						
							| 
									
										
										
										
											2014-12-10 22:43:31 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  |   // Now, estimate using non-linear optimization
 | 
					
						
							| 
									
										
										
										
											2020-03-18 02:34:11 +08:00
										 |  |  |   NonlinearFactorGraph graph; | 
					
						
							| 
									
										
										
										
											2014-12-10 22:43:31 +08:00
										 |  |  |   Key key = 12; | 
					
						
							| 
									
										
										
										
											2014-12-11 02:00:52 +08:00
										 |  |  |   for (size_t i = 0; i < K; i++) { | 
					
						
							| 
									
										
										
										
											2020-03-19 03:44:33 +08:00
										 |  |  |     graph.emplace_shared<TOAFactor>(key, sensors[i], simulatedTOA[i], model); | 
					
						
							| 
									
										
										
										
											2014-12-10 22:43:31 +08:00
										 |  |  |   } | 
					
						
							| 
									
										
										
										
											2014-12-10 23:02:13 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  |   // Create initial estimate
 | 
					
						
							|  |  |  |   Values initialEstimate; | 
					
						
							| 
									
										
										
										
											2020-03-18 02:34:11 +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); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   // 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
										 |  |  |   LevenbergMarquardtOptimizer optimizer(graph, initialEstimate, params); | 
					
						
							| 
									
										
										
										
											2014-12-10 23:02:13 +08:00
										 |  |  |   Values result = optimizer.optimize(); | 
					
						
							| 
									
										
										
										
											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); | 
					
						
							|  |  |  | } | 
					
						
							|  |  |  | //*****************************************************************************
 |