gtsam 4.2
gtsam
Loading...
Searching...
No Matches
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
17
24
25#pragma once
26
27// As this is a full 3D problem, we will use Pose3 variables to represent the camera
28// positions and Point3 variables (x, y, z) to represent the landmark coordinates.
29// Camera observations of landmarks (i.e. pixel coordinates) will be stored as Point2 (x, y).
30// We will also need a camera object to hold calibration information and perform projections.
33
34// We will also need a camera object to hold calibration information and perform projections.
37
38/* ************************************************************************* */
39std::vector<gtsam::Point3> createPoints() {
40
41 // Create the set of ground-truth landmarks
42 std::vector<gtsam::Point3> points;
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 points.push_back(gtsam::Point3(-10.0,-10.0,-10.0));
50 points.push_back(gtsam::Point3(10.0,-10.0,-10.0));
51
52 return points;
53}
54
55/* ************************************************************************* */
56std::vector<gtsam::Pose3> createPoses(
57 const gtsam::Pose3& init = gtsam::Pose3(gtsam::Rot3::Ypr(M_PI/2,0,-M_PI/2), gtsam::Point3(30, 0, 0)),
58 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)))),
59 int steps = 8) {
60
61 // Create the set of ground-truth poses
62 // Default values give a circular trajectory, radius 30 at pi/4 intervals, always facing the circle center
63 std::vector<gtsam::Pose3> poses;
64 int i = 1;
65 poses.push_back(init);
66 for(; i < steps; ++i) {
67 poses.push_back(poses[i-1].compose(delta));
68 }
69
70 return poses;
71}
The most common 5DOF 3D->2D calibration.
3D Point
Base class for all pinhole cameras.
3D Pose
Vector3 Point3
As of GTSAM 4, in order to make GTSAM more lean, it is now possible to just typedef Point3 to Vector3...
Definition Point3.h:36
A 3D pose (R,t) : (Rot3,Point3).
Definition Pose3.h:37
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)
Returns rotation nRb from body to nav frame.
Definition Rot3.h:196
std::vector< gtsam::Point3 > createPoints()
A structure-from-motion example with landmarks, default function arguments give.
Definition SFMdata.h:39