46 using namespace gtsam;
49 int main(
int argc,
char** argv){
53 bool output_poses =
true;
54 string poseOutput(
"../../../examples/data/optimized_poses.txt");
55 string init_poseOutput(
"../../../examples/data/initial_poses.txt");
59 ofstream pose3Out, init_pose3Out;
61 bool add_initial_noise =
true;
69 cout <<
"Reading calibration info" << endl;
70 ifstream calibration_file(calibration_loc.c_str());
73 calibration_file >> fx >> fy >> s >> u0 >> v0 >>
b;
76 cout <<
"Reading camera poses" << endl;
77 ifstream pose_file(pose_loc.c_str());
82 while (pose_file >> pose_id) {
83 for (
int i = 0;
i < 16;
i++) {
84 pose_file >> m.
data()[
i];
86 if(add_initial_noise){
87 m(1,3) += (pose_id % 10)/10.0;
92 const auto initialPoses = initial_estimate.
extract<
Pose3>();
94 init_pose3Out.open(init_poseOutput.c_str(),
ios::out);
95 for (
size_t i = 1;
i <= initialPoses.size();
i++) {
98 << initialPoses.at(
X(
i)).matrix().format(
108 double uL, uR,
v, _X,
Y,
Z;
109 ifstream factor_file(factor_loc.c_str());
110 cout <<
"Reading stereo factors" << endl;
115 size_t current_l = 3;
117 while (factor_file >> x >> l >> uL >> uR >> v >> _X >> Y >> Z) {
134 params.verbosityLM = LevenbergMarquardtParams::TRYLAMBDA;
135 params.verbosity = NonlinearOptimizerParams::ERROR;
137 cout <<
"Optimizing" << endl;
142 cout <<
"Final result sample:" << endl;
144 pose_values.
print(
"Final camera poses:\n");
147 pose3Out.open(poseOutput.c_str(),
ios::out);
148 for(
size_t i = 1;
i<=pose_values.
size();
i++){
152 cout <<
"Writing output" << endl;
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
std::ofstream out("Result.txt")
IsDerived< DERIVEDFACTOR > push_back(std::shared_ptr< DERIVEDFACTOR > factor)
Add a factor directly using a shared_ptr.
std::map< Key, ValueType > extract(const std::function< bool(Key)> &filterFcn=&_truePredicate< Key >) const
static Cal3_S2 K(500, 500, 0.1, 640/2, 480/2)
NonlinearFactorGraph graph
Smart stereo factor on poses, assuming camera calibration is fixed.
static const SmartProjectionParams params
void print(const std::string &str="", const KeyFormatter &keyFormatter=DefaultKeyFormatter) const
static const Line3 l(Rot3(), 1, 1)
The most common 5DOF 3D->2D calibration, stereo version.
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.
std::shared_ptr< Isotropic > shared_ptr
int main(int argc, char **argv)
std::shared_ptr< Cal3_S2Stereo > shared_ptr
GTSAM_EXPORT std::string findExampleDataFile(const std::string &name)
The most common 5DOF 3D->2D calibration + Stereo baseline.
void insert(Key j, const Value &val)
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.
std::shared_ptr< This > shared_ptr
shorthand for a smart pointer to a factor
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