37 using namespace gtsam;
42 int main(
int argc,
char** argv){
46 const auto model = noiseModel::Isotropic::Sigma(2,1);
55 ifstream calibration_file(calibration_loc.c_str());
56 cout <<
"Reading calibration info" << endl;
57 calibration_file >> fx >> fy >> s >> u0 >> v0 >>
b;
60 const Cal3_S2 true_K(fx,fy,s,u0,v0);
61 const Cal3_S2 noisy_K(fx*1.2,fy*1.2,s,u0-10,v0+10);
63 initial_estimate.
insert(
K(0), noisy_K);
65 auto calNoise = noiseModel::Diagonal::Sigmas((
Vector(5) << 500, 500, 1
e-5, 100, 100).finished());
69 ifstream pose_file(pose_loc.c_str());
70 cout <<
"Reading camera poses" << endl;
74 while (pose_file >> pose_id) {
75 for (
int i = 0;
i < 16;
i++) {
76 pose_file >> m.
data()[
i];
81 auto poseNoise = noiseModel::Isotropic::Sigma(6, 0.01);
89 double uL, uR,
v, _X,
Y,
Z;
90 ifstream factor_file(factor_loc.c_str());
91 cout <<
"Reading stereo factors" << endl;
93 while (factor_file >> x >> l >> uL >> uR >> v >> _X >> Y >> Z) {
100 if (!initial_estimate.
exists(
L(l))) {
104 initial_estimate.
insert(
L(l), worldPoint);
114 cout <<
"Optimizing" << endl;
116 params.
verbosityLM = LevenbergMarquardtParams::TRYLAMBDA;
117 params.
verbosity = NonlinearOptimizerParams::ERROR;
123 string K_values_file =
"K_values.txt";
124 ofstream stream_K(K_values_file.c_str());
135 currentError = optimizer.
error();
140 if(params.
verbosity >= NonlinearOptimizerParams::ERROR) cout <<
"newError: " << optimizer.
error() << endl;
147 cout <<
"Final result sample:" << endl;
149 pose_values.
print(
"Final camera poses:\n");
153 noisy_K.
print(
"Initial noisy K\n");
154 true_K.
print(
"Initial correct K\n");
IsDerived< DERIVEDFACTOR > emplace_shared(Args &&... args)
Emplace a shared pointer to factor of given type.
A non-templated config holding any types of Manifold-group elements.
Factor Graph consisting of non-linear factors.
EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const Scalar * data() const
noiseModel::Diagonal::shared_ptr model
const ValueType at(Key j) const
size_t iterations() const
return number of iterations in current optimizer state
static Cal3_S2 K(500, 500, 0.1, 640/2, 480/2)
Verbosity verbosity
The printing verbosity during optimization (default SILENT)
EIGEN_STRONG_INLINE Packet4f print(const Packet4f &a)
const Values & values() const
return values in current optimizer state
NonlinearFactorGraph graph
double absoluteErrorTol
The maximum absolute error decrease to stop iterating (default 1e-5)
static const SmartProjectionParams params
void addPrior(Key key, const T &prior, const SharedNoiseModel &model=nullptr)
double relativeErrorTol
The maximum relative error decrease to stop iterating (default 1e-5)
bool checkConvergence(double relativeErrorTreshold, double absoluteErrorTreshold, double errorThreshold, double currentError, double newError, NonlinearOptimizerParams::Verbosity verbosity)
double errorTol
The maximum total error to stop iterating (default 0.0)
static Pose3 camPose(Rot3((Matrix3()<< 1., 0., 0., 0.,-1., 0., 0., 0.,-1.).finished()), Point3(0, 0, 6.25))
void print(const std::string &str="", const KeyFormatter &keyFormatter=DefaultKeyFormatter) const
static const Line3 l(Rot3(), 1, 1)
Array< int, Dynamic, 1 > v
Point3 transformFrom(const Point3 &point, OptionalJacobian< 3, 6 > Hself={}, OptionalJacobian< 3, 3 > Hpoint={}) const
takes point in Pose coordinates and transforms it to world coordinates
A nonlinear optimizer that uses the Levenberg-Marquardt trust-region scheme.
Array< double, 1, 3 > e(1./3., 0.5, 2.)
Values allPose3s(const Values &values)
Extract all Pose3 values.
The most common 5DOF 3D->2D calibration.
Reprojection of a LANDMARK to a 2D point.
GTSAM_EXPORT std::string findExampleDataFile(const std::string &name)
GaussianFactorGraph::shared_ptr iterate() override
int main(int argc, char **argv)
void insert(Key j, const Value &val)
The matrix class, also used for vectors and row-vectors.
VerbosityLM verbosityLM
The verbosity level for Levenberg-Marquardt (default: SILENT), see also NonlinearOptimizerParams::ver...
a general SFM factor with an unknown calibration
set noclip points set clip one set noclip two set bar set border lt lw set xdata set ydata set zdata set x2data set y2data set boxwidth set dummy x
double error() const
return error in current optimizer state
Eigen::Matrix< double, Eigen::Dynamic, 1 > Vector
utility functions for loading datasets
void print(const std::string &s="Cal3_S2") const override
print with optional string
size_t maxIterations
The maximum iterations to stop iterating (default 100)