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. More...
 
void addCamera (const SfmCamera &cam)
 Add a camera to SfmData. More...
 
size_t numberTracks () const
 The number of reconstructed 3D points. More...
 
size_t numberCameras () const
 The number of cameras. More...
 
const SfmTracktrack (size_t idx) const
 The track formed by series of landmark measurements. More...
 
const SfmCameracamera (size_t idx) const
 The camera pose at frame index idx More...
 
const std::vector< SfmCamera > & cameraList () const
 Getters. More...
 
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 More...
 
bool equals (const SfmData &sfmData, double tol=1e-9) const
 assert equality up to a tolerance More...
 

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. More...
 
std::vector< SfmTracktracks
 Sparse set of points. More...
 

Detailed Description

SfmData stores a bunch of SfmTracks.

Definition at line 39 of file SfmData.h.

Member Function Documentation

◆ addCamera()

void gtsam::SfmData::addCamera ( const SfmCamera cam)
inline

Add a camera to SfmData.

Definition at line 71 of file SfmData.h.

◆ addTrack()

void gtsam::SfmData::addTrack ( const SfmTrack t)
inline

Add a track to SfmData.

Definition at line 68 of file SfmData.h.

◆ camera()

const SfmCamera& gtsam::SfmData::camera ( size_t  idx) const
inline

The camera pose at frame index idx

Definition at line 83 of file SfmData.h.

◆ cameraList()

const std::vector<SfmCamera>& gtsam::SfmData::cameraList ( ) const
inline

Getters.

Definition at line 86 of file SfmData.h.

◆ equals()

bool gtsam::SfmData::equals ( const SfmData sfmData,
double  tol = 1e-9 
) const

assert equality up to a tolerance

Definition at line 40 of file SfmData.cpp.

◆ FromBalFile()

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.

Definition at line 189 of file SfmData.cpp.

◆ FromBundlerFile()

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

Definition at line 102 of file SfmData.cpp.

◆ 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

Definition at line 388 of file SfmData.cpp.

◆ numberCameras()

size_t gtsam::SfmData::numberCameras ( ) const
inline

The number of cameras.

Definition at line 77 of file SfmData.h.

◆ numberTracks()

size_t gtsam::SfmData::numberTracks ( ) const
inline

The number of reconstructed 3D points.

Definition at line 74 of file SfmData.h.

◆ print()

void gtsam::SfmData::print ( const std::string &  s = "") const

print

Definition at line 34 of file SfmData.cpp.

◆ 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

Definition at line 407 of file SfmData.cpp.

◆ track()

const SfmTrack& gtsam::SfmData::track ( size_t  idx) const
inline

The track formed by series of landmark measurements.

Definition at line 80 of file SfmData.h.

◆ trackList()

const std::vector<SfmTrack>& gtsam::SfmData::trackList ( ) const
inline

Definition at line 87 of file SfmData.h.

Member Data Documentation

◆ cameras

std::vector<SfmCamera> gtsam::SfmData::cameras

Set of cameras.

Definition at line 40 of file SfmData.h.

◆ tracks

std::vector<SfmTrack> gtsam::SfmData::tracks

Sparse set of points.

Definition at line 42 of file SfmData.h.


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


gtsam
Author(s):
autogenerated on Tue Jul 4 2023 02:47:08