SFMdata.h
Go to the documentation of this file.
1 /* ----------------------------------------------------------------------------
2 
3  * GTSAM Copyright 2010, Georgia Tech Research Corporation,
4  * Atlanta, Georgia 30332-0415
5  * All Rights Reserved
6  * Authors: Frank Dellaert, et al. (see THANKS for the full author list)
7 
8  * See LICENSE for the license information
9 
10  * -------------------------------------------------------------------------- */
11 
25 // As this is a full 3D problem, we will use Pose3 variables to represent the camera
26 // positions and Point3 variables (x, y, z) to represent the landmark coordinates.
27 // Camera observations of landmarks (i.e. pixel coordinates) will be stored as Point2 (x, y).
28 // We will also need a camera object to hold calibration information and perform projections.
29 #include <gtsam/geometry/Pose3.h>
30 #include <gtsam/geometry/Point3.h>
31 
32 // We will also need a camera object to hold calibration information and perform projections.
34 #include <gtsam/geometry/Cal3_S2.h>
35 
36 /* ************************************************************************* */
37 std::vector<gtsam::Point3> createPoints() {
38 
39  // Create the set of ground-truth landmarks
40  std::vector<gtsam::Point3> points;
41  points.push_back(gtsam::Point3(10.0,10.0,10.0));
42  points.push_back(gtsam::Point3(-10.0,10.0,10.0));
43  points.push_back(gtsam::Point3(-10.0,-10.0,10.0));
44  points.push_back(gtsam::Point3(10.0,-10.0,10.0));
45  points.push_back(gtsam::Point3(10.0,10.0,-10.0));
46  points.push_back(gtsam::Point3(-10.0,10.0,-10.0));
47  points.push_back(gtsam::Point3(-10.0,-10.0,-10.0));
48  points.push_back(gtsam::Point3(10.0,-10.0,-10.0));
49 
50  return points;
51 }
52 
53 /* ************************************************************************* */
54 std::vector<gtsam::Pose3> createPoses(
56  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)))),
57  int steps = 8) {
58 
59  // Create the set of ground-truth poses
60  // Default values give a circular trajectory, radius 30 at pi/4 intervals, always facing the circle center
61  std::vector<gtsam::Pose3> poses;
62  int i = 1;
63  poses.push_back(init);
64  for(; i < steps; ++i) {
65  poses.push_back(poses[i-1].compose(delta));
66  }
67 
68  return poses;
69 }
#define M_PI
Definition: main.h:78
static Rot3 Ypr(double y, double p, double r, OptionalJacobian< 3, 1 > Hy=boost::none, OptionalJacobian< 3, 1 > Hp=boost::none, OptionalJacobian< 3, 1 > Hr=boost::none)
Definition: Rot3.h:199
T compose(const T &t1, const T &t2)
Definition: lieProxies.h:39
std::vector< gtsam::Point3 > createPoints()
Definition: SFMdata.h:37
Base class for all pinhole cameras.
std::vector< gtsam::Pose3 > createPoses(const gtsam::Pose3 &init=gtsam::Pose3(gtsam::Rot3::Ypr(M_PI/2, 0,-M_PI/2), gtsam::Point3(30, 0, 0)), 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)))), int steps=8)
Definition: SFMdata.h:54
3D Point
EIGEN_DEVICE_FUNC const SinReturnType sin() const
Vector3 Point3
Definition: Point3.h:35
3D Pose
The most common 5DOF 3D->2D calibration.


gtsam
Author(s):
autogenerated on Sat May 8 2021 02:44:01