Go to the documentation of this file.
86 const std::vector<SfmCamera>&
cameraList()
const {
return cameras; }
87 const std::vector<SfmTrack>&
trackList()
const {
return tracks; }
111 std::optional<size_t> fixedCamera = 0,
112 std::optional<size_t> fixedPoint = 0)
const;
119 void print(
const std::string&
s =
"")
const;
128 #ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
129 friend class boost::serialization::access;
131 template <
class Archive>
132 void serialize(Archive& ar,
const unsigned int ) {
133 ar& BOOST_SERIALIZATION_NVP(cameras);
134 ar& BOOST_SERIALIZATION_NVP(tracks);
const SfmCamera & camera(size_t idx) const
The camera pose at frame index idx
Values initialCamerasAndPointsEstimate(const SfmData &db)
This function creates initial values for cameras and points from db.
Array< double, 1, 3 > e(1./3., 0.5, 2.)
Pose3 openGL2gtsam(const Rot3 &R, double tx, double ty, double tz)
This function converts an openGL camera pose to an GTSAM camera pose.
const SfmTrack & track(size_t idx) const
The track formed by series of landmark measurements.
SfmData readBal(const std::string &filename)
This function parses a "Bundle Adjustment in the Large" (BAL) file and returns the data as a SfmData ...
SfmData stores a bunch of SfmTracks.
bool writeBAL(const std::string &filename, const SfmData &data)
This function writes a "Bundle Adjustment in the Large" (BAL) file from a SfmData structure.
std::vector< SfmTrack > tracks
Sparse set of points.
void print(const Matrix &A, const string &s, ostream &stream)
Rot3 is a 3D rotation represented as a rotation matrix if the preprocessor symbol GTSAM_USE_QUATERNIO...
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...
Base class for all pinhole cameras.
noiseModel::Base::shared_ptr SharedNoiseModel
const std::vector< SfmTrack > & trackList() const
const std::vector< SfmCamera > & cameraList() const
Getters.
noiseModel::Diagonal::shared_ptr model
void addCamera(const SfmCamera &cam)
Add a camera to SfmData.
size_t numberCameras() const
The number of cameras.
Factor Graph consisting of non-linear factors.
std::vector< SfmCamera > cameras
Set of cameras.
Pose3 gtsam2openGL(const Rot3 &R, double tx, double ty, double tz)
This function converts a GTSAM camera pose to an openGL camera pose.
static shared_ptr Sigma(size_t dim, double sigma, bool smart=true)
PinholeCamera< Cal3Bundler > SfmCamera
Define the structure for the camera poses.
size_t numberTracks() const
The number of reconstructed 3D points.
Calibration used by Bundler.
A simple data structure for a track in Structure from Motion.
Rot2 R(Rot2::fromAngle(0.1))
A non-templated config holding any types of Manifold-group elements.
void addTrack(const SfmTrack &t)
Add a track to SfmData.
Values initialCamerasEstimate(const SfmData &db)
This function creates initial values for cameras from db.
gtsam
Author(s):
autogenerated on Fri Nov 1 2024 03:35:15