| 
									
										
										
										
											2013-08-30 12:23:45 +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 | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |  * -------------------------------------------------------------------------- */ | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | /**
 | 
					
						
							| 
									
										
										
										
											2020-02-22 08:42:55 +08:00
										 |  |  |  * @file    SFMdata.h | 
					
						
							| 
									
										
										
										
											2013-10-18 13:31:55 +08:00
										 |  |  |  * @brief   Simple example for the structure-from-motion problems | 
					
						
							| 
									
										
										
										
											2013-08-30 12:23:45 +08:00
										 |  |  |  * @author  Duy-Nguyen Ta | 
					
						
							|  |  |  |  */ | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | /**
 | 
					
						
							| 
									
										
										
										
											2024-10-25 02:43:40 +08:00
										 |  |  |  * A structure-from-motion example with landmarks, default arguments give: | 
					
						
							| 
									
										
										
										
											2013-08-30 12:23:45 +08:00
										 |  |  |  *  - The landmarks form a 10 meter cube | 
					
						
							|  |  |  |  *  - The robot rotates around the landmarks, always facing towards the cube | 
					
						
							| 
									
										
										
										
											2024-10-25 02:43:40 +08:00
										 |  |  |  * Passing function argument allows to specify an initial position, a pose | 
					
						
							|  |  |  |  * increment and step count. | 
					
						
							| 
									
										
										
										
											2013-08-30 12:23:45 +08:00
										 |  |  |  */ | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2022-02-22 00:59:01 +08:00
										 |  |  | #pragma once
 | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2024-10-25 02:43:40 +08:00
										 |  |  | // As this is a full 3D problem, we will use Pose3 variables to represent the
 | 
					
						
							|  |  |  | // camera positions and Point3 variables (x, y, z) to represent the landmark
 | 
					
						
							|  |  |  | // coordinates. Camera observations of landmarks (i.e. pixel coordinates) will
 | 
					
						
							|  |  |  | // be stored as Point2 (x, y).
 | 
					
						
							| 
									
										
										
										
											2013-08-30 12:23:45 +08:00
										 |  |  | #include <gtsam/geometry/Point3.h>
 | 
					
						
							| 
									
										
										
										
											2024-10-25 02:43:40 +08:00
										 |  |  | #include <gtsam/geometry/Pose3.h>
 | 
					
						
							| 
									
										
										
										
											2013-08-30 12:23:45 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2024-10-25 02:43:40 +08:00
										 |  |  | // We will also need a camera object to hold calibration information and perform
 | 
					
						
							|  |  |  | // projections.
 | 
					
						
							| 
									
										
										
										
											2020-02-22 08:42:55 +08:00
										 |  |  | #include <gtsam/geometry/Cal3_S2.h>
 | 
					
						
							| 
									
										
										
										
											2024-10-25 02:43:40 +08:00
										 |  |  | #include <gtsam/geometry/PinholeCamera.h>
 | 
					
						
							| 
									
										
										
										
											2013-08-30 12:23:45 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2024-10-25 02:43:40 +08:00
										 |  |  | namespace gtsam { | 
					
						
							| 
									
										
										
										
											2013-08-30 12:23:45 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2024-10-25 02:43:40 +08:00
										 |  |  | /// Create a set of ground-truth landmarks
 | 
					
						
							|  |  |  | std::vector<Point3> createPoints() { | 
					
						
							|  |  |  |   std::vector<Point3> points; | 
					
						
							|  |  |  |   points.push_back(Point3(10.0, 10.0, 10.0)); | 
					
						
							|  |  |  |   points.push_back(Point3(-10.0, 10.0, 10.0)); | 
					
						
							|  |  |  |   points.push_back(Point3(-10.0, -10.0, 10.0)); | 
					
						
							|  |  |  |   points.push_back(Point3(10.0, -10.0, 10.0)); | 
					
						
							|  |  |  |   points.push_back(Point3(10.0, 10.0, -10.0)); | 
					
						
							|  |  |  |   points.push_back(Point3(-10.0, 10.0, -10.0)); | 
					
						
							|  |  |  |   points.push_back(Point3(-10.0, -10.0, -10.0)); | 
					
						
							|  |  |  |   points.push_back(Point3(10.0, -10.0, -10.0)); | 
					
						
							| 
									
										
										
										
											2013-08-30 12:23:45 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  |   return points; | 
					
						
							|  |  |  | } | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2024-10-25 02:43:40 +08:00
										 |  |  | /**
 | 
					
						
							|  |  |  |  * Create a set of ground-truth poses | 
					
						
							| 
									
										
										
										
											2024-10-28 23:55:49 +08:00
										 |  |  |  * Default values give a circular trajectory, radius 30 at pi/4 intervals, | 
					
						
							| 
									
										
										
										
											2024-10-25 02:43:40 +08:00
										 |  |  |  * always facing the circle center | 
					
						
							|  |  |  |  */ | 
					
						
							|  |  |  | std::vector<Pose3> createPoses( | 
					
						
							|  |  |  |     const Pose3& init = Pose3(Rot3::Ypr(M_PI_2, 0, -M_PI_2), {30, 0, 0}), | 
					
						
							|  |  |  |     const Pose3& delta = Pose3(Rot3::Ypr(0, -M_PI_4, 0), | 
					
						
							|  |  |  |                                {sin(M_PI_4) * 30, 0, 30 * (1 - sin(M_PI_4))}), | 
					
						
							|  |  |  |     int steps = 8) { | 
					
						
							|  |  |  |   std::vector<Pose3> poses; | 
					
						
							|  |  |  |   poses.reserve(steps); | 
					
						
							| 
									
										
										
										
											2019-02-11 22:39:48 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2019-01-04 23:17:33 +08:00
										 |  |  |   poses.push_back(init); | 
					
						
							| 
									
										
										
										
											2024-10-25 02:43:40 +08:00
										 |  |  |   for (int i = 1; i < steps; ++i) { | 
					
						
							|  |  |  |     poses.push_back(poses[i - 1].compose(delta)); | 
					
						
							| 
									
										
										
										
											2013-08-30 12:23:45 +08:00
										 |  |  |   } | 
					
						
							| 
									
										
										
										
											2019-02-11 22:39:48 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2013-08-30 12:23:45 +08:00
										 |  |  |   return poses; | 
					
						
							| 
									
										
										
										
											2022-02-22 00:59:26 +08:00
										 |  |  | } | 
					
						
							| 
									
										
										
										
											2024-10-25 02:43:40 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  | /**
 | 
					
						
							|  |  |  |  * Create regularly spaced poses with specified radius and number of cameras | 
					
						
							|  |  |  |  */ | 
					
						
							| 
									
										
										
										
											2024-10-25 07:40:53 +08:00
										 |  |  | std::vector<Pose3> posesOnCircle(int num_cameras = 8, double R = 30) { | 
					
						
							|  |  |  |   const double theta = 2 * M_PI / num_cameras; | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   // Initial pose at angle 0, position (R, 0, 0), facing the center with Y-axis
 | 
					
						
							|  |  |  |   // pointing down
 | 
					
						
							|  |  |  |   const Pose3 init(Rot3::Ypr(M_PI_2, 0, -M_PI_2), {R, 0, 0}); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   // Delta rotation: rotate by -theta around Z-axis (counterclockwise movement)
 | 
					
						
							|  |  |  |   Rot3 delta_rotation = Rot3::Ypr(0, -theta, 0); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   // Delta translation in world frame
 | 
					
						
							|  |  |  |   Vector3 delta_translation_world(R * (cos(theta) - 1), R * sin(theta), 0); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   // Transform delta translation to local frame of the camera
 | 
					
						
							|  |  |  |   Vector3 delta_translation_local = | 
					
						
							|  |  |  |       init.rotation().inverse() * delta_translation_world; | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   // Define delta pose
 | 
					
						
							|  |  |  |   const Pose3 delta(delta_rotation, delta_translation_local); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   // Generate poses using createPoses
 | 
					
						
							| 
									
										
										
										
											2024-10-25 02:43:40 +08:00
										 |  |  |   return createPoses(init, delta, num_cameras); | 
					
						
							|  |  |  | } | 
					
						
							|  |  |  | }  // namespace gtsam
 |