45 using namespace gtsam;
47 int main(
int argc,
char** argv){
51 bool output_poses =
true;
52 string poseOutput(
"../../../examples/data/optimized_poses.txt");
53 string init_poseOutput(
"../../../examples/data/initial_poses.txt");
57 ofstream pose3Out, init_pose3Out;
59 bool add_initial_noise =
true;
67 cout <<
"Reading calibration info" << endl;
68 ifstream calibration_file(calibration_loc.c_str());
71 calibration_file >> fx >> fy >> s >> u0 >> v0 >>
b;
74 cout <<
"Reading camera poses" << endl;
75 ifstream pose_file(pose_loc.c_str());
80 while (pose_file >> pose_id) {
81 for (
int i = 0;
i < 16;
i++) {
82 pose_file >> m.
data()[
i];
84 if(add_initial_noise){
85 m(1,3) += (pose_id % 10)/10.0;
92 init_pose3Out.open(init_poseOutput.c_str(), ios::out);
93 for (
size_t i = 1;
i <= initial_pose_values.
size();
i++) {
106 double uL, uR,
v,
X,
Y,
Z;
107 ifstream factor_file(factor_loc.c_str());
108 cout <<
"Reading stereo factors" << endl;
113 size_t current_l = 3;
115 while (factor_file >> x >> l >> uL >> uR >> v >> X >> Y >> Z) {
132 params.verbosityLM = LevenbergMarquardtParams::TRYLAMBDA;
133 params.verbosity = NonlinearOptimizerParams::ERROR;
135 cout <<
"Optimizing" << endl;
140 cout <<
"Final result sample:" << endl;
142 pose_values.
print(
"Final camera poses:\n");
145 pose3Out.open(poseOutput.c_str(),ios::out);
146 for(
size_t i = 1;
i<=pose_values.
size();
i++){
150 cout <<
"Writing output" << endl;
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
Smart stereo factor on poses, assuming camera calibration is fixed.
string findExampleDataFile(const string &name)
IsDerived< DERIVEDFACTOR > emplace_shared(Args &&...args)
Emplace a shared pointer to factor of given type.
static const Line3 l(Rot3(), 1, 1)
boost::shared_ptr< Cal3_S2Stereo > shared_ptr
const ValueType at(Key j) const
SmartProjectionPoseFactor< Cal3_S2 > SmartFactor
A nonlinear optimizer that uses the Levenberg-Marquardt trust-region scheme.
static SmartStereoProjectionParams params
int main(int argc, char **argv)
void print(const std::string &str="", const KeyFormatter &keyFormatter=DefaultKeyFormatter) const
The most common 5DOF 3D->2D calibration + Stereo baseline.
boost::shared_ptr< Isotropic > shared_ptr
boost::shared_ptr< This > shared_ptr
shorthand for a smart pointer to a factor
Map< Matrix< T, Dynamic, Dynamic, ColMajor >, 0, OuterStride<> > matrix(T *data, int rows, int cols, int stride)
The matrix class, also used for vectors and row-vectors.
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
utility functions for loading datasets
Filtered< Value > filter(const boost::function< bool(Key)> &filterFcn)