SfmData.h
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 #pragma once
20 
24 #include <gtsam/nonlinear/Values.h>
25 #include <gtsam/sfm/SfmTrack.h>
26 
27 #include <string>
28 #include <vector>
29 
30 namespace gtsam {
31 
34 
39 struct GTSAM_EXPORT SfmData {
40  std::vector<SfmCamera> cameras;
41 
42  std::vector<SfmTrack> tracks;
43 
46 
53  static SfmData FromBundlerFile(const std::string& filename);
54 
61  static SfmData FromBalFile(const std::string& filename);
62 
66 
68  void addTrack(const SfmTrack& t) { tracks.push_back(t); }
69 
71  void addCamera(const SfmCamera& cam) { cameras.push_back(cam); }
72 
74  size_t numberTracks() const { return tracks.size(); }
75 
77  size_t numberCameras() const { return cameras.size(); }
78 
80  const SfmTrack& track(size_t idx) const { return tracks[idx]; }
81 
83  const SfmCamera& camera(size_t idx) const { return cameras[idx]; }
84 
86  const std::vector<SfmCamera>& cameraList() const { return cameras; }
87  const std::vector<SfmTrack>& trackList() const { return tracks; }
88 
95  NonlinearFactorGraph generalSfmFactors(
97  1.0)) const;
98 
109  NonlinearFactorGraph sfmFactorGraph(
111  std::optional<size_t> fixedCamera = 0,
112  std::optional<size_t> fixedPoint = 0) const;
113 
117 
119  void print(const std::string& s = "") const;
120 
122  bool equals(const SfmData& sfmData, double tol = 1e-9) const;
123 
127 
128 #ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
129  friend class boost::serialization::access;
131  template <class Archive>
132  void serialize(Archive& ar, const unsigned int /*version*/) {
133  ar& BOOST_SERIALIZATION_NVP(cameras);
134  ar& BOOST_SERIALIZATION_NVP(tracks);
135  }
136 #endif
137 
138 
140 };
141 
143 template <>
144 struct traits<SfmData> : public Testable<SfmData> {};
145 
152 GTSAM_EXPORT SfmData readBal(const std::string& filename);
153 
161 GTSAM_EXPORT bool writeBAL(const std::string& filename, const SfmData& data);
162 
175 GTSAM_EXPORT bool writeBALfromValues(const std::string& filename,
176  const SfmData& data, const Values& values);
177 
186 GTSAM_EXPORT Pose3 openGL2gtsam(const Rot3& R, double tx, double ty, double tz);
187 
196 GTSAM_EXPORT Pose3 gtsam2openGL(const Rot3& R, double tx, double ty, double tz);
197 
203 GTSAM_EXPORT Pose3 gtsam2openGL(const Pose3& PoseGTSAM);
204 
213 GTSAM_EXPORT Values initialCamerasEstimate(const SfmData& db);
214 
223 GTSAM_EXPORT Values initialCamerasAndPointsEstimate(const SfmData& db);
224 
225 } // namespace gtsam
gtsam::SfmData::camera
const SfmCamera & camera(size_t idx) const
The camera pose at frame index idx
Definition: SfmData.h:83
gtsam::initialCamerasAndPointsEstimate
Values initialCamerasAndPointsEstimate(const SfmData &db)
This function creates initial values for cameras and points from db.
Definition: SfmData.cpp:430
s
RealScalar s
Definition: level1_cplx_impl.h:126
e
Array< double, 1, 3 > e(1./3., 0.5, 2.)
gtsam::openGL2gtsam
Pose3 openGL2gtsam(const Rot3 &R, double tx, double ty, double tz)
This function converts an openGL camera pose to an GTSAM camera pose.
Definition: SfmData.cpp:79
gtsam::SfmData::track
const SfmTrack & track(size_t idx) const
The track formed by series of landmark measurements.
Definition: SfmData.h:80
gtsam::readBal
SfmData readBal(const std::string &filename)
This function parses a "Bundle Adjustment in the Large" (BAL) file and returns the data as a SfmData ...
Definition: SfmData.cpp:325
different_sigmas::values
HybridValues values
Definition: testHybridBayesNet.cpp:245
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
gtsam::SfmData::tracks
std::vector< SfmTrack > tracks
Sparse set of points.
Definition: SfmData.h:42
gtsam::print
void print(const Matrix &A, const string &s, ostream &stream)
Definition: Matrix.cpp:155
data
int data[]
Definition: Map_placement_new.cpp:1
gtsam::Rot3
Rot3 is a 3D rotation represented as a rotation matrix if the preprocessor symbol GTSAM_USE_QUATERNIO...
Definition: Rot3.h:58
gtsam::writeBALfromValues
bool writeBALfromValues(const std::string &filename, const SfmData &data, const Values &values)
This function writes a "Bundle Adjustment in the Large" (BAL) file from a SfmData structure and a val...
Definition: SfmData.cpp:330
relicense.filename
filename
Definition: relicense.py:57
gtsam::Pose3
Definition: Pose3.h:37
gtsam::PinholeCamera< Cal3Bundler >
gtsam::NonlinearFactorGraph
Definition: NonlinearFactorGraph.h:55
PinholeCamera.h
Base class for all pinhole cameras.
gtsam::SharedNoiseModel
noiseModel::Base::shared_ptr SharedNoiseModel
Definition: NoiseModel.h:762
gtsam::SfmData::trackList
const std::vector< SfmTrack > & trackList() const
Definition: SfmData.h:87
gtsam::SfmData::cameraList
const std::vector< SfmCamera > & cameraList() const
Getters.
Definition: SfmData.h:86
model
noiseModel::Diagonal::shared_ptr model
Definition: doc/Code/Pose2SLAMExample.cpp:7
gtsam::SfmData::addCamera
void addCamera(const SfmCamera &cam)
Add a camera to SfmData.
Definition: SfmData.h:71
gtsam::equals
Definition: Testable.h:112
gtsam::SfmData::numberCameras
size_t numberCameras() const
The number of cameras.
Definition: SfmData.h:77
gtsam
traits
Definition: SFMdata.h:40
gtsam::Testable
Definition: Testable.h:152
gtsam::traits
Definition: Group.h:36
NonlinearFactorGraph.h
Factor Graph consisting of non-linear factors.
gtsam::SfmData::cameras
std::vector< SfmCamera > cameras
Set of cameras.
Definition: SfmData.h:40
gtsam::Values
Definition: Values.h:65
gtsam::tol
const G double tol
Definition: Group.h:79
gtsam::gtsam2openGL
Pose3 gtsam2openGL(const Rot3 &R, double tx, double ty, double tz)
This function converts a GTSAM camera pose to an openGL camera pose.
Definition: SfmData.cpp:88
gtsam::noiseModel::Isotropic::Sigma
static shared_ptr Sigma(size_t dim, double sigma, bool smart=true)
Definition: NoiseModel.cpp:624
gtsam::SfmCamera
PinholeCamera< Cal3Bundler > SfmCamera
Define the structure for the camera poses.
Definition: SfmData.h:33
align_3::t
Point2 t(10, 10)
gtsam::SfmData::numberTracks
size_t numberTracks() const
The number of reconstructed 3D points.
Definition: SfmData.h:74
Cal3Bundler.h
Calibration used by Bundler.
SfmTrack.h
A simple data structure for a track in Structure from Motion.
R
Rot2 R(Rot2::fromAngle(0.1))
Values.h
A non-templated config holding any types of Manifold-group elements.
gtsam::SfmData::addTrack
void addTrack(const SfmTrack &t)
Add a track to SfmData.
Definition: SfmData.h:68
gtsam::initialCamerasEstimate
Values initialCamerasEstimate(const SfmData &db)
This function creates initial values for cameras from db.
Definition: SfmData.cpp:422


gtsam
Author(s):
autogenerated on Fri Nov 1 2024 03:35:15