40#ifdef GTSAM_ALLOW_DEPRECATED_SINCE_V42
48 typedef boost::shared_ptr<SimpleCamera> shared_ptr;
61 explicit SimpleCamera(
const Pose3& pose) :
81 static SimpleCamera Level(
const Cal3_S2 &K,
const Pose2& pose2,
83 return SimpleCamera(Base::LevelPose(pose2, height), K);
87 static SimpleCamera Level(
const Pose2& pose2,
double height) {
88 return SimpleCamera::Level(
Cal3_S2(), pose2, height);
100 static SimpleCamera Lookat(
const Point3& eye,
const Point3& target,
102 return SimpleCamera(Base::LookatPose(eye, target, upVector), K);
110 explicit SimpleCamera(
const Vector &v) :
115 SimpleCamera(
const Vector &v,
const Vector &K) :
120 SimpleCamera::shared_ptr clone()
const {
return boost::make_shared<SimpleCamera>(*
this); }
128 SimpleCamera retract(
const Vector& d)
const {
129 if ((
size_t) d.size() == 6)
130 return SimpleCamera(this->pose().retract(d), calibration());
132 return SimpleCamera(this->pose().retract(d.head(6)),
133 calibration().retract(d.tail(calibration().dim())));
141GTSAM_EXPORT SimpleCamera simpleCamera(
const Matrix34& P);
145struct traits<SimpleCamera> :
public internal::Manifold<SimpleCamera> {};
148struct traits<const SimpleCamera> :
public internal::Manifold<SimpleCamera> {};
152struct Range<SimpleCamera, T> : HasRange<SimpleCamera, T, double> {};
Calibration used by Bundler.
The most common 5DOF 3D->2D calibration.
Calibration of a fisheye camera.
Unified Calibration Model, see Mei07icra for details.
Base class for all pinhole cameras.
Calibration of a camera with radial distortion, calculations in base class Cal3DS2_Base.
Global functions in a separate testing namespace.
Definition chartTesting.h:28
gtsam::PinholeCamera< gtsam::Cal3_S2 > PinholeCameraCal3_S2
Convenient aliases for Pinhole camera classes with different calibrations.
Definition SimpleCamera.h:34
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
The most common 5DOF 3D->2D calibration.
Definition Cal3_S2.h:34
A pinhole camera class that has a Pose3 and a Calibration.
Definition PinholeCamera.h:33
A 2D pose (Point2,Rot2)
Definition Pose2.h:36
A 3D pose (R,t) : (Rot3,Point3)
Definition Pose3.h:37