40 std::vector<gtsam::Point3> points;
61 std::vector<gtsam::Pose3> poses;
63 poses.push_back(
init);
64 for(; i < steps; ++
i) {
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)
T compose(const T &t1, const T &t2)
std::vector< gtsam::Point3 > createPoints()
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)
EIGEN_DEVICE_FUNC const SinReturnType sin() const
The most common 5DOF 3D->2D calibration.