| 
									
										
										
										
											2012-08-03 03:27:36 +08:00
										 |  |  | /*
 | 
					
						
							|  |  |  |  * testInvDepthFactor.cpp | 
					
						
							|  |  |  |  * | 
					
						
							|  |  |  |  *  Created on: Apr 13, 2012 | 
					
						
							|  |  |  |  *      Author: cbeall3 | 
					
						
							|  |  |  |  */ | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | #include <CppUnitLite/TestHarness.h>
 | 
					
						
							| 
									
										
										
										
											2012-08-03 04:47:16 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2020-02-22 08:42:55 +08:00
										 |  |  | #include <gtsam/geometry/PinholeCamera.h>
 | 
					
						
							| 
									
										
										
										
											2012-08-03 03:27:36 +08:00
										 |  |  | #include <gtsam/nonlinear/NonlinearEquality.h>
 | 
					
						
							|  |  |  | #include <gtsam/nonlinear/NonlinearFactorGraph.h>
 | 
					
						
							|  |  |  | #include <gtsam/nonlinear/LevenbergMarquardtOptimizer.h>
 | 
					
						
							| 
									
										
										
										
											2013-08-19 23:32:16 +08:00
										 |  |  | #include <gtsam/inference/Symbol.h>
 | 
					
						
							| 
									
										
										
										
											2012-08-03 03:27:36 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2012-08-03 04:47:16 +08:00
										 |  |  | #include <gtsam_unstable/slam/InvDepthFactor3.h>
 | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2012-08-03 03:27:36 +08:00
										 |  |  | using namespace std; | 
					
						
							|  |  |  | using namespace gtsam; | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | static Cal3_S2::shared_ptr K(new Cal3_S2(1500, 1200, 0, 640, 480)); | 
					
						
							| 
									
										
										
										
											2012-08-03 04:47:16 +08:00
										 |  |  | static SharedNoiseModel sigma(noiseModel::Unit::Create(2)); | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2012-11-30 02:20:39 +08:00
										 |  |  | // camera pose at (0,0,1) looking straight along the x-axis.
 | 
					
						
							| 
									
										
										
										
											2016-01-27 15:09:58 +08:00
										 |  |  | Pose3 level_pose = Pose3(Rot3::Ypr(-M_PI/2, 0., -M_PI/2), gtsam::Point3(0,0,1)); | 
					
						
							| 
									
										
										
										
											2020-02-22 08:42:55 +08:00
										 |  |  | PinholeCamera<Cal3_S2> level_camera(level_pose, *K); | 
					
						
							| 
									
										
										
										
											2012-08-03 03:27:36 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2014-11-03 20:32:58 +08:00
										 |  |  | typedef InvDepthFactor3<Pose3, Vector5, double> InverseDepthFactor; | 
					
						
							| 
									
										
										
										
											2012-08-03 03:27:36 +08:00
										 |  |  | typedef NonlinearEquality<Pose3> PoseConstraint; | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | /* ************************************************************************* */ | 
					
						
							|  |  |  | TEST( InvDepthFactor, optimize) { | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2012-11-30 02:20:39 +08:00
										 |  |  |   // landmark 5 meters infront of camera (camera center at (0,0,1))
 | 
					
						
							| 
									
										
										
										
											2012-08-03 03:27:36 +08:00
										 |  |  |   Point3 landmark(5, 0, 1); | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2012-11-30 02:20:39 +08:00
										 |  |  |   // get expected projection using pinhole camera
 | 
					
						
							| 
									
										
										
										
											2012-08-03 03:27:36 +08:00
										 |  |  |   Point2 expected_uv = level_camera.project(landmark); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   InvDepthCamera3<Cal3_S2> inv_camera(level_pose, K); | 
					
						
							| 
									
										
										
										
											2014-11-23 08:35:27 +08:00
										 |  |  |   Vector5 inv_landmark((Vector(5) << 0., 0., 1., 0., 0.).finished()); | 
					
						
							| 
									
										
										
										
											2012-11-30 02:20:39 +08:00
										 |  |  |   // initialize inverse depth with "incorrect" depth of 1/4
 | 
					
						
							|  |  |  |   // in reality this is 1/5, but initial depth is guessed
 | 
					
						
							| 
									
										
										
										
											2014-11-03 20:32:58 +08:00
										 |  |  |   double inv_depth(1./4); | 
					
						
							| 
									
										
										
										
											2012-08-03 03:27:36 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  |   gtsam::NonlinearFactorGraph graph; | 
					
						
							|  |  |  |   Values initial; | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   InverseDepthFactor::shared_ptr factor(new InverseDepthFactor(expected_uv, sigma, | 
					
						
							|  |  |  |       Symbol('x',1), Symbol('l',1), Symbol('d',1), K)); | 
					
						
							|  |  |  |   graph.push_back(factor); | 
					
						
							| 
									
										
										
										
											2013-08-12 02:41:08 +08:00
										 |  |  |   graph += PoseConstraint(Symbol('x',1),level_pose); | 
					
						
							| 
									
										
										
										
											2012-08-03 03:27:36 +08:00
										 |  |  |   initial.insert(Symbol('x',1), level_pose); | 
					
						
							|  |  |  |   initial.insert(Symbol('l',1), inv_landmark); | 
					
						
							|  |  |  |   initial.insert(Symbol('d',1), inv_depth); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   LevenbergMarquardtParams lmParams; | 
					
						
							|  |  |  |   Values result = LevenbergMarquardtOptimizer(graph, initial, lmParams).optimize(); | 
					
						
							| 
									
										
										
										
											2019-02-11 22:39:48 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2012-11-30 02:20:39 +08:00
										 |  |  |   // with a single factor the incorrect initialization of 1/4 should not move!
 | 
					
						
							| 
									
										
										
										
											2012-08-03 04:47:16 +08:00
										 |  |  |   EXPECT(assert_equal(initial, result, 1e-9)); | 
					
						
							| 
									
										
										
										
											2012-08-03 03:27:36 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  |   /// Add a second camera
 | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2012-11-30 02:20:39 +08:00
										 |  |  |   // add a camera 2 meters to the right
 | 
					
						
							| 
									
										
										
										
											2012-08-03 03:27:36 +08:00
										 |  |  |   Pose3 right_pose = level_pose * Pose3(Rot3(), Point3(2,0,0)); | 
					
						
							| 
									
										
										
										
											2020-02-22 08:42:55 +08:00
										 |  |  |   PinholeCamera<Cal3_S2> right_camera(right_pose, *K); | 
					
						
							| 
									
										
										
										
											2012-08-03 03:27:36 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2012-11-30 02:20:39 +08:00
										 |  |  |   // projection measurement of landmark into right camera
 | 
					
						
							|  |  |  |   // this measurement disagrees with the depth initialization
 | 
					
						
							|  |  |  |   // and will push it to 1/5
 | 
					
						
							|  |  |  |   Point2 right_uv = right_camera.project(landmark); | 
					
						
							| 
									
										
										
										
											2012-08-03 03:27:36 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  |   InverseDepthFactor::shared_ptr factor1(new InverseDepthFactor(right_uv, sigma, | 
					
						
							|  |  |  |       Symbol('x',2), Symbol('l',1),Symbol('d',1),K)); | 
					
						
							|  |  |  |   graph.push_back(factor1); | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2013-08-12 02:41:08 +08:00
										 |  |  |   graph += PoseConstraint(Symbol('x',2),right_pose); | 
					
						
							| 
									
										
										
										
											2012-08-03 03:27:36 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  |   initial.insert(Symbol('x',2), right_pose); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   Values result2 = LevenbergMarquardtOptimizer(graph, initial, lmParams).optimize(); | 
					
						
							| 
									
										
										
										
											2019-02-11 22:39:48 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2012-11-30 02:20:39 +08:00
										 |  |  |   Point3 result2_lmk = InvDepthCamera3<Cal3_S2>::invDepthTo3D( | 
					
						
							| 
									
										
										
										
											2014-11-03 20:32:58 +08:00
										 |  |  |       result2.at<Vector5>(Symbol('l',1)), | 
					
						
							|  |  |  |       result2.at<double>(Symbol('d',1))); | 
					
						
							| 
									
										
										
										
											2012-11-30 02:20:39 +08:00
										 |  |  |   EXPECT(assert_equal(landmark, result2_lmk, 1e-9)); | 
					
						
							| 
									
										
										
										
											2019-02-11 22:39:48 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2012-11-30 02:20:39 +08:00
										 |  |  |   // TODO: need to add priors to make this work with
 | 
					
						
							|  |  |  |   //    Values result2 = optimize<NonlinearFactorGraph>(graph, initial,
 | 
					
						
							|  |  |  |   //      NonlinearOptimizationParameters(),MULTIFRONTAL, GN);
 | 
					
						
							| 
									
										
										
										
											2012-08-03 03:27:36 +08:00
										 |  |  | } | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | /* ************************************************************************* */ | 
					
						
							|  |  |  | int main() { TestResult tr; return TestRegistry::runAllTests(tr);} | 
					
						
							|  |  |  | /* ************************************************************************* */ |