35 using namespace gtsam;
36 using namespace noiseModel;
43 int main(
int argc,
char* argv[]) {
46 if (argc > 1) filename = string(argv[1]);
51 cout << boost::format(
"read %1% tracks on %2% cameras\n") %
61 Pose3_ pose0_(&SfmCamera::getPose, camera0_);
64 noiseModel::Isotropic::Sigma(6, 0.1));
69 noiseModel::Isotropic::Sigma(3, 0.1));
72 auto noise = noiseModel::Isotropic::Sigma(2, 1.0);
86 Point2_ predict_ = project2<SfmCamera>(camera_, point_);
107 }
catch (exception&
e) {
110 cout <<
"final error: " << graph.
error(result) << endl;
virtual const Values & optimize()
Define the structure for SfM data.
void insert(Key j, const Value &val)
NonlinearFactorGraph graph
std::vector< SfmTrack > tracks
Sparse set of points.
string findExampleDataFile(const string &name)
std::pair< size_t, Point2 > SfmMeasurement
A measurement with its camera index.
size_t number_tracks() const
The number of reconstructed 3D points.
Define the structure for the 3D points.
Factor graph that supports adding ExpressionFactors directly.
void setVerbosity(const std::string &src)
A nonlinear optimizer that uses the Levenberg-Marquardt trust-region scheme.
Array< double, 1, 3 > e(1./3., 0.5, 2.)
static SmartStereoProjectionParams params
int main(int argc, char *argv[])
Matrix< Scalar, Dynamic, Dynamic > C
std::vector< SfmCamera > cameras
Set of cameras.
Point3 p
3D position of the point
void addExpressionFactor(const Expression< T > &h, const T &z, const SharedNoiseModel &R)
double error(const Values &values) const
static const CalibratedCamera camera(kDefaultPose)
utility functions for loading datasets
std::vector< SfmMeasurement > measurements
The 2D image projections (id,(u,v))
bool readBAL(const string &filename, SfmData &data)
This function parses a "Bundle Adjustment in the Large" (BAL) file and stores the data into a SfmData...
size_t number_cameras() const