32 template<
typename Calibration>
106 const Point3& upVector,
const Calibration&
K = Calibration()) {
116 *H1 << I_6x6, MatrixK6::Zero();
120 *H2 << Matrix6K::Zero(), MatrixK::Identity();
132 K_ = Calibration(v.tail<DimK>());
151 void print(
const std::string&
s =
"PinholeCamera")
const override {
153 K_.print(
s +
".calibration");
172 H->template block<6, 6>(0, 0) = I_6x6;
200 if ((
size_t) d.size() == 6)
229 template<
class POINT>
236 Dcamera ? &Dcal : 0);
238 *Dcamera <<
Dpose, Dcal;
264 *Dcamera << Dpose_, Eigen::Matrix<double, 1, DimK>::Zero();
278 *Dcamera << Dpose_, Eigen::Matrix<double, 1, DimK>::Zero();
287 template<
class CalibrationB>
291 Matrix16 Dcamera_, Dother_;
293 Dother ? &Dother_ : 0);
295 *Dcamera << Dcamera_, Eigen::Matrix<double, 1, DimK>::Zero();
299 Dother->template block<1, 6>(0, 0) = Dother_;
312 return range(camera.
pose(), Dcamera, Dother);
318 friend class boost::serialization::access;
319 template<
class Archive>
322 & boost::serialization::make_nvp(
"PinholeBaseK",
323 boost::serialization::base_object<Base>(*
this));
324 ar & BOOST_SERIALIZATION_NVP(K_);
333 template <
typename Calibration>
337 template <
typename Calibration>
342 template <
typename Calibration,
typename T>
Pinhole camera with known calibration.
static PinholeCamera Level(const Calibration &K, const Pose2 &pose2, double height)
Point2 _project2(const POINT &pw, OptionalJacobian< 2, dimension > Dcamera, OptionalJacobian< 2, FixedDimension< POINT >::value > Dpoint) const
Both ManifoldTraits and Testable.
Point2 project2(const Point3 &pw, OptionalJacobian< 2, dimension > Dcamera=boost::none, OptionalJacobian< 2, 3 > Dpoint=boost::none) const
project a 3D point from world coordinates into the image
static PinholeCamera Lookat(const Point3 &eye, const Point3 &target, const Point3 &upVector, const Calibration &K=Calibration())
const Pose3 & pose() const
return pose
virtual void print(const std::string &s="PinholeBase") const
print
PinholeBaseK< Calibration > Base
base class has 3D pose as private member
Eigen::Matrix< double, dimension, 1 > VectorK6
PinholeCamera(const Pose3 &pose, const Calibration &K)
Give fixed size dimension of a type, fails at compile time if dynamic.
static Pose3 LookatPose(const Point3 &eye, const Point3 &target, const Point3 &upVector)
static Pose3 LevelPose(const Pose2 &pose2, double height)
static Cal3_S2 K(500, 500, 0.1, 640/2, 480/2)
Pose2 T2(M_PI/2.0, Point2(0.0, 2.0))
PinholeCamera retract(const Vector &d) const
move a cameras according to d
set noclip points set clip one set noclip two set bar set border lt lw set xdata set ydata set zdata set x2data set y2data set boxwidth set dummy y set format x g set format y g set format x2 g set format y2 g set format z g set angles radians set nogrid set key title set key left top Right noreverse box linetype linewidth samplen spacing width set nolabel set noarrow set nologscale set logscale x set set pointsize set encoding default set nopolar set noparametric set set set set surface set nocontour set clabel set mapping cartesian set nohidden3d set cntrparam order set cntrparam linear set cntrparam levels auto set cntrparam points set size set set xzeroaxis lt lw set x2zeroaxis lt lw set yzeroaxis lt lw set y2zeroaxis lt lw set tics in set ticslevel set tics set mxtics default set mytics default set mx2tics default set my2tics default set xtics border mirror norotate autofreq set ytics border mirror norotate autofreq set ztics border nomirror norotate autofreq set nox2tics set noy2tics set timestamp bottom norotate set rrange[*:*] noreverse nowriteback set trange[*:*] noreverse nowriteback set urange[*:*] noreverse nowriteback set vrange[*:*] noreverse nowriteback set xlabel matrix size set x2label set timefmt d m y n H
const Calibration & calibration() const override
return calibration
const Pose3 & pose() const
return pose, constant version
double range(const Point3 &point, OptionalJacobian< 1, dimension > Dcamera=boost::none, OptionalJacobian< 1, 3 > Dpoint=boost::none) const
Eigen::Matrix< double, 2, DimK > Matrix2K
Represents a 3D point on a unit sphere.
double range(const CalibratedCamera &camera, OptionalJacobian< 1, dimension > Dcamera=boost::none, OptionalJacobian< 1, 6 > Dother=boost::none) const
double range(const PinholeCamera< CalibrationB > &camera, OptionalJacobian< 1, dimension > Dcamera=boost::none, OptionalJacobian< 1, 6+CalibrationB::dimension > Dother=boost::none) const
PinholeCamera(const Vector &v)
Init from vector, can be 6D (default calibration) or dim.
static PinholeCamera identity()
for Canonical
bool equals(const Base &camera, double tol=1e-9) const
assert equality up to a tolerance
std::vector< Point2, Eigen::aligned_allocator< Point2 > > Point2Vector
bool equals(const PinholeBase &camera, double tol=1e-9) const
assert equality up to a tolerance
PinholeCamera(const Pose3 &pose)
~PinholeCamera() override
VectorK6 localCoordinates(const PinholeCamera &T2) const
return canonical coordinate
double range(const Point3 &point, OptionalJacobian< 1, 6 > Hself=boost::none, OptionalJacobian< 1, 3 > Hpoint=boost::none) const
Array< double, 1, 3 > e(1./3., 0.5, 2.)
static Matrix23 Dpoint(const Point2 &pn, double d, const Matrix3 &Rt)
static Matrix26 Dpose(const Point2 &pn, double d)
Class retract(const TangentVector &v) const
retract as required by manifold concept: applies v at *this
static PinholeCamera Create(const Pose3 &pose, const Calibration &K, OptionalJacobian< dimension, 6 > H1=boost::none, OptionalJacobian< dimension, DimK > H2=boost::none)
double range(const Pose3 &pose, OptionalJacobian< 1, dimension > Dcamera=boost::none, OptionalJacobian< 1, 6 > Dpose=boost::none) const
EIGEN_DEVICE_FUNC SegmentReturnType head(Index n)
This is the const version of head(Index).
void serialize(Archive &ar, const unsigned int)
Calibration K_
Calibration, part of class now.
Point2 project(const Point3 &pw, OptionalJacobian< 2, 6 > Dpose=boost::none, OptionalJacobian< 2, 3 > Dpoint=boost::none, OptionalJacobian< 2, DimK > Dcal=boost::none) const
project a 3D point from world coordinates into the image
Point2Vector MeasurementVector
#define GTSAM_MAKE_ALIGNED_OPERATOR_NEW
Point2 project2(const Unit3 &pw, OptionalJacobian< 2, dimension > Dcamera=boost::none, OptionalJacobian< 2, 2 > Dpoint=boost::none) const
project a point at infinity from world coordinates into the image
The matrix class, also used for vectors and row-vectors.
static const CalibratedCamera camera(kDefaultPose)
static PinholeCamera Level(const Pose2 &pose2, double height)
PinholeCamera::level with default calibration.
PinholeCamera(const Vector &v, const Vector &K)
Init from Vector and calibration.
const Pose3 & getPose(OptionalJacobian< 6, dimension > H) const
return pose, with derivative
void print(const std::string &s="PinholeCamera") const override
print
TangentVector localCoordinates(const Class &g) const
localCoordinates as required by manifold concept: finds tangent vector between *this and g ...