GTSAM  4.0.2
C++ library for smoothing and mapping (SAM)
Public Attributes | List of all members
gtsam::SfmData Struct Reference

SfmData stores a bunch of SfmTracks. More...

#include <SfmData.h>

Public Member Functions

Standard Interface
void addTrack (const SfmTrack &t)
 Add a track to SfmData.
 
void addCamera (const SfmCamera &cam)
 Add a camera to SfmData.
 
size_t numberTracks () const
 The number of reconstructed 3D points.
 
size_t numberCameras () const
 The number of cameras.
 
const SfmTracktrack (size_t idx) const
 The track formed by series of landmark measurements.
 
const SfmCameracamera (size_t idx) const
 The camera pose at frame index idx
 
const std::vector< SfmCamera > & cameraList () const
 Getters.
 
const std::vector< SfmTrack > & trackList () const
 
NonlinearFactorGraph generalSfmFactors (const SharedNoiseModel &model=noiseModel::Isotropic::Sigma(2, 1.0)) const
 Create projection factors using keys i and P(j) More...
 
NonlinearFactorGraph sfmFactorGraph (const SharedNoiseModel &model=noiseModel::Isotropic::Sigma(2, 1.0), std::optional< size_t > fixedCamera=0, std::optional< size_t > fixedPoint=0) const
 Create factor graph with projection factors and gauge fix. More...
 
Testable
void print (const std::string &s="") const
 print
 
bool equals (const SfmData &sfmData, double tol=1e-9) const
 assert equality up to a tolerance
 

Static Public Member Functions

Create from file
static SfmData FromBundlerFile (const std::string &filename)
 Parses a bundler output file and return result as SfmData instance. More...
 
static SfmData FromBalFile (const std::string &filename)
 Parse a "Bundle Adjustment in the Large" (BAL) file and return result as SfmData instance. More...
 

Public Attributes

std::vector< SfmCameracameras
 Set of cameras.
 
std::vector< SfmTracktracks
 Sparse set of points.
 

Detailed Description

SfmData stores a bunch of SfmTracks.

Member Function Documentation

◆ FromBalFile()

static SfmData gtsam::SfmData::FromBalFile ( const std::string &  filename)
static

Parse a "Bundle Adjustment in the Large" (BAL) file and return result as SfmData instance.

Parameters
filenameThe name of the BAL file.
Returns
SfM structure where the data is stored.

◆ FromBundlerFile()

static SfmData gtsam::SfmData::FromBundlerFile ( const std::string &  filename)
static

Parses a bundler output file and return result as SfmData instance.

Parameters
filenameThe name of the bundler file
dataSfM structure where the data is stored
Returns
true if the parsing was successful, false otherwise

◆ generalSfmFactors()

NonlinearFactorGraph gtsam::SfmData::generalSfmFactors ( const SharedNoiseModel model = noiseModel::Isotropic::Sigma(2, 1.0)) const

Create projection factors using keys i and P(j)

Parameters
modela noise model for projection errors
Returns
NonlinearFactorGraph

◆ sfmFactorGraph()

NonlinearFactorGraph gtsam::SfmData::sfmFactorGraph ( const SharedNoiseModel model = noiseModel::Isotropic::Sigma(2, 1.0),
std::optional< size_t >  fixedCamera = 0,
std::optional< size_t >  fixedPoint = 0 
) const

Create factor graph with projection factors and gauge fix.

Note: pose keys are simply integer indices, points use Symbol('p', j).

Parameters
modela noise model for projection errors
fixedCamerawhich camera to fix, if any (use std::nullopt if none)
fixedPointwhich point to fix, if any (use std::nullopt if none)
Returns
NonlinearFactorGraph

The documentation for this struct was generated from the following file: