diff --git a/examples/StereoVOExample.cpp b/examples/StereoVOExample.cpp new file mode 100644 index 000000000..8a04d13a3 --- /dev/null +++ b/examples/StereoVOExample.cpp @@ -0,0 +1,75 @@ +/* ---------------------------------------------------------------------------- + + * GTSAM Copyright 2010, Georgia Tech Research Corporation, + * Atlanta, Georgia 30332-0415 + * All Rights Reserved + * Authors: Frank Dellaert, et al. (see THANKS for the full author list) + + * See LICENSE for the license information + + * -------------------------------------------------------------------------- */ + +/** + * @file SteroVOExample.cpp + * @brief A stereo visual odometry example + * @date May 25, 2014 + * @author Stephen Camp + */ + +/** + * A 3D stereo visual odometry example + * - robot starts at origin + * -moves forward 1 meter + * -takes stereo readings on three landmarks + */ + +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + + + +using namespace std; +using namespace gtsam; + +int main(int argc, char** argv){ + //create graph object, add first pose at origin with key '1' + NonlinearFactorGraph graph; + Pose3 first_pose = Pose3(); + graph.push_back(NonlinearEquality(1, first_pose)); + + //create factor noise model with 3 sigmas of value 1 + const noiseModel::Isotropic::shared_ptr model = noiseModel::Isotropic::Sigma(3,1); + //create stereo camera calibration object with .2m between cameras + const Cal3_S2Stereo::shared_ptr K(new Cal3_S2Stereo(1000, 1000, 0, 320, 240, 0.2)); + //create and add stereo factors between first pose (key value 1) and the three landmarks + graph.push_back(GenericStereoFactor(StereoPoint2(520, 480, 440), model, 1, 3, K)); + graph.push_back(GenericStereoFactor(StereoPoint2(120, 80, 440), model, 1, 4, K)); + graph.push_back(GenericStereoFactor(StereoPoint2(320, 280, 140), model, 1, 5, K)); + //create and add stereo factors between second pose and the three landmarks + graph.push_back(GenericStereoFactor(StereoPoint2(570, 520, 490), model, 2, 3, K)); + graph.push_back(GenericStereoFactor(StereoPoint2(70, 20, 490), model, 2, 4, K)); + graph.push_back(GenericStereoFactor(StereoPoint2(320, 270, 115), model, 2, 5, K)); + //create Values object to contain initial estimates of camera poses and landmark locations + Values initial_estimate = Values(); + //create and add iniital estimates + initial_estimate.insert(1, first_pose); + initial_estimate.insert(2, Pose3(Rot3(), Point3(0.1, -0.1, 1.1))); + initial_estimate.insert(3, Point3(1, 1, 5)); + initial_estimate.insert(4, Point3(-1, 1, 5)); + initial_estimate.insert(5, Point3(0, -0.5, 5)); + //create Levenberg-Marquardt optimizer for resulting factor graph, optimize + LevenbergMarquardtOptimizer optimizer = LevenbergMarquardtOptimizer(graph, initial_estimate); + Values result = optimizer.optimize(); + + result.print("Final result:\n"); + + return 0; +} \ No newline at end of file diff --git a/examples/StereoVOExample_large.cpp b/examples/StereoVOExample_large.cpp new file mode 100644 index 000000000..c661967c0 --- /dev/null +++ b/examples/StereoVOExample_large.cpp @@ -0,0 +1,112 @@ +/* ---------------------------------------------------------------------------- + +* GTSAM Copyright 2010, Georgia Tech Research Corporation, +* Atlanta, Georgia 30332-0415 +* All Rights Reserved +* Authors: Frank Dellaert, et al. (see THANKS for the full author list) + +* See LICENSE for the license information + +* -------------------------------------------------------------------------- */ + +/** +* @file SteroVOExample.cpp +* @brief A stereo visual odometry example +* @date May 25, 2014 +* @author Stephen Camp +*/ + + +/** + * A 3D stereo visual odometry example + * - robot starts at origin + * -moves forward, taking periodic stereo measurements + * -takes stereo readings of many landmarks + */ + +#include +#include +#include +#include +#include +#include +#include + +#include +#include +#include + +#include +#include +#include +#include + +using namespace std; +using namespace gtsam; + +int main(int argc, char** argv){ + + NonlinearFactorGraph graph; + const noiseModel::Isotropic::shared_ptr model = noiseModel::Isotropic::Sigma(3,1); + Values initial_estimate = Values(); + vector read_vector; + string read_string, parse_string; + + string data_folder = "C:/Users/Stephen/Documents/Borg/gtsam/Examples/Data/"; + string calibration_loc = data_folder + "VO_calibration.txt"; + string pose_loc = data_folder + "VO_camera_poses_large.txt"; + string factor_loc = data_folder + "VO_stereo_factors_large.txt"; + + //read camera calibration info from file + double fx,fy,s,u,v,b; + ifstream calibration_file(calibration_loc); + cout << "Reading calibration info" << endl; + calibration_file >> fx >> fy >> s >> u >> v >> b; + //create stereo camera calibration object + const Cal3_S2Stereo::shared_ptr K(new Cal3_S2Stereo(fx,fy,s,u,v,b)); + + ifstream pose_file(pose_loc); + cout << "Reading camera poses" << endl; + int pose_id; + MatrixRowMajor m(4,4); + //read camera pose parameters and use to make initial estimates of camera poses + while (pose_file >> pose_id) { + for (int i = 0; i < 16; i++) { + pose_file >> m.data()[i]; + } + initial_estimate.insert(Symbol('x', pose_id), Pose3(m)); + } + + double x, l, uL, uR, v, X, Y, Z; + ifstream factor_file(factor_loc); + cout << "Reading stereo factors" << endl; + //read stereo measurement details from file and use to create and add GenericStereoFactor objects to the graph representation + while (factor_file >> x >> l >> uL >> uR >> v >> X >> Y >> Z) { + graph.push_back( + GenericStereoFactor(StereoPoint2(uL, uR, v), model, + Symbol('x', x), Symbol('l', l), K)); + //if the landmark variable included in this factor has not yet been added to the initial variable value estimate, add it + if(!initial_estimate.exists(Symbol('l',l))){ + Pose3 camPose = initial_estimate.at(Symbol('x', x)); + //transform_from() transforms the input Point3 from the camera pose space, camPose, to the global space + Point3 worldPoint = camPose.transform_from(Point3(X,Y,Z)); + initial_estimate.insert(Symbol('l',l),worldPoint); + } + } + + Pose3 first_pose = initial_estimate.at(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 + graph.push_back(NonlinearEquality(Symbol('x',1),first_pose)); + + cout << "Optimizing" << endl; + //create Levenberg-Marquardt optimizer to solve the initial factor graph estimate + LevenbergMarquardtOptimizer optimizer = LevenbergMarquardtOptimizer(graph, initial_estimate); + Values result = optimizer.optimize(); + + cout << "Final result sample:" << endl; + Values pose_values = result.filter(); + pose_values.print("Final camera poses:\n"); + + return 0; +} \ No newline at end of file