43 using namespace gtsam;
45 int main(
int argc,
char** argv){
58 cout <<
"Reading calibration info" << endl;
59 ifstream calibration_file(calibration_loc.c_str());
62 calibration_file >> fx >> fy >> s >> u0 >> v0 >>
b;
65 cout <<
"Reading camera poses" << endl;
66 ifstream pose_file(pose_loc.c_str());
71 while (pose_file >> pose_index) {
72 for (
int i = 0;
i < 16;
i++)
73 pose_file >> m.
data()[
i];
82 double uL, uR,
v,
X,
Y,
Z;
83 ifstream factor_file(factor_loc.c_str());
84 cout <<
"Reading stereo factors" << endl;
91 while (factor_file >> pose_index >> landmark_key >> uL >> uR >> v >> X >> Y >> Z) {
93 if(current_l != landmark_key) {
96 current_l = landmark_key;
98 factor->add(
Point2(uL,v), pose_index);
108 params.verbosityLM = LevenbergMarquardtParams::TRYLAMBDA;
109 params.verbosity = NonlinearOptimizerParams::ERROR;
111 cout <<
"Optimizing" << endl;
116 cout <<
"Final result sample:" << endl;
118 pose_values.
print(
"Final camera poses:\n");
Smart factor on poses, assuming camera calibration is fixed.
virtual const Values & optimize()
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)
IsDerived< DERIVEDFACTOR > push_back(boost::shared_ptr< DERIVEDFACTOR > factor)
Add a factor directly using a shared_ptr.
NonlinearFactorGraph graph
string findExampleDataFile(const string &name)
IsDerived< DERIVEDFACTOR > emplace_shared(Args &&...args)
Emplace a shared pointer to factor of given type.
const ValueType at(Key j) const
SmartProjectionPoseFactor< Cal3_S2 > SmartFactor
A nonlinear optimizer that uses the Levenberg-Marquardt trust-region scheme.
static SmartStereoProjectionParams params
void print(const std::string &str="", const KeyFormatter &keyFormatter=DefaultKeyFormatter) const
The most common 5DOF 3D->2D calibration + Stereo baseline.
int main(int argc, char **argv)
boost::shared_ptr< Isotropic > shared_ptr
boost::shared_ptr< This > shared_ptr
shorthand for a smart pointer to a factor
The matrix class, also used for vectors and row-vectors.
boost::shared_ptr< Cal3_S2 > shared_ptr
utility functions for loading datasets
Filtered< Value > filter(const boost::function< bool(Key)> &filterFcn)