minor cleanup and comments
parent
fe5953d195
commit
182fd06cb8
|
@ -25,45 +25,41 @@
|
||||||
*/
|
*/
|
||||||
|
|
||||||
#include <gtsam/geometry/Pose3.h>
|
#include <gtsam/geometry/Pose3.h>
|
||||||
#include <gtsam/inference/Key.h>
|
#include <gtsam/geometry/Cal3_S2Stereo.h>
|
||||||
|
#include <gtsam/nonlinear/Values.h>
|
||||||
|
#include <gtsam/nonlinear/NonlinearEquality.h>
|
||||||
#include <gtsam/nonlinear/NonlinearFactorGraph.h>
|
#include <gtsam/nonlinear/NonlinearFactorGraph.h>
|
||||||
#include <gtsam/nonlinear/LevenbergMarquardtOptimizer.h>
|
#include <gtsam/nonlinear/LevenbergMarquardtOptimizer.h>
|
||||||
#include <gtsam/nonlinear/Marginals.h>
|
|
||||||
#include <gtsam/nonlinear/Values.h>
|
|
||||||
#include <gtsam/geometry/Cal3_S2Stereo.h>
|
|
||||||
|
|
||||||
#include <gtsam/slam/StereoFactor.h>
|
|
||||||
#include <gtsam/nonlinear/NonlinearEquality.h>
|
|
||||||
#include <gtsam/inference/Symbol.h>
|
#include <gtsam/inference/Symbol.h>
|
||||||
|
#include <gtsam/slam/StereoFactor.h>
|
||||||
|
#include <gtsam/slam/dataset.h>
|
||||||
|
|
||||||
|
#include <string>
|
||||||
#include <fstream>
|
#include <fstream>
|
||||||
#include <iostream>
|
#include <iostream>
|
||||||
#include <sstream>
|
|
||||||
#include <string>
|
|
||||||
|
|
||||||
using namespace std;
|
using namespace std;
|
||||||
using namespace gtsam;
|
using namespace gtsam;
|
||||||
|
|
||||||
int main(int argc, char** argv){
|
int main(int argc, char** argv){
|
||||||
|
|
||||||
|
Values initial_estimate;
|
||||||
NonlinearFactorGraph graph;
|
NonlinearFactorGraph graph;
|
||||||
const noiseModel::Isotropic::shared_ptr model = noiseModel::Isotropic::Sigma(3,1);
|
const noiseModel::Isotropic::shared_ptr model = noiseModel::Isotropic::Sigma(3,1);
|
||||||
Values initial_estimate = Values();
|
|
||||||
vector<double> read_vector;
|
|
||||||
string read_string, parse_string;
|
|
||||||
|
|
||||||
string data_folder = "C:/Users/Stephen/Documents/Borg/gtsam/Examples/Data/";
|
string calibration_loc = findExampleDataFile("VO_calibration.txt");
|
||||||
string calibration_loc = data_folder + "VO_calibration.txt";
|
string pose_loc = findExampleDataFile("VO_camera_poses_large.txt");
|
||||||
string pose_loc = data_folder + "VO_camera_poses_large.txt";
|
string factor_loc = findExampleDataFile("VO_stereo_factors_large.txt");
|
||||||
string factor_loc = data_folder + "VO_stereo_factors_large.txt";
|
|
||||||
|
|
||||||
//read camera calibration info from file
|
//read camera calibration info from file
|
||||||
double fx,fy,s,u,v,b;
|
// focal lengths fx, fy, skew s, principal point u0, v0, baseline b
|
||||||
|
double fx, fy, s, u0, v0, b;
|
||||||
ifstream calibration_file(calibration_loc);
|
ifstream calibration_file(calibration_loc);
|
||||||
cout << "Reading calibration info" << endl;
|
cout << "Reading calibration info" << endl;
|
||||||
calibration_file >> fx >> fy >> s >> u >> v >> b;
|
calibration_file >> fx >> fy >> s >> u0 >> v0 >> b;
|
||||||
|
|
||||||
//create stereo camera calibration object
|
//create stereo camera calibration object
|
||||||
const Cal3_S2Stereo::shared_ptr K(new Cal3_S2Stereo(fx,fy,s,u,v,b));
|
const Cal3_S2Stereo::shared_ptr K(new Cal3_S2Stereo(fx,fy,s,u0,v0,b));
|
||||||
|
|
||||||
ifstream pose_file(pose_loc);
|
ifstream pose_file(pose_loc);
|
||||||
cout << "Reading camera poses" << endl;
|
cout << "Reading camera poses" << endl;
|
||||||
|
@ -77,7 +73,12 @@ int main(int argc, char** argv){
|
||||||
initial_estimate.insert(Symbol('x', pose_id), Pose3(m));
|
initial_estimate.insert(Symbol('x', pose_id), Pose3(m));
|
||||||
}
|
}
|
||||||
|
|
||||||
double x, l, uL, uR, v, X, Y, Z;
|
// camera and landmark keys
|
||||||
|
size_t x, l;
|
||||||
|
|
||||||
|
// pixel coordinates uL, uR, v (same for left/right images due to rectification)
|
||||||
|
// landmark coordinates X, Y, Z in camera frame, resulting from triangulation
|
||||||
|
double uL, uR, v, X, Y, Z;
|
||||||
ifstream factor_file(factor_loc);
|
ifstream factor_file(factor_loc);
|
||||||
cout << "Reading stereo factors" << endl;
|
cout << "Reading stereo factors" << endl;
|
||||||
//read stereo measurement details from file and use to create and add GenericStereoFactor objects to the graph representation
|
//read stereo measurement details from file and use to create and add GenericStereoFactor objects to the graph representation
|
||||||
|
@ -95,12 +96,13 @@ int main(int argc, char** argv){
|
||||||
}
|
}
|
||||||
|
|
||||||
Pose3 first_pose = initial_estimate.at<Pose3>(Symbol('x',1));
|
Pose3 first_pose = initial_estimate.at<Pose3>(Symbol('x',1));
|
||||||
first_pose.print("Check estimate poses:\n");
|
|
||||||
//constrain the first pose such that it cannot change from its original value during optimization
|
//constrain the first pose such that it cannot change from its original value during optimization
|
||||||
|
// NOTE: NonlinearEquality forces the optimizer to use QR rather than Cholesky
|
||||||
|
// QR is much slower than Cholesky, but numerically more stable
|
||||||
graph.push_back(NonlinearEquality<Pose3>(Symbol('x',1),first_pose));
|
graph.push_back(NonlinearEquality<Pose3>(Symbol('x',1),first_pose));
|
||||||
|
|
||||||
cout << "Optimizing" << endl;
|
cout << "Optimizing" << endl;
|
||||||
//create Levenberg-Marquardt optimizer to solve the initial factor graph estimate
|
//create Levenberg-Marquardt optimizer to optimize the factor graph
|
||||||
LevenbergMarquardtOptimizer optimizer = LevenbergMarquardtOptimizer(graph, initial_estimate);
|
LevenbergMarquardtOptimizer optimizer = LevenbergMarquardtOptimizer(graph, initial_estimate);
|
||||||
Values result = optimizer.optimize();
|
Values result = optimizer.optimize();
|
||||||
|
|
||||||
|
|
Loading…
Reference in New Issue