42 std::vector<gtsam::Point3> points;
56std::vector<gtsam::Pose3> createPoses(
63 std::vector<gtsam::Pose3> poses;
65 poses.push_back(init);
66 for(; i < steps; ++i) {
67 poses.push_back(poses[i-1].compose(delta));
The most common 5DOF 3D->2D calibration.
Base class for all pinhole cameras.
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