| 
									
										
										
										
											2010-10-14 12:54:38 +08:00
										 |  |  | /* ----------------------------------------------------------------------------
 | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2019-02-11 22:39:48 +08:00
										 |  |  |  * GTSAM Copyright 2010, Georgia Tech Research Corporation, | 
					
						
							| 
									
										
										
										
											2010-10-14 12:54:38 +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 | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |  * -------------------------------------------------------------------------- */ | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2011-10-14 11:23:14 +08:00
										 |  |  | /**
 | 
					
						
							|  |  |  |  * @file testSimulated2DOriented.cpp | 
					
						
							|  |  |  |  * @date Jun 10, 2010 | 
					
						
							|  |  |  |  * @author nikai | 
					
						
							|  |  |  |  * @brief unit tests for simulated2DOriented | 
					
						
							| 
									
										
										
										
											2010-06-11 02:09:57 +08:00
										 |  |  |  */ | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2012-06-10 04:15:44 +08:00
										 |  |  | #include <tests/simulated2D.h>
 | 
					
						
							|  |  |  | #include <tests/simulated2DOriented.h>
 | 
					
						
							| 
									
										
										
										
											2013-08-19 23:32:16 +08:00
										 |  |  | #include <gtsam/inference/Symbol.h>
 | 
					
						
							| 
									
										
										
										
											2012-06-03 03:05:38 +08:00
										 |  |  | #include <gtsam/base/Testable.h>
 | 
					
						
							|  |  |  | #include <gtsam/base/numericalDerivative.h>
 | 
					
						
							| 
									
										
										
										
											2010-06-11 02:09:57 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  | using namespace std; | 
					
						
							| 
									
										
										
										
											2011-11-07 03:08:42 +08:00
										 |  |  | using namespace gtsam; | 
					
						
							| 
									
										
										
										
											2012-06-03 03:05:38 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  | #include <iostream>
 | 
					
						
							|  |  |  | #include <CppUnitLite/TestHarness.h>
 | 
					
						
							| 
									
										
										
										
											2010-06-11 02:09:57 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2012-06-03 00:18:40 +08:00
										 |  |  | // Convenience for named keys
 | 
					
						
							| 
									
										
										
										
											2012-06-03 03:28:21 +08:00
										 |  |  | using symbol_shorthand::X; | 
					
						
							|  |  |  | using symbol_shorthand::L; | 
					
						
							| 
									
										
										
										
											2012-06-03 00:18:40 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-06-11 02:09:57 +08:00
										 |  |  | /* ************************************************************************* */ | 
					
						
							|  |  |  | TEST( simulated2DOriented, Dprior ) | 
					
						
							|  |  |  | { | 
					
						
							|  |  |  |   Pose2 x(1,-9, 0.1); | 
					
						
							| 
									
										
										
										
											2011-11-07 03:08:42 +08:00
										 |  |  |   Matrix numerical = numericalDerivative11(simulated2DOriented::prior,x); | 
					
						
							| 
									
										
										
										
											2010-06-11 02:09:57 +08:00
										 |  |  |   Matrix computed; | 
					
						
							| 
									
										
										
										
											2011-11-07 03:08:42 +08:00
										 |  |  |   simulated2DOriented::prior(x,computed); | 
					
						
							| 
									
										
										
										
											2010-06-11 02:09:57 +08:00
										 |  |  |   CHECK(assert_equal(numerical,computed,1e-9)); | 
					
						
							|  |  |  | } | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | /* ************************************************************************* */ | 
					
						
							|  |  |  |   TEST( simulated2DOriented, DOdo ) | 
					
						
							|  |  |  | { | 
					
						
							|  |  |  |   Pose2 x1(1,-9,0.1),x2(-5,6,0.2); | 
					
						
							|  |  |  |   Matrix H1,H2; | 
					
						
							| 
									
										
										
										
											2011-11-07 03:08:42 +08:00
										 |  |  |   simulated2DOriented::odo(x1,x2,H1,H2); | 
					
						
							|  |  |  |   Matrix A1 = numericalDerivative21(simulated2DOriented::odo,x1,x2); | 
					
						
							| 
									
										
										
										
											2010-06-11 02:09:57 +08:00
										 |  |  |   CHECK(assert_equal(A1,H1,1e-9)); | 
					
						
							| 
									
										
										
										
											2011-11-07 03:08:42 +08:00
										 |  |  |   Matrix A2 = numericalDerivative22(simulated2DOriented::odo,x1,x2); | 
					
						
							| 
									
										
										
										
											2010-06-11 02:09:57 +08:00
										 |  |  |   CHECK(assert_equal(A2,H2,1e-9)); | 
					
						
							|  |  |  | } | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | /* ************************************************************************* */ | 
					
						
							|  |  |  | TEST( simulated2DOriented, constructor ) | 
					
						
							|  |  |  | { | 
					
						
							| 
									
										
										
										
											2012-10-02 22:40:07 +08:00
										 |  |  |   Pose2 measurement(0.2, 0.3, 0.1); | 
					
						
							| 
									
										
										
										
											2014-11-24 02:22:25 +08:00
										 |  |  |   SharedDiagonal model = noiseModel::Diagonal::Sigmas(Vector3(1., 1., 1.)); | 
					
						
							| 
									
										
										
										
											2012-10-02 22:40:07 +08:00
										 |  |  |   simulated2DOriented::Odometry factor(measurement, model, X(1), X(2)); | 
					
						
							| 
									
										
										
										
											2010-06-11 02:09:57 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2012-10-02 22:40:07 +08:00
										 |  |  |   simulated2DOriented::Values config; | 
					
						
							|  |  |  |   config.insert(X(1), Pose2(1., 0., 0.2)); | 
					
						
							|  |  |  |   config.insert(X(2), Pose2(2., 0., 0.1)); | 
					
						
							| 
									
										
										
										
											2023-01-18 06:05:12 +08:00
										 |  |  |   std::shared_ptr<GaussianFactor> lf = factor.linearize(config); | 
					
						
							| 
									
										
										
										
											2010-06-11 02:09:57 +08:00
										 |  |  | } | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | /* ************************************************************************* */ | 
					
						
							|  |  |  | int main() { TestResult tr; return TestRegistry::runAllTests(tr);} | 
					
						
							|  |  |  | /* ************************************************************************* */ |