Public Types | Private Types | Private Attributes | Static Private Attributes | List of all members
gtsam::PinholeCamera< Calibration > Class Template Reference

#include <PinholeCamera.h>

Inheritance diagram for gtsam::PinholeCamera< Calibration >:
Inheritance graph
[legend]

Public Types

enum  { dimension = 6 + DimK }
 
typedef Point2 Measurement
 
typedef Point2Vector MeasurementVector
 
- Public Types inherited from gtsam::PinholeBaseK< Calibration >
typedef Calibration CalibrationType
 
- Public Types inherited from gtsam::PinholeBase
typedef Point2 Measurement
 
typedef Point2Vector MeasurementVector
 
typedef Rot3 Rotation
 
typedef Point3 Translation
 

Private Types

typedef PinholeBaseK< Calibration > Base
 base class has 3D pose as private member More...
 

Private Attributes

Calibration K_
 Calibration, part of class now. More...
 

Static Private Attributes

static const int DimK = FixedDimension<Calibration>::value
 

Standard Constructors

 PinholeCamera ()
 
 PinholeCamera (const Pose3 &pose)
 
 PinholeCamera (const Pose3 &pose, const Calibration &K)
 

Named Constructors

static PinholeCamera Level (const Calibration &K, const Pose2 &pose2, double height)
 
static PinholeCamera Level (const Pose2 &pose2, double height)
 PinholeCamera::level with default calibration. More...
 
static PinholeCamera Lookat (const Point3 &eye, const Point3 &target, const Point3 &upVector, const Calibration &K=Calibration())
 
static PinholeCamera Create (const Pose3 &pose, const Calibration &K, OptionalJacobian< dimension, 6 > H1={}, OptionalJacobian< dimension, DimK > H2={})
 

Advanced Constructors

 PinholeCamera (const Vector &v)
 Init from vector, can be 6D (default calibration) or dim. More...
 
 PinholeCamera (const Vector &v, const Vector &K)
 Init from Vector and calibration. More...
 

Testable

bool equals (const Base &camera, double tol=1e-9) const
 assert equality up to a tolerance More...
 
void print (const std::string &s="PinholeCamera") const override
 print More...
 

Standard Interface

 ~PinholeCamera () override
 
const Pose3pose () const
 return pose More...
 
const Pose3getPose (OptionalJacobian< 6, dimension > H) const
 return pose, with derivative More...
 
const Calibration & calibration () const override
 return calibration More...
 

Manifold

typedef Eigen::Matrix< double, dimension, 1 > VectorK6
 
size_t dim () const
 
PinholeCamera retract (const Vector &d) const
 move a cameras according to d More...
 
VectorK6 localCoordinates (const PinholeCamera &T2) const
 return canonical coordinate More...
 
static size_t Dim ()
 
static PinholeCamera Identity ()
 for Canonical More...
 

Transformations and measurement functions

typedef Eigen::Matrix< double, 2, DimKMatrix2K
 
template<class POINT >
Point2 _project2 (const POINT &pw, OptionalJacobian< 2, dimension > Dcamera, OptionalJacobian< 2, FixedDimension< POINT >::value > Dpoint) const
 
Point2 project2 (const Point3 &pw, OptionalJacobian< 2, dimension > Dcamera={}, OptionalJacobian< 2, 3 > Dpoint={}) const
 project a 3D point from world coordinates into the image More...
 
Point2 project2 (const Unit3 &pw, OptionalJacobian< 2, dimension > Dcamera={}, OptionalJacobian< 2, 2 > Dpoint={}) const
 project a point at infinity from world coordinates into the image More...
 
double range (const Point3 &point, OptionalJacobian< 1, dimension > Dcamera={}, OptionalJacobian< 1, 3 > Dpoint={}) const
 
double range (const Pose3 &pose, OptionalJacobian< 1, dimension > Dcamera={}, OptionalJacobian< 1, 6 > Dpose={}) const
 
template<class CalibrationB >
double range (const PinholeCamera< CalibrationB > &camera, OptionalJacobian< 1, dimension > Dcamera={}, OptionalJacobian< 1, 6+CalibrationB::dimension > Dother={}) const
 
double range (const CalibratedCamera &camera, OptionalJacobian< 1, dimension > Dcamera={}, OptionalJacobian< 1, 6 > Dother={}) const
 
Matrix34 cameraProjectionMatrix () const
 for Linear Triangulation More...
 
Vector defaultErrorWhenTriangulatingBehindCamera () const
 for Nonlinear Triangulation More...
 

Additional Inherited Members

- Public Member Functions inherited from gtsam::PinholeBaseK< Calibration >
 PinholeBaseK ()
 
 PinholeBaseK (const Pose3 &pose)
 
 PinholeBaseK (const Vector &v)
 
virtual const Calibration & calibration () const=0
 return calibration More...
 
std::pair< Point2, bool > projectSafe (const Point3 &pw) const
 Project a point into the image and check depth. More...
 
Point2 _project (const POINT &pw, OptionalJacobian< 2, 6 > Dpose, OptionalJacobian< 2, FixedDimension< POINT >::value > Dpoint, OptionalJacobian< 2, DimK > Dcal) const
 
Point2 project (const Point3 &pw, OptionalJacobian< 2, 6 > Dpose={}, OptionalJacobian< 2, 3 > Dpoint={}, OptionalJacobian< 2, DimK > Dcal={}) const
 project a 3D point from world coordinates into the image More...
 
Point2 project (const Unit3 &pw, OptionalJacobian< 2, 6 > Dpose={}, OptionalJacobian< 2, 2 > Dpoint={}, OptionalJacobian< 2, DimK > Dcal={}) const
 project a point at infinity from world coordinates into the image More...
 
Point2 reprojectionError (const Point3 &pw, const Point2 &measured, OptionalJacobian< 2, 6 > Dpose={}, OptionalJacobian< 2, 3 > Dpoint={}, OptionalJacobian< 2, DimK > Dcal={}) const
 project a 3D point from world coordinates into the image More...
 
Point3 backproject (const Point2 &p, double depth, OptionalJacobian< 3, 6 > Dresult_dpose={}, OptionalJacobian< 3, 2 > Dresult_dp={}, OptionalJacobian< 3, 1 > Dresult_ddepth={}, OptionalJacobian< 3, DimK > Dresult_dcal={}) const
 backproject a 2-dimensional point to a 3-dimensional point at given depth More...
 
Unit3 backprojectPointAtInfinity (const Point2 &p) const
 backproject a 2-dimensional point to a 3-dimensional point at infinity More...
 
double range (const Point3 &point, OptionalJacobian< 1, 6 > Dcamera={}, OptionalJacobian< 1, 3 > Dpoint={}) const
 
double range (const Pose3 &pose, OptionalJacobian< 1, 6 > Dcamera={}, OptionalJacobian< 1, 6 > Dpose={}) const
 
double range (const CalibratedCamera &camera, OptionalJacobian< 1, 6 > Dcamera={}, OptionalJacobian< 1, 6 > Dother={}) const
 
double range (const PinholeBaseK< CalibrationB > &camera, OptionalJacobian< 1, 6 > Dcamera={}, OptionalJacobian< 1, 6 > Dother={}) const
 
- Public Member Functions inherited from gtsam::PinholeBase
 PinholeBase ()
 Default constructor. More...
 
 PinholeBase (const Pose3 &pose)
 Constructor with pose. More...
 
 PinholeBase (const Vector &v)
 
virtual ~PinholeBase ()=default
 Default destructor. More...
 
bool equals (const PinholeBase &camera, double tol=1e-9) const
 assert equality up to a tolerance More...
 
const Pose3pose () const
 return pose, constant version More...
 
const Rot3rotation () const
 get rotation More...
 
const Point3translation () const
 get translation More...
 
const Pose3getPose (OptionalJacobian< 6, 6 > H) const
 return pose, with derivative More...
 
std::pair< Point2, bool > projectSafe (const Point3 &pw) const
 Project a point into the image and check depth. More...
 
Point2 project2 (const Point3 &point, OptionalJacobian< 2, 6 > Dpose={}, OptionalJacobian< 2, 3 > Dpoint={}) const
 
Point2 project2 (const Unit3 &point, OptionalJacobian< 2, 6 > Dpose={}, OptionalJacobian< 2, 2 > Dpoint={}) const
 
- Static Public Member Functions inherited from gtsam::PinholeBase
static Pose3 LevelPose (const Pose2 &pose2, double height)
 
static Pose3 LookatPose (const Point3 &eye, const Point3 &target, const Point3 &upVector)
 
static Point2 Project (const Point3 &pc, OptionalJacobian< 2, 3 > Dpoint={})
 
static Point2 Project (const Unit3 &pc, OptionalJacobian< 2, 2 > Dpoint={})
 
static Point3 BackprojectFromCamera (const Point2 &p, const double depth, OptionalJacobian< 3, 2 > Dpoint={}, OptionalJacobian< 3, 1 > Ddepth={})
 backproject a 2-dimensional point to a 3-dimensional point at given depth More...
 
static std::pair< size_t, size_ttranslationInterval ()
 
- Static Protected Member Functions inherited from gtsam::PinholeBase
static Matrix26 Dpose (const Point2 &pn, double d)
 
static Matrix23 Dpoint (const Point2 &pn, double d, const Matrix3 &Rt)
 

Detailed Description

template<typename Calibration>
class gtsam::PinholeCamera< Calibration >

A pinhole camera class that has a Pose3 and a Calibration. Use PinholePose if you will not be optimizing for Calibration

Definition at line 33 of file PinholeCamera.h.

Member Typedef Documentation

◆ Base

template<typename Calibration >
typedef PinholeBaseK<Calibration> gtsam::PinholeCamera< Calibration >::Base
private

base class has 3D pose as private member

Definition at line 46 of file PinholeCamera.h.

◆ Matrix2K

template<typename Calibration >
typedef Eigen::Matrix<double, 2, DimK> gtsam::PinholeCamera< Calibration >::Matrix2K

Definition at line 224 of file PinholeCamera.h.

◆ Measurement

template<typename Calibration >
typedef Point2 gtsam::PinholeCamera< Calibration >::Measurement

Some classes template on either PinholeCamera or StereoCamera, and this typedef informs those classes what "project" returns.

Definition at line 41 of file PinholeCamera.h.

◆ MeasurementVector

template<typename Calibration >
typedef Point2Vector gtsam::PinholeCamera< Calibration >::MeasurementVector

Definition at line 42 of file PinholeCamera.h.

◆ VectorK6

template<typename Calibration >
typedef Eigen::Matrix<double, dimension, 1> gtsam::PinholeCamera< Calibration >::VectorK6

Definition at line 196 of file PinholeCamera.h.

Member Enumeration Documentation

◆ anonymous enum

template<typename Calibration >
anonymous enum
Enumerator
dimension 

Definition at line 54 of file PinholeCamera.h.

Constructor & Destructor Documentation

◆ PinholeCamera() [1/5]

template<typename Calibration >
gtsam::PinholeCamera< Calibration >::PinholeCamera ( )
inline

default constructor

Definition at line 62 of file PinholeCamera.h.

◆ PinholeCamera() [2/5]

template<typename Calibration >
gtsam::PinholeCamera< Calibration >::PinholeCamera ( const Pose3 pose)
inlineexplicit

constructor with pose

Definition at line 66 of file PinholeCamera.h.

◆ PinholeCamera() [3/5]

template<typename Calibration >
gtsam::PinholeCamera< Calibration >::PinholeCamera ( const Pose3 pose,
const Calibration &  K 
)
inline

constructor with pose and calibration

Definition at line 71 of file PinholeCamera.h.

◆ PinholeCamera() [4/5]

template<typename Calibration >
gtsam::PinholeCamera< Calibration >::PinholeCamera ( const Vector v)
inlineexplicit

Init from vector, can be 6D (default calibration) or dim.

Definition at line 129 of file PinholeCamera.h.

◆ PinholeCamera() [5/5]

template<typename Calibration >
gtsam::PinholeCamera< Calibration >::PinholeCamera ( const Vector v,
const Vector K 
)
inline

Init from Vector and calibration.

Definition at line 136 of file PinholeCamera.h.

◆ ~PinholeCamera()

template<typename Calibration >
gtsam::PinholeCamera< Calibration >::~PinholeCamera ( )
inlineoverride

Definition at line 160 of file PinholeCamera.h.

Member Function Documentation

◆ _project2()

template<typename Calibration >
template<class POINT >
Point2 gtsam::PinholeCamera< Calibration >::_project2 ( const POINT &  pw,
OptionalJacobian< 2, dimension Dcamera,
OptionalJacobian< 2, FixedDimension< POINT >::value >  Dpoint 
) const
inline

Templated projection of a 3D point or a point at infinity into the image

Parameters
pweither a Point3 or a Unit3, in world coordinates

Definition at line 230 of file PinholeCamera.h.

◆ calibration()

template<typename Calibration >
const Calibration& gtsam::PinholeCamera< Calibration >::calibration ( ) const
inlineoverride

return calibration

Definition at line 178 of file PinholeCamera.h.

◆ cameraProjectionMatrix()

template<typename Calibration >
Matrix34 gtsam::PinholeCamera< Calibration >::cameraProjectionMatrix ( ) const
inline

for Linear Triangulation

Definition at line 318 of file PinholeCamera.h.

◆ Create()

template<typename Calibration >
static PinholeCamera gtsam::PinholeCamera< Calibration >::Create ( const Pose3 pose,
const Calibration &  K,
OptionalJacobian< dimension, 6 >  H1 = {},
OptionalJacobian< dimension, DimK H2 = {} 
)
inlinestatic

Definition at line 111 of file PinholeCamera.h.

◆ defaultErrorWhenTriangulatingBehindCamera()

template<typename Calibration >
Vector gtsam::PinholeCamera< Calibration >::defaultErrorWhenTriangulatingBehindCamera ( ) const
inline

for Nonlinear Triangulation

Definition at line 323 of file PinholeCamera.h.

◆ Dim()

template<typename Calibration >
static size_t gtsam::PinholeCamera< Calibration >::Dim ( )
inlinestatic
Deprecated:

Definition at line 192 of file PinholeCamera.h.

◆ dim()

template<typename Calibration >
size_t gtsam::PinholeCamera< Calibration >::dim ( ) const
inline
Deprecated:

Definition at line 187 of file PinholeCamera.h.

◆ equals()

template<typename Calibration >
bool gtsam::PinholeCamera< Calibration >::equals ( const Base camera,
double  tol = 1e-9 
) const
inline

assert equality up to a tolerance

Definition at line 145 of file PinholeCamera.h.

◆ getPose()

template<typename Calibration >
const Pose3& gtsam::PinholeCamera< Calibration >::getPose ( OptionalJacobian< 6, dimension H) const
inline

return pose, with derivative

Definition at line 169 of file PinholeCamera.h.

◆ Identity()

template<typename Calibration >
static PinholeCamera gtsam::PinholeCamera< Calibration >::Identity ( )
inlinestatic

for Canonical

Definition at line 216 of file PinholeCamera.h.

◆ Level() [1/2]

template<typename Calibration >
static PinholeCamera gtsam::PinholeCamera< Calibration >::Level ( const Calibration &  K,
const Pose2 pose2,
double  height 
)
inlinestatic

Create a level camera at the given 2D pose and height

Parameters
Kthe calibration
pose2specifies the location and viewing direction (theta 0 = looking in direction of positive X axis)
heightcamera height

Definition at line 86 of file PinholeCamera.h.

◆ Level() [2/2]

template<typename Calibration >
static PinholeCamera gtsam::PinholeCamera< Calibration >::Level ( const Pose2 pose2,
double  height 
)
inlinestatic

PinholeCamera::level with default calibration.

Definition at line 92 of file PinholeCamera.h.

◆ localCoordinates()

template<typename Calibration >
VectorK6 gtsam::PinholeCamera< Calibration >::localCoordinates ( const PinholeCamera< Calibration > &  T2) const
inline

return canonical coordinate

Definition at line 208 of file PinholeCamera.h.

◆ Lookat()

template<typename Calibration >
static PinholeCamera gtsam::PinholeCamera< Calibration >::Lookat ( const Point3 eye,
const Point3 target,
const Point3 upVector,
const Calibration &  K = Calibration() 
)
inlinestatic

Create a camera at the given eye position looking at a target point in the scene with the specified up direction vector.

Parameters
eyespecifies the camera position
targetthe point to look at
upVectorspecifies the camera up direction vector, doesn't need to be on the image plane nor orthogonal to the viewing axis
Koptional calibration parameter

Definition at line 105 of file PinholeCamera.h.

◆ pose()

template<typename Calibration >
const Pose3& gtsam::PinholeCamera< Calibration >::pose ( ) const
inline

return pose

Definition at line 164 of file PinholeCamera.h.

◆ print()

template<typename Calibration >
void gtsam::PinholeCamera< Calibration >::print ( const std::string &  s = "PinholeCamera< Calibration >") const
inlineoverridevirtual

print

Reimplemented from gtsam::PinholeBase.

Definition at line 151 of file PinholeCamera.h.

◆ project2() [1/2]

template<typename Calibration >
Point2 gtsam::PinholeCamera< Calibration >::project2 ( const Point3 pw,
OptionalJacobian< 2, dimension Dcamera = {},
OptionalJacobian< 2, 3 >  Dpoint = {} 
) const
inline

project a 3D point from world coordinates into the image

Definition at line 245 of file PinholeCamera.h.

◆ project2() [2/2]

template<typename Calibration >
Point2 gtsam::PinholeCamera< Calibration >::project2 ( const Unit3 pw,
OptionalJacobian< 2, dimension Dcamera = {},
OptionalJacobian< 2, 2 >  Dpoint = {} 
) const
inline

project a point at infinity from world coordinates into the image

Definition at line 251 of file PinholeCamera.h.

◆ range() [1/4]

template<typename Calibration >
double gtsam::PinholeCamera< Calibration >::range ( const CalibratedCamera camera,
OptionalJacobian< 1, dimension Dcamera = {},
OptionalJacobian< 1, 6 >  Dother = {} 
) const
inline

Calculate range to a calibrated camera

Parameters
cameraOther camera
Returns
range (double)

Definition at line 311 of file PinholeCamera.h.

◆ range() [2/4]

template<typename Calibration >
template<class CalibrationB >
double gtsam::PinholeCamera< Calibration >::range ( const PinholeCamera< CalibrationB > &  camera,
OptionalJacobian< 1, dimension Dcamera = {},
OptionalJacobian< 1, 6+CalibrationB::dimension >  Dother = {} 
) const
inline

Calculate range to another camera

Parameters
cameraOther camera
Returns
range (double)

Definition at line 290 of file PinholeCamera.h.

◆ range() [3/4]

template<typename Calibration >
double gtsam::PinholeCamera< Calibration >::range ( const Point3 point,
OptionalJacobian< 1, dimension Dcamera = {},
OptionalJacobian< 1, 3 >  Dpoint = {} 
) const
inline

Calculate range to a landmark

Parameters
point3D location of landmark
Returns
range (double)

Definition at line 261 of file PinholeCamera.h.

◆ range() [4/4]

template<typename Calibration >
double gtsam::PinholeCamera< Calibration >::range ( const Pose3 pose,
OptionalJacobian< 1, dimension Dcamera = {},
OptionalJacobian< 1, 6 >  Dpose = {} 
) const
inline

Calculate range to another pose

Parameters
poseOther SO(3) pose
Returns
range (double)

Definition at line 275 of file PinholeCamera.h.

◆ retract()

template<typename Calibration >
PinholeCamera gtsam::PinholeCamera< Calibration >::retract ( const Vector d) const
inline

move a cameras according to d

Definition at line 199 of file PinholeCamera.h.

Member Data Documentation

◆ DimK

template<typename Calibration >
const int gtsam::PinholeCamera< Calibration >::DimK = FixedDimension<Calibration>::value
staticprivate

Definition at line 50 of file PinholeCamera.h.

◆ K_

template<typename Calibration >
Calibration gtsam::PinholeCamera< Calibration >::K_
private

Calibration, part of class now.

Definition at line 47 of file PinholeCamera.h.


The documentation for this class was generated from the following file:


gtsam
Author(s):
autogenerated on Sat Nov 16 2024 04:16:24