44 using namespace gtsam;
46 int main(
int argc,
char** argv){
59 cout <<
"Reading calibration info" << endl;
60 ifstream calibration_file(calibration_loc.c_str());
63 calibration_file >> fx >> fy >> s >> u0 >> v0 >>
b;
66 cout <<
"Reading camera poses" << endl;
67 ifstream pose_file(pose_loc.c_str());
72 while (pose_file >> pose_index) {
73 for (
int i = 0;
i < 16;
i++)
74 pose_file >> m.
data()[
i];
83 double uL, uR,
v,
X,
Y,
Z;
84 ifstream factor_file(factor_loc.c_str());
85 cout <<
"Reading stereo factors" << endl;
92 while (factor_file >> pose_index >> landmark_key >> uL >> uR >> v >> X >> Y >> Z) {
94 if(current_l != landmark_key) {
97 current_l = landmark_key;
99 factor->add(
Point2(uL,v), pose_index);
109 params.verbosityLM = LevenbergMarquardtParams::TRYLAMBDA;
110 params.verbosity = NonlinearOptimizerParams::ERROR;
112 cout <<
"Optimizing" << endl;
117 cout <<
"Final result sample:" << endl;
119 pose_values.
print(
"Final camera poses:\n");
Smart factor on poses, assuming camera calibration is fixed.
virtual const Values & optimize()
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
IsDerived< DERIVEDFACTOR > push_back(std::shared_ptr< DERIVEDFACTOR > factor)
Add a factor directly using a shared_ptr.
static Cal3_S2 K(500, 500, 0.1, 640/2, 480/2)
NonlinearFactorGraph graph
static const SmartProjectionParams params
void print(const std::string &str="", const KeyFormatter &keyFormatter=DefaultKeyFormatter) const
std::shared_ptr< Cal3_S2 > shared_ptr
SmartProjectionPoseFactor< Cal3_S2 > SmartFactor
Array< int, Dynamic, 1 > v
A nonlinear optimizer that uses the Levenberg-Marquardt trust-region scheme.
Values allPose3s(const Values &values)
Extract all Pose3 values.
The most common 5DOF 3D->2D calibration.
std::shared_ptr< Isotropic > shared_ptr
GTSAM_EXPORT std::string findExampleDataFile(const std::string &name)
The most common 5DOF 3D->2D calibration + Stereo baseline.
int main(int argc, char **argv)
void insert(Key j, const Value &val)
The matrix class, also used for vectors and row-vectors.
std::shared_ptr< This > shared_ptr
shorthand for a smart pointer to a factor
utility functions for loading datasets