53 static SfmData FromBundlerFile(
const std::string& filename);
61 static SfmData FromBalFile(
const std::string& filename);
86 const std::vector<SfmCamera>&
cameraList()
const {
return cameras; }
87 const std::vector<SfmTrack>& trackList()
const {
return tracks; }
95 NonlinearFactorGraph generalSfmFactors(
109 NonlinearFactorGraph sfmFactorGraph(
111 boost::optional<size_t> fixedCamera = 0,
112 boost::optional<size_t> fixedPoint = 0)
const;
119 void print(
const std::string& s =
"")
const;
122 bool equals(
const SfmData& sfmData,
double tol = 1e-9)
const;
125#ifdef GTSAM_ALLOW_DEPRECATED_SINCE_V42
128 void GTSAM_DEPRECATED add_track(
const SfmTrack& t) { tracks.push_back(t); }
129 void GTSAM_DEPRECATED add_camera(
const SfmCamera& cam) {
130 cameras.push_back(cam);
132 size_t GTSAM_DEPRECATED number_tracks()
const {
return tracks.size(); }
133 size_t GTSAM_DEPRECATED number_cameras()
const {
return cameras.size(); }
140 friend class boost::serialization::access;
141 template <
class Archive>
142 void serialize(Archive& ar,
const unsigned int ) {
143 ar& BOOST_SERIALIZATION_NVP(cameras);
144 ar& BOOST_SERIALIZATION_NVP(tracks);
154#ifdef GTSAM_ALLOW_DEPRECATED_SINCE_V42
155GTSAM_EXPORT
bool GTSAM_DEPRECATED readBundler(
const std::string& filename,
157GTSAM_EXPORT
bool GTSAM_DEPRECATED readBAL(
const std::string& filename,
176GTSAM_EXPORT
bool writeBAL(
const std::string& filename,
const SfmData& data);
Base class for all pinhole cameras.
Calibration used by Bundler.
Factor Graph consisting of non-linear factors.
A non-templated config holding any types of Manifold-group elements.
A simple data structure for a track in Structure from Motion.
Global functions in a separate testing namespace.
Definition: chartTesting.h:28
std::string serialize(const T &input)
serializes to a string
Definition: serialization.h:113
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
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:349
void print(const Matrix &A, const string &s, ostream &stream)
print without optional string, must specify cout yourself
Definition: Matrix.cpp:156
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:344
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
noiseModel::Base::shared_ptr SharedNoiseModel
Aliases.
Definition: NoiseModel.h:724
Values initialCamerasAndPointsEstimate(const SfmData &db)
This function creates initial values for cameras and points from db.
Definition: SfmData.cpp:449
PinholeCamera< Cal3Bundler > SfmCamera
Define the structure for the camera poses.
Definition: SfmData.h:33
Values initialCamerasEstimate(const SfmData &db)
This function creates initial values for cameras from db.
Definition: SfmData.cpp:441
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
A manifold defines a space in which there is a notion of a linear tangent space that can be centered ...
Definition: concepts.h:30
A helper that implements the traits interface for GTSAM types.
Definition: Testable.h:151
A pinhole camera class that has a Pose3 and a Calibration.
Definition: PinholeCamera.h:33
A 3D pose (R,t) : (Rot3,Point3)
Definition: Pose3.h:37
Rot3 is a 3D rotation represented as a rotation matrix if the preprocessor symbol GTSAM_USE_QUATERNIO...
Definition: Rot3.h:58
static shared_ptr Sigma(size_t dim, double sigma, bool smart=true)
An isotropic noise model created by specifying a standard devation sigma.
Definition: NoiseModel.cpp:597
A non-templated config holding any types of Manifold-group elements.
Definition: Values.h:65
SfmData stores a bunch of SfmTracks.
Definition: SfmData.h:39
const std::vector< SfmCamera > & cameraList() const
Getters.
Definition: SfmData.h:86
void addCamera(const SfmCamera &cam)
Add a camera to SfmData.
Definition: SfmData.h:71
size_t numberCameras() const
The number of cameras.
Definition: SfmData.h:77
size_t numberTracks() const
The number of reconstructed 3D points.
Definition: SfmData.h:74
const SfmTrack & track(size_t idx) const
The track formed by series of landmark measurements.
Definition: SfmData.h:80
void addTrack(const SfmTrack &t)
Add a track to SfmData.
Definition: SfmData.h:68
const SfmCamera & camera(size_t idx) const
The camera pose at frame index idx
Definition: SfmData.h:83
std::vector< SfmCamera > cameras
Set of cameras.
Definition: SfmData.h:40
std::vector< SfmTrack > tracks
Sparse set of points.
Definition: SfmData.h:42
Definition: SfmTrack.h:126