CreateSFMExampleData.cpp
Go to the documentation of this file.
1 /* ----------------------------------------------------------------------------
2 
3  * GTSAM Copyright 2010, Georgia Tech Research Corporation,
4  * Atlanta, Georgia 30332-0415
5  * All Rights Reserved
6  * Authors: Frank Dellaert, et al. (see THANKS for the full author list)
7 
8  * See LICENSE for the license information
9 
10  * -------------------------------------------------------------------------- */
11 
19 #include <gtsam/slam/dataset.h>
20 
21 using namespace std;
22 using namespace gtsam;
23 
24 /* ************************************************************************* */
25 
26 void createExampleBALFile(const string& filename, const vector<Point3>& points,
27  const Pose3& pose1, const Pose3& pose2,
28  const Cal3Bundler& K = Cal3Bundler()) {
29  // Class that will gather all data
30  SfmData data;
31  // Create two cameras and add them to data
32  data.cameras.push_back(SfmCamera(pose1, K));
33  data.cameras.push_back(SfmCamera(pose2, K));
34 
35  for (const Point3& p : points) {
36  // Create the track
37  SfmTrack track;
38  track.p = p;
39  track.r = 1;
40  track.g = 1;
41  track.b = 1;
42 
43  // Project points in both cameras
44  for (size_t i = 0; i < 2; i++)
45  track.measurements.push_back(make_pair(i, data.cameras[i].project(p)));
46 
47  // Add track to data
48  data.tracks.push_back(track);
49  }
50 
52 }
53 
54 /* ************************************************************************* */
55 
57  // Create two cameras poses
58  Rot3 aRb = Rot3::Yaw(M_PI_2);
59  Point3 aTb(0.1, 0, 0);
60  Pose3 pose1, pose2(aRb, aTb);
61 
62  // Create test data, we need at least 5 points
63  vector<Point3> points = {
64  {0, 0, 1}, {-0.1, 0, 1}, {0.1, 0, 1}, {0, 0.5, 0.5}, {0, -0.5, 0.5}};
65 
66  // Assumes example is run in ${GTSAM_TOP}/build/examples
67  const string filename = "../../examples/Data/5pointExample1.txt";
69 }
70 
71 /* ************************************************************************* */
72 
74  // Create two cameras poses
75  Rot3 aRb = Rot3::Yaw(M_PI_2);
76  Point3 aTb(10, 0, 0);
77  Pose3 pose1, pose2(aRb, aTb);
78 
79  // Create test data, we need at least 5 points
80  vector<Point3> points = {{0, 0, 100}, {-10, 0, 100}, {10, 0, 100}, //
81  {0, 50, 50}, {0, -50, 50}, {-20, 0, 80}, //
82  {20, -50, 80}};
83 
84  // Assumes example is run in ${GTSAM_TOP}/build/examples
85  const string filename = "../../examples/Data/5pointExample2.txt";
86  Cal3Bundler K(500, 0, 0);
88 }
89 
90 /* ************************************************************************* */
91 
93  // Create two cameras poses
94  Rot3 aRb = Rot3::Yaw(M_PI_2);
95  Point3 aTb(0.1, 0, 0);
96  Pose3 pose1, pose2(aRb, aTb);
97 
98  // Create test data, we need 15 points
99  vector<Point3> points = {
100  {0, 0, 1}, {-0.1, 0, 1}, {0.1, 0, 1}, //
101  {0, 0.5, 0.5}, {0, -0.5, 0.5}, {-1, -0.5, 2}, //
102  {-1, 0.5, 2}, {0.25, -0.5, 1.5}, {0.25, 0.5, 1.5}, //
103  {-0.1, -0.5, 0.5}, {0.1, -0.5, 1}, {0.1, 0.5, 1}, //
104  {-0.1, 0, 0.5}, {-0.1, 0.5, 0.5}, {0, 0, 0.5}, //
105  {0.1, -0.5, 0.5}, {0.1, 0, 0.5}, {0.1, 0.5, 0.5}};
106 
107  // Assumes example is run in ${GTSAM_TOP}/build/examples
108  const string filename = "../../examples/Data/18pointExample1.txt";
110 }
111 
112 int main(int argc, char* argv[]) {
116  return 0;
117 }
118 
119 /* ************************************************************************* */
create5PointExample1
void create5PointExample1()
Definition: CreateSFMExampleData.cpp:56
gtsam::SfmTrack2d::measurements
std::vector< SfmMeasurement > measurements
The 2D image projections (id,(u,v))
Definition: SfmTrack.h:44
simple::pose2
static Pose3 pose2
Definition: testInitializePose3.cpp:58
createExampleBALFile
void createExampleBALFile(const string &filename, const vector< Point3 > &points, const Pose3 &pose1, const Pose3 &pose2, const Cal3Bundler &K=Cal3Bundler())
Definition: CreateSFMExampleData.cpp:26
gtsam::SfmTrack::b
float b
RGB color of the 3D point.
Definition: SfmTrack.h:127
CalibratedCamera.h
Calibrated camera for which only pose is unknown.
gtsam::SfmData
SfmData stores a bunch of SfmTracks.
Definition: SfmData.h:39
gtsam::SfmTrack
Definition: SfmTrack.h:125
gtsam::writeBAL
bool writeBAL(const std::string &filename, const SfmData &data)
This function writes a "Bundle Adjustment in the Large" (BAL) file from a SfmData structure.
Definition: SfmData.cpp:249
data
int data[]
Definition: Map_placement_new.cpp:1
dataset.h
utility functions for loading datasets
gtsam::Rot3
Rot3 is a 3D rotation represented as a rotation matrix if the preprocessor symbol GTSAM_USE_QUATERNIO...
Definition: Rot3.h:58
relicense.filename
filename
Definition: relicense.py:57
gtsam::Pose3
Definition: Pose3.h:37
gtsam::Cal3Bundler
Calibration used by Bundler.
Definition: Cal3Bundler.h:32
main
int main(int argc, char *argv[])
Definition: CreateSFMExampleData.cpp:112
gtsam::SfmTrack::r
float r
Definition: SfmTrack.h:127
example2::aTb
Point3 aTb
Definition: testEssentialMatrixFactor.cpp:541
gtsam::SfmTrack::g
float g
Definition: SfmTrack.h:127
M_PI_2
#define M_PI_2
Definition: mconf.h:118
gtsam
traits
Definition: chartTesting.h:28
pose1
static const Pose3 pose1(Rot3(), Point3(0, 1, 0.5))
K
#define K
Definition: igam.h:8
std
Definition: BFloat16.h:88
p
float * p
Definition: Tutorial_Map_using.cpp:9
gtsam::Point3
Vector3 Point3
Definition: Point3.h:38
gtsam::SfmCamera
PinholeCamera< Cal3Bundler > SfmCamera
Define the structure for the camera poses.
Definition: SfmData.h:33
example2::aRb
Rot3 aRb
Definition: testEssentialMatrixFactor.cpp:540
gtsam::SfmTrack::p
Point3 p
3D position of the point
Definition: SfmTrack.h:126
create18PointExample1
void create18PointExample1()
Definition: CreateSFMExampleData.cpp:92
i
int i
Definition: BiCGSTAB_step_by_step.cpp:9
create5PointExample2
void create5PointExample2()
Definition: CreateSFMExampleData.cpp:73


gtsam
Author(s):
autogenerated on Tue Jun 25 2024 03:00:42