wrap SfM_data struct
parent
6ab77600cc
commit
381f7bee30
5
gtsam.h
5
gtsam.h
|
@ -2724,6 +2724,11 @@ virtual class EssentialMatrixFactor : gtsam::NoiseModelFactor {
|
||||||
};
|
};
|
||||||
|
|
||||||
#include <gtsam/slam/dataset.h>
|
#include <gtsam/slam/dataset.h>
|
||||||
|
class SfM_data {
|
||||||
|
size_t number_cameras() const;
|
||||||
|
size_t number_tracks() const;
|
||||||
|
};
|
||||||
|
|
||||||
string findExampleDataFile(string name);
|
string findExampleDataFile(string name);
|
||||||
pair<gtsam::NonlinearFactorGraph*, gtsam::Values*> load2D(string filename,
|
pair<gtsam::NonlinearFactorGraph*, gtsam::Values*> load2D(string filename,
|
||||||
gtsam::noiseModel::Diagonal* model, int maxID, bool addNoise, bool smart);
|
gtsam::noiseModel::Diagonal* model, int maxID, bool addNoise, bool smart);
|
||||||
|
|
Loading…
Reference in New Issue