SfmData stores a bunch of SfmTracks.
More...
#include <SfmData.h>
SfmData stores a bunch of SfmTracks.
Definition at line 39 of file SfmData.h.
◆ addCamera()
void gtsam::SfmData::addCamera |
( |
const SfmCamera & |
cam | ) |
|
|
inline |
◆ addTrack()
void gtsam::SfmData::addTrack |
( |
const SfmTrack & |
t | ) |
|
|
inline |
◆ camera()
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 |
◆ 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
-
filename | The 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
-
filename | The name of the bundler file |
data | SfM structure where the data is stored |
- Returns
- true if the parsing was successful, false otherwise
Definition at line 102 of file SfmData.cpp.
◆ generalSfmFactors()
Create projection factors using keys i and P(j)
- Parameters
-
model | a 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 |
◆ sfmFactorGraph()
Create factor graph with projection factors and gauge fix.
Note: pose keys are simply integer indices, points use Symbol('p', j).
- Parameters
-
model | a noise model for projection errors |
fixedCamera | which camera to fix, if any (use std::nullopt if none) |
fixedPoint | which point to fix, if any (use std::nullopt if none) |
- Returns
- NonlinearFactorGraph
Definition at line 407 of file SfmData.cpp.
◆ track()
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 |
◆ cameras
std::vector<SfmCamera> gtsam::SfmData::cameras |
◆ 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: