32 using namespace gtsam;
42 int main(
int argc,
char* argv[]) {
45 if (argc > 1) filename = string(argv[1]);
50 cout << boost::format(
"read %1% tracks on %2% cameras\n") %
57 auto noise = noiseModel::Isotropic::Sigma(2, 1.0);
66 uv, noise,
C(i),
P(j));
73 graph.
addPrior(
C(0), mydata.
cameras[0], noiseModel::Isotropic::Sigma(9, 0.1));
75 noiseModel::Isotropic::Sigma(3, 0.1));
91 params_using_METIS.
ordering = Ordering::Create(Ordering::METIS, graph);
96 params_using_COLAMD.
ordering = Ordering::Create(Ordering::COLAMD, graph);
98 }
catch (exception&
e) {
104 cout <<
"COLAMD and METIS produce the same ordering. " 105 <<
"Problem here!!!" << endl;
110 Values result_METIS, result_COLAMD;
112 gttic_(OPTIMIZE_WITH_METIS);
115 gttoc_(OPTIMIZE_WITH_METIS);
117 gttic_(OPTIMIZE_WITH_COLAMD);
119 result_COLAMD = lm_COLAMD.
optimize();
120 gttoc_(OPTIMIZE_WITH_COLAMD);
121 }
catch (exception& e) {
127 cout <<
"COLAMD final error: " << graph.
error(result_COLAMD) << endl;
128 cout <<
"METIS final error: " << graph.
error(result_METIS) << endl;
130 cout << endl << endl;
132 cout <<
"Time comparison by solving " << filename <<
" results:" << endl;
133 cout << boost::format(
"%1% point tracks and %2% cameras\n") %
virtual const Values & optimize()
Define the structure for SfM data.
Factor Graph consisting of non-linear factors.
int main(int argc, char *argv[])
void insert(Key j, const Value &val)
NonlinearFactorGraph graph
std::vector< SfmTrack > tracks
Sparse set of points.
void addPrior(Key key, const T &prior, const SharedNoiseModel &model=nullptr)
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.
IsDerived< DERIVEDFACTOR > emplace_shared(Args &&...args)
Emplace a shared pointer to factor of given type.
Define the structure for the 3D points.
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.)
boost::optional< Ordering > ordering
The optional variable elimination ordering, or empty to use COLAMD (default: empty) ...
Matrix< Scalar, Dynamic, Dynamic > C
std::vector< SfmCamera > cameras
Set of cameras.
Point3 p
3D position of the point
double error(const Values &values) const
static const CalibratedCamera camera(kDefaultPose)
a general SFM factor with an unknown calibration
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...
GeneralSFMFactor< SfmCamera, Point3 > MyFactor
size_t number_cameras() const