StereoVOExample.cpp 2.9 KB

1234567891011121314151617181920212223242526272829303132333435363738394041424344454647484950515253545556575859606162636465666768697071727374757677
  1. /* ----------------------------------------------------------------------------
  2. * GTSAM Copyright 2010, Georgia Tech Research Corporation,
  3. * Atlanta, Georgia 30332-0415
  4. * All Rights Reserved
  5. * Authors: Frank Dellaert, et al. (see THANKS for the full author list)
  6. * See LICENSE for the license information
  7. * -------------------------------------------------------------------------- */
  8. /**
  9. * @file StereoVOExample.cpp
  10. * @brief A stereo visual odometry example
  11. * @date May 25, 2014
  12. * @author Stephen Camp
  13. */
  14. /**
  15. * A 3D stereo visual odometry example
  16. * - robot starts at origin
  17. * -moves forward 1 meter
  18. * -takes stereo readings on three landmarks
  19. */
  20. #include <gtsam/geometry/Pose3.h>
  21. #include <gtsam/geometry/Cal3_S2Stereo.h>
  22. #include <gtsam/nonlinear/Values.h>
  23. #include <gtsam/nonlinear/NonlinearEquality.h>
  24. #include <gtsam/nonlinear/NonlinearFactorGraph.h>
  25. #include <gtsam/nonlinear/LevenbergMarquardtOptimizer.h>
  26. #include <gtsam/slam/StereoFactor.h>
  27. using namespace std;
  28. using namespace gtsam;
  29. int main(int argc, char** argv) {
  30. // create graph object, add first pose at origin with key '1'
  31. NonlinearFactorGraph graph;
  32. Pose3 first_pose;
  33. graph.emplace_shared<NonlinearEquality<Pose3> >(1, Pose3());
  34. // create factor noise model with 3 sigmas of value 1
  35. const auto model = noiseModel::Isotropic::Sigma(3, 1);
  36. // create stereo camera calibration object with .2m between cameras
  37. const Cal3_S2Stereo::shared_ptr K(
  38. new Cal3_S2Stereo(1000, 1000, 0, 320, 240, 0.2));
  39. //create and add stereo factors between first pose (key value 1) and the three landmarks
  40. graph.emplace_shared<GenericStereoFactor<Pose3,Point3> >(StereoPoint2(520, 480, 440), model, 1, 3, K);
  41. graph.emplace_shared<GenericStereoFactor<Pose3,Point3> >(StereoPoint2(120, 80, 440), model, 1, 4, K);
  42. graph.emplace_shared<GenericStereoFactor<Pose3,Point3> >(StereoPoint2(320, 280, 140), model, 1, 5, K);
  43. //create and add stereo factors between second pose and the three landmarks
  44. graph.emplace_shared<GenericStereoFactor<Pose3,Point3> >(StereoPoint2(570, 520, 490), model, 2, 3, K);
  45. graph.emplace_shared<GenericStereoFactor<Pose3,Point3> >(StereoPoint2(70, 20, 490), model, 2, 4, K);
  46. graph.emplace_shared<GenericStereoFactor<Pose3,Point3> >(StereoPoint2(320, 270, 115), model, 2, 5, K);
  47. // create Values object to contain initial estimates of camera poses and
  48. // landmark locations
  49. Values initial_estimate;
  50. // create and add iniital estimates
  51. initial_estimate.insert(1, first_pose);
  52. initial_estimate.insert(2, Pose3(Rot3(), Point3(0.1, -0.1, 1.1)));
  53. initial_estimate.insert(3, Point3(1, 1, 5));
  54. initial_estimate.insert(4, Point3(-1, 1, 5));
  55. initial_estimate.insert(5, Point3(0, -0.5, 5));
  56. // create Levenberg-Marquardt optimizer for resulting factor graph, optimize
  57. LevenbergMarquardtOptimizer optimizer(graph, initial_estimate);
  58. Values result = optimizer.optimize();
  59. result.print("Final result:\n");
  60. return 0;
  61. }