| 
									
										
										
										
											2013-12-23 14:41:17 +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    CreateSFMExampleData.cpp | 
					
						
							|  |  |  |  * @brief   Create some example data that for inclusion in the data folder | 
					
						
							|  |  |  |  * @author  Frank Dellaert | 
					
						
							|  |  |  |  */ | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | #include <gtsam/geometry/CalibratedCamera.h>
 | 
					
						
							| 
									
										
										
										
											2021-06-14 11:30:04 +08:00
										 |  |  | #include <gtsam/slam/dataset.h>
 | 
					
						
							| 
									
										
										
										
											2013-12-25 05:47:30 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2013-12-23 14:41:17 +08:00
										 |  |  | using namespace std; | 
					
						
							|  |  |  | using namespace gtsam; | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2013-12-25 05:47:30 +08:00
										 |  |  | /* ************************************************************************* */ | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2021-06-21 11:47:10 +08:00
										 |  |  | void createExampleBALFile(const string& filename, const vector<Point3>& points, | 
					
						
							| 
									
										
										
										
											2021-06-14 11:30:04 +08:00
										 |  |  |                           const Pose3& pose1, const Pose3& pose2, | 
					
						
							|  |  |  |                           const Cal3Bundler& K = Cal3Bundler()) { | 
					
						
							| 
									
										
										
										
											2013-12-23 14:41:17 +08:00
										 |  |  |   // Class that will gather all data
 | 
					
						
							| 
									
										
										
										
											2020-03-07 06:59:09 +08:00
										 |  |  |   SfmData data; | 
					
						
							| 
									
										
										
										
											2021-06-14 09:30:00 +08:00
										 |  |  |   // Create two cameras and add them to data
 | 
					
						
							| 
									
										
										
										
											2020-03-07 06:59:09 +08:00
										 |  |  |   data.cameras.push_back(SfmCamera(pose1, K)); | 
					
						
							|  |  |  |   data.cameras.push_back(SfmCamera(pose2, K)); | 
					
						
							| 
									
										
										
										
											2013-12-23 14:41:17 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2021-06-21 11:47:10 +08:00
										 |  |  |   for (const Point3& p : points) { | 
					
						
							| 
									
										
										
										
											2013-12-23 14:41:17 +08:00
										 |  |  |     // Create the track
 | 
					
						
							| 
									
										
										
										
											2020-03-07 06:59:09 +08:00
										 |  |  |     SfmTrack track; | 
					
						
							| 
									
										
										
										
											2013-12-23 14:41:17 +08:00
										 |  |  |     track.p = p; | 
					
						
							|  |  |  |     track.r = 1; | 
					
						
							|  |  |  |     track.g = 1; | 
					
						
							|  |  |  |     track.b = 1; | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |     // Project points in both cameras
 | 
					
						
							|  |  |  |     for (size_t i = 0; i < 2; i++) | 
					
						
							| 
									
										
										
										
											2021-06-14 11:30:04 +08:00
										 |  |  |       track.measurements.push_back(make_pair(i, data.cameras[i].project(p))); | 
					
						
							| 
									
										
										
										
											2013-12-23 14:41:17 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  |     // Add track to data
 | 
					
						
							|  |  |  |     data.tracks.push_back(track); | 
					
						
							|  |  |  |   } | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2013-12-25 05:47:30 +08:00
										 |  |  |   writeBAL(filename, data); | 
					
						
							|  |  |  | } | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | /* ************************************************************************* */ | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | void create5PointExample1() { | 
					
						
							|  |  |  |   // Create two cameras poses
 | 
					
						
							| 
									
										
										
										
											2016-01-27 15:09:58 +08:00
										 |  |  |   Rot3 aRb = Rot3::Yaw(M_PI_2); | 
					
						
							| 
									
										
										
										
											2013-12-25 05:47:30 +08:00
										 |  |  |   Point3 aTb(0.1, 0, 0); | 
					
						
							|  |  |  |   Pose3 pose1, pose2(aRb, aTb); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   // Create test data, we need at least 5 points
 | 
					
						
							| 
									
										
										
										
											2021-06-21 13:26:19 +08:00
										 |  |  |   vector<Point3> points = { | 
					
						
							|  |  |  |       {0, 0, 1}, {-0.1, 0, 1}, {0.1, 0, 1}, {0, 0.5, 0.5}, {0, -0.5, 0.5}}; | 
					
						
							| 
									
										
										
										
											2013-12-25 05:47:30 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2013-12-23 14:41:17 +08:00
										 |  |  |   // Assumes example is run in ${GTSAM_TOP}/build/examples
 | 
					
						
							| 
									
										
										
										
											2021-06-14 09:30:00 +08:00
										 |  |  |   const string filename = "../../examples/Data/5pointExample1.txt"; | 
					
						
							| 
									
										
										
										
											2021-06-21 11:47:10 +08:00
										 |  |  |   createExampleBALFile(filename, points, pose1, pose2); | 
					
						
							| 
									
										
										
										
											2013-12-23 14:41:17 +08:00
										 |  |  | } | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2013-12-25 05:47:30 +08:00
										 |  |  | /* ************************************************************************* */ | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | void create5PointExample2() { | 
					
						
							|  |  |  |   // Create two cameras poses
 | 
					
						
							| 
									
										
										
										
											2016-01-27 15:09:58 +08:00
										 |  |  |   Rot3 aRb = Rot3::Yaw(M_PI_2); | 
					
						
							| 
									
										
										
										
											2013-12-25 05:47:30 +08:00
										 |  |  |   Point3 aTb(10, 0, 0); | 
					
						
							|  |  |  |   Pose3 pose1, pose2(aRb, aTb); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   // Create test data, we need at least 5 points
 | 
					
						
							| 
									
										
										
										
											2021-06-21 13:26:19 +08:00
										 |  |  |   vector<Point3> points = {{0, 0, 100},  {-10, 0, 100}, {10, 0, 100},  //
 | 
					
						
							|  |  |  |                            {0, 50, 50},  {0, -50, 50},  {-20, 0, 80},  //
 | 
					
						
							|  |  |  |                            {20, -50, 80}}; | 
					
						
							| 
									
										
										
										
											2013-12-25 05:47:30 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  |   // Assumes example is run in ${GTSAM_TOP}/build/examples
 | 
					
						
							| 
									
										
										
										
											2021-06-14 09:30:00 +08:00
										 |  |  |   const string filename = "../../examples/Data/5pointExample2.txt"; | 
					
						
							| 
									
										
										
										
											2013-12-25 05:47:30 +08:00
										 |  |  |   Cal3Bundler K(500, 0, 0); | 
					
						
							| 
									
										
										
										
											2021-06-21 11:47:10 +08:00
										 |  |  |   createExampleBALFile(filename, points, pose1, pose2, K); | 
					
						
							| 
									
										
										
										
											2013-12-25 05:47:30 +08:00
										 |  |  | } | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2021-06-09 04:14:56 +08:00
										 |  |  | /* ************************************************************************* */ | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | void create18PointExample1() { | 
					
						
							|  |  |  |   // Create two cameras poses
 | 
					
						
							|  |  |  |   Rot3 aRb = Rot3::Yaw(M_PI_2); | 
					
						
							|  |  |  |   Point3 aTb(0.1, 0, 0); | 
					
						
							|  |  |  |   Pose3 pose1, pose2(aRb, aTb); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   // Create test data, we need 15 points
 | 
					
						
							| 
									
										
										
										
											2021-06-21 13:26:19 +08:00
										 |  |  |   vector<Point3> points = { | 
					
						
							|  |  |  |       {0, 0, 1},         {-0.1, 0, 1},      {0.1, 0, 1},       //
 | 
					
						
							|  |  |  |       {0, 0.5, 0.5},     {0, -0.5, 0.5},    {-1, -0.5, 2},     //
 | 
					
						
							|  |  |  |       {-1, 0.5, 2},      {0.25, -0.5, 1.5}, {0.25, 0.5, 1.5},  //
 | 
					
						
							|  |  |  |       {-0.1, -0.5, 0.5}, {0.1, -0.5, 1},    {0.1, 0.5, 1},     //
 | 
					
						
							|  |  |  |       {-0.1, 0, 0.5},    {-0.1, 0.5, 0.5},  {0, 0, 0.5},       //
 | 
					
						
							|  |  |  |       {0.1, -0.5, 0.5},  {0.1, 0, 0.5},     {0.1, 0.5, 0.5}}; | 
					
						
							| 
									
										
										
										
											2021-06-09 04:14:56 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  |   // Assumes example is run in ${GTSAM_TOP}/build/examples
 | 
					
						
							| 
									
										
										
										
											2021-06-14 09:30:00 +08:00
										 |  |  |   const string filename = "../../examples/Data/18pointExample1.txt"; | 
					
						
							| 
									
										
										
										
											2021-06-21 11:47:10 +08:00
										 |  |  |   createExampleBALFile(filename, points, pose1, pose2); | 
					
						
							| 
									
										
										
										
											2021-06-09 04:14:56 +08:00
										 |  |  | } | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2013-12-23 14:41:17 +08:00
										 |  |  | int main(int argc, char* argv[]) { | 
					
						
							|  |  |  |   create5PointExample1(); | 
					
						
							| 
									
										
										
										
											2013-12-25 05:47:30 +08:00
										 |  |  |   create5PointExample2(); | 
					
						
							| 
									
										
										
										
											2021-06-09 04:14:56 +08:00
										 |  |  |   create18PointExample1(); | 
					
						
							| 
									
										
										
										
											2013-12-23 14:41:17 +08:00
										 |  |  |   return 0; | 
					
						
							|  |  |  | } | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | /* ************************************************************************* */ |