2012-06-15 01:33:58 +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
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								%
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								% @brief Basic VO Example with 3 landmarks and two cameras
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								% @author Chris Beall
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							
								
									
										
										
										
											2012-08-06 03:31:27 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								import gtsam.*
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							
								
									
										
										
										
											2012-06-15 01:33:58 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								%% Assumptions
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								%  - For simplicity this example is in the camera's coordinate frame
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								%  - X: right, Y: down, Z: forward
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								%  - Pose x1 is at the origin, Pose 2 is 1 meter forward (along Z-axis)
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								%  - x1 is fixed with a constraint, x2 is initialized with noisy values
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								%  - No noise on measurements
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								%% Create keys for variables
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								x1 = symbol('x',1); x2 = symbol('x',2); 
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								l1 = symbol('l',1); l2 = symbol('l',2); l3 = symbol('l',3);
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								%% Create graph container and add factors to it
							 | 
						
					
						
							
								
									
										
										
										
											2012-07-24 22:23:39 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								graph = NonlinearFactorGraph;
							 | 
						
					
						
							
								
									
										
										
										
											2012-06-15 01:33:58 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								%% add a constraint on the starting pose
							 | 
						
					
						
							
								
									
										
										
										
											2012-07-18 23:47:06 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								first_pose = Pose3();
							 | 
						
					
						
							
								
									
										
										
										
											2012-07-24 22:23:39 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								graph.add(NonlinearEqualityPose3(x1, first_pose));
							 | 
						
					
						
							
								
									
										
										
										
											2012-06-15 01:33:58 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								%% Create realistic calibration and measurement noise model
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								% format: fx fy skew cx cy baseline
							 | 
						
					
						
							
								
									
										
										
										
											2012-07-18 23:47:06 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								K = Cal3_S2Stereo(1000, 1000, 0, 320, 240, 0.2);
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								stereo_model = noiseModel.Diagonal.Sigmas([1.0; 1.0; 1.0]);
							 | 
						
					
						
							
								
									
										
										
										
											2012-06-15 01:33:58 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								%% Add measurements
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								% pose 1
							 | 
						
					
						
							
								
									
										
										
										
											2012-07-24 22:23:39 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								graph.add(GenericStereoFactor3D(StereoPoint2(520, 480, 440), stereo_model, x1, l1, K));
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								graph.add(GenericStereoFactor3D(StereoPoint2(120,  80, 440), stereo_model, x1, l2, K));
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								graph.add(GenericStereoFactor3D(StereoPoint2(320, 280, 140), stereo_model, x1, l3, K));
							 | 
						
					
						
							
								
									
										
										
										
											2012-06-15 01:33:58 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								%pose 2
							 | 
						
					
						
							
								
									
										
										
										
											2012-07-24 22:23:39 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								graph.add(GenericStereoFactor3D(StereoPoint2(570, 520, 490), stereo_model, x2, l1, K));
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								graph.add(GenericStereoFactor3D(StereoPoint2( 70,  20, 490), stereo_model, x2, l2, K));
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								graph.add(GenericStereoFactor3D(StereoPoint2(320, 270, 115), stereo_model, x2, l3, K));
							 | 
						
					
						
							
								
									
										
										
										
											2012-06-15 01:33:58 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								%% Create initial estimate for camera poses and landmarks
							 | 
						
					
						
							
								
									
										
										
										
											2012-07-24 22:23:39 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								initialEstimate = Values;
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								initialEstimate.insert(x1, first_pose);
							 | 
						
					
						
							
								
									
										
										
										
											2012-06-15 01:33:58 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								% noisy estimate for pose 2
							 | 
						
					
						
							
								
									
										
										
										
											2012-07-24 22:23:39 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								initialEstimate.insert(x2, Pose3(Rot3(), Point3(0.1,-.1,1.1)));
							 | 
						
					
						
							
								
									
										
										
										
											2012-07-28 03:02:11 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								expected_l1 = Point3( 1,  1, 5);
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								initialEstimate.insert(l1, expected_l1);
							 | 
						
					
						
							
								
									
										
										
										
											2012-07-24 22:23:39 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								initialEstimate.insert(l2, Point3(-1,  1, 5));
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								initialEstimate.insert(l3, Point3( 0,-.5, 5));
							 | 
						
					
						
							
								
									
										
										
										
											2012-06-15 01:33:58 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								%% optimize
							 | 
						
					
						
							
								
									
										
										
										
											2012-07-24 22:23:39 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								optimizer = LevenbergMarquardtOptimizer(graph, initialEstimate);
							 | 
						
					
						
							
								
									
										
										
										
											2012-07-28 03:02:11 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								result = optimizer.optimize();
							 | 
						
					
						
							
								
									
										
										
										
											2012-06-15 01:33:58 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							
								
									
										
										
										
											2012-07-28 03:02:11 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								%% check equality for the first pose and point
							 | 
						
					
						
							
								
									
										
										
										
											2014-11-14 06:59:51 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								pose_x1 = result.atPose3(x1);
							 | 
						
					
						
							
								
									
										
										
										
											2012-07-28 03:02:11 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								CHECK('pose_x1.equals(first_pose,1e-4)',pose_x1.equals(first_pose,1e-4));
							 | 
						
					
						
							
								
									
										
										
										
											2012-06-15 01:33:58 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							
								
									
										
										
										
											2014-11-14 06:59:51 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								point_l1 = result.atPoint3(l1);
							 | 
						
					
						
							
								
									
										
										
										
											2020-08-18 02:37:12 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								CHECK('point_1.equals(expected_l1,1e-4)',norm(point_l1 - expected_l1) < 1e-4);
							 |