SFMdata.h 2.7 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869
  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 SFMdata.h
  10. * @brief Simple example for the structure-from-motion problems
  11. * @author Duy-Nguyen Ta
  12. */
  13. /**
  14. * A structure-from-motion example with landmarks, default function arguments give
  15. * - The landmarks form a 10 meter cube
  16. * - The robot rotates around the landmarks, always facing towards the cube
  17. * Passing function argument allows to specificy an initial position, a pose increment and step count.
  18. */
  19. // As this is a full 3D problem, we will use Pose3 variables to represent the camera
  20. // positions and Point3 variables (x, y, z) to represent the landmark coordinates.
  21. // Camera observations of landmarks (i.e. pixel coordinates) will be stored as Point2 (x, y).
  22. // We will also need a camera object to hold calibration information and perform projections.
  23. #include <gtsam/geometry/Pose3.h>
  24. #include <gtsam/geometry/Point3.h>
  25. // We will also need a camera object to hold calibration information and perform projections.
  26. #include <gtsam/geometry/PinholeCamera.h>
  27. #include <gtsam/geometry/Cal3_S2.h>
  28. /* ************************************************************************* */
  29. std::vector<gtsam::Point3> createPoints() {
  30. // Create the set of ground-truth landmarks
  31. std::vector<gtsam::Point3> points;
  32. points.push_back(gtsam::Point3(10.0,10.0,10.0));
  33. points.push_back(gtsam::Point3(-10.0,10.0,10.0));
  34. points.push_back(gtsam::Point3(-10.0,-10.0,10.0));
  35. points.push_back(gtsam::Point3(10.0,-10.0,10.0));
  36. points.push_back(gtsam::Point3(10.0,10.0,-10.0));
  37. points.push_back(gtsam::Point3(-10.0,10.0,-10.0));
  38. points.push_back(gtsam::Point3(-10.0,-10.0,-10.0));
  39. points.push_back(gtsam::Point3(10.0,-10.0,-10.0));
  40. return points;
  41. }
  42. /* ************************************************************************* */
  43. std::vector<gtsam::Pose3> createPoses(
  44. const gtsam::Pose3& init = gtsam::Pose3(gtsam::Rot3::Ypr(M_PI/2,0,-M_PI/2), gtsam::Point3(30, 0, 0)),
  45. const gtsam::Pose3& delta = gtsam::Pose3(gtsam::Rot3::Ypr(0,-M_PI/4,0), gtsam::Point3(sin(M_PI/4)*30, 0, 30*(1-sin(M_PI/4)))),
  46. int steps = 8) {
  47. // Create the set of ground-truth poses
  48. // Default values give a circular trajectory, radius 30 at pi/4 intervals, always facing the circle center
  49. std::vector<gtsam::Pose3> poses;
  50. int i = 1;
  51. poses.push_back(init);
  52. for(; i < steps; ++i) {
  53. poses.push_back(poses[i-1].compose(delta));
  54. }
  55. return poses;
  56. }