34 #include <boost/lexical_cast.hpp> 37 using namespace gtsam;
39 int main(
int argc,
char** argv){
52 ifstream calibration_file(calibration_loc.c_str());
53 cout <<
"Reading calibration info" << endl;
54 calibration_file >> fx >> fy >> s >> u0 >> v0 >>
b;
66 ifstream pose_file(pose_loc.c_str());
67 cout <<
"Reading camera poses" << endl;
71 while (pose_file >> pose_id) {
72 for (
int i = 0;
i < 16;
i++) {
73 pose_file >> m.
data()[
i];
86 double uL, uR,
v,
X,
Y,
Z;
87 ifstream factor_file(factor_loc.c_str());
88 cout <<
"Reading stereo factors" << endl;
90 while (factor_file >> x >> l >> uL >> uR >> v >> X >> Y >> Z) {
111 cout <<
"Optimizing" << endl;
113 params.
verbosityLM = LevenbergMarquardtParams::TRYLAMBDA;
114 params.
verbosity = NonlinearOptimizerParams::ERROR;
120 string K_values_file =
"K_values.txt";
121 ofstream stream_K(K_values_file.c_str());
132 currentError = optimizer.
error();
137 if(params.
verbosity >= NonlinearOptimizerParams::ERROR) cout <<
"newError: " << optimizer.
error() << endl;
144 cout <<
"Final result sample:" << endl;
146 pose_values.
print(
"Final camera poses:\n");
150 noisy_K->print(
"Initial noisy K\n");
151 K->print(
"Initial correct K\n");
A non-templated config holding any types of Manifold-group elements.
Factor Graph consisting of non-linear factors.
noiseModel::Diagonal::shared_ptr model
void insert(Key j, const Value &val)
EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const Scalar * data() const
static Cal3_S2 K(500, 500, 0.1, 640/2, 480/2)
Verbosity verbosity
The printing verbosity during optimization (default SILENT)
NonlinearFactorGraph graph
double absoluteErrorTol
The maximum absolute error decrease to stop iterating (default 1e-5)
void addPrior(Key key, const T &prior, const SharedNoiseModel &model=nullptr)
double relativeErrorTol
The maximum relative error decrease to stop iterating (default 1e-5)
string findExampleDataFile(const string &name)
double errorTol
The maximum total error to stop iterating (default 0.0)
Point3 transformFrom(const Point3 &point, OptionalJacobian< 3, 6 > Hself=boost::none, OptionalJacobian< 3, 3 > Hpoint=boost::none) const
takes point in Pose coordinates and transforms it to world coordinates
IsDerived< DERIVEDFACTOR > emplace_shared(Args &&...args)
Emplace a shared pointer to factor of given type.
static const Line3 l(Rot3(), 1, 1)
bool checkConvergence(double relativeErrorTreshold, double absoluteErrorTreshold, double errorThreshold, double currentError, double newError, NonlinearOptimizerParams::Verbosity verbosity)
const ValueType at(Key j) const
const Values & values() const
return values in current optimizer state
A nonlinear optimizer that uses the Levenberg-Marquardt trust-region scheme.
Array< double, 1, 3 > e(1./3., 0.5, 2.)
static SmartStereoProjectionParams params
double error() const
return error in current optimizer state
boost::shared_ptr< Diagonal > shared_ptr
Basic bearing factor from 2D measurement.
void print(const std::string &str="", const KeyFormatter &keyFormatter=DefaultKeyFormatter) const
std::vector< float > Values
static Pose3 camPose(Rot3((Matrix3()<< 1., 0., 0., 0.,-1., 0., 0., 0.,-1.).finished()), Point3(0, 0, 6.25))
GaussianFactorGraph::shared_ptr iterate() override
int main(int argc, char **argv)
boost::shared_ptr< Isotropic > shared_ptr
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
Eigen::Matrix< double, Eigen::Dynamic, 1 > Vector
boost::shared_ptr< Cal3_S2 > shared_ptr
utility functions for loading datasets
size_t maxIterations
The maximum iterations to stop iterating (default 100)
Filtered< Value > filter(const boost::function< bool(Key)> &filterFcn)
size_t iterations() const
return number of iterations in current optimizer state