Public Types | Private Attributes | List of all members
gtsam::PinholeBase Class Reference

#include <CalibratedCamera.h>

Inheritance diagram for gtsam::PinholeBase:
Inheritance graph
[legend]

Public Types

typedef Point2 Measurement
 
typedef Point2Vector MeasurementVector
 
typedef Rot3 Rotation
 
typedef Point3 Translation
 

Private Attributes

Pose3 pose_
 3D pose of camera More...
 

Derivatives

static Matrix26 Dpose (const Point2 &pn, double d)
 
static Matrix23 Dpoint (const Point2 &pn, double d, const Matrix3 &Rt)
 

Static functions

static Pose3 LevelPose (const Pose2 &pose2, double height)
 
static Pose3 LookatPose (const Point3 &eye, const Point3 &target, const Point3 &upVector)
 

Standard Constructors

 PinholeBase ()
 Default constructor. More...
 
 PinholeBase (const Pose3 &pose)
 Constructor with pose. More...
 

Advanced Constructors

 PinholeBase (const Vector &v)
 
virtual ~PinholeBase ()=default
 Default destructor. More...
 

Testable

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

Standard Interface

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...
 

Transformations and measurement functions

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...
 
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
 

Advanced interface

static std::pair< size_t, size_ttranslationInterval ()
 

Detailed Description

A pinhole camera class that has a Pose3, functions as base class for all pinhole cameras

Definition at line 54 of file CalibratedCamera.h.

Member Typedef Documentation

◆ Measurement

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

Definition at line 66 of file CalibratedCamera.h.

◆ MeasurementVector

Definition at line 67 of file CalibratedCamera.h.

◆ Rotation

Pose Concept requirements

Definition at line 59 of file CalibratedCamera.h.

◆ Translation

Definition at line 60 of file CalibratedCamera.h.

Constructor & Destructor Documentation

◆ PinholeBase() [1/3]

gtsam::PinholeBase::PinholeBase ( )
inline

Default constructor.

Definition at line 125 of file CalibratedCamera.h.

◆ PinholeBase() [2/3]

gtsam::PinholeBase::PinholeBase ( const Pose3 pose)
inlineexplicit

Constructor with pose.

Definition at line 128 of file CalibratedCamera.h.

◆ PinholeBase() [3/3]

gtsam::PinholeBase::PinholeBase ( const Vector v)
inlineexplicit

Definition at line 134 of file CalibratedCamera.h.

◆ ~PinholeBase()

virtual gtsam::PinholeBase::~PinholeBase ( )
virtualdefault

Default destructor.

Member Function Documentation

◆ BackprojectFromCamera()

Point3 gtsam::PinholeBase::BackprojectFromCamera ( const Point2 p,
const double  depth,
OptionalJacobian< 3, 2 >  Dpoint = {},
OptionalJacobian< 3, 1 >  Ddepth = {} 
)
static

backproject a 2-dimensional point to a 3-dimensional point at given depth

Definition at line 167 of file CalibratedCamera.cpp.

◆ Dpoint()

Matrix23 gtsam::PinholeBase::Dpoint ( const Point2 pn,
double  d,
const Matrix3 &  Rt 
)
staticprotected

Calculate Jacobian with respect to point

Parameters
pnprojection in normalized coordinates
ddisparity (inverse depth)
Rttransposed rotation matrix

Definition at line 37 of file CalibratedCamera.cpp.

◆ Dpose()

Matrix26 gtsam::PinholeBase::Dpose ( const Point2 pn,
double  d 
)
staticprotected

Calculate Jacobian with respect to pose

Parameters
pnprojection in normalized coordinates
ddisparity (inverse depth)

Definition at line 27 of file CalibratedCamera.cpp.

◆ equals()

bool gtsam::PinholeBase::equals ( const PinholeBase camera,
double  tol = 1e-9 
) const

assert equality up to a tolerance

Definition at line 69 of file CalibratedCamera.cpp.

◆ getPose()

const Pose3 & gtsam::PinholeBase::getPose ( OptionalJacobian< 6, 6 >  H) const

return pose, with derivative

Definition at line 79 of file CalibratedCamera.cpp.

◆ LevelPose()

Pose3 gtsam::PinholeBase::LevelPose ( const Pose2 pose2,
double  height 
)
static

Create a level pose 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 49 of file CalibratedCamera.cpp.

◆ LookatPose()

Pose3 gtsam::PinholeBase::LookatPose ( const Point3 eye,
const Point3 target,
const Point3 upVector 
)
static

Create a camera pose 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

Definition at line 58 of file CalibratedCamera.cpp.

◆ pose()

const Pose3& gtsam::PinholeBase::pose ( ) const
inline

return pose, constant version

Definition at line 154 of file CalibratedCamera.h.

◆ print()

void gtsam::PinholeBase::print ( const std::string &  s = "PinholeBase") const
virtual

◆ Project() [1/2]

Point2 gtsam::PinholeBase::Project ( const Point3 pc,
OptionalJacobian< 2, 3 >  Dpoint = {} 
)
static

Project from 3D point in camera coordinates into image Does not throw a CheiralityException, even if pc behind image plane

Parameters
pcpoint in camera coordinates

Definition at line 88 of file CalibratedCamera.cpp.

◆ Project() [2/2]

Point2 gtsam::PinholeBase::Project ( const Unit3 pc,
OptionalJacobian< 2, 2 >  Dpoint = {} 
)
static

Project from 3D point at infinity in camera coordinates into image Does not throw a CheiralityException, even if pc behind image plane

Parameters
pcpoint in camera coordinates

Definition at line 97 of file CalibratedCamera.cpp.

◆ project2() [1/2]

Point2 gtsam::PinholeBase::project2 ( const Point3 point,
OptionalJacobian< 2, 6 >  Dpose = {},
OptionalJacobian< 2, 3 >  Dpoint = {} 
) const

Project point into the image Throws a CheiralityException if point behind image plane iff GTSAM_THROW_CHEIRALITY_EXCEPTION

Parameters
point3D point in world coordinates
Returns
the intrinsic coordinates of the projected point

Definition at line 116 of file CalibratedCamera.cpp.

◆ project2() [2/2]

Point2 gtsam::PinholeBase::project2 ( const Unit3 point,
OptionalJacobian< 2, 6 >  Dpose = {},
OptionalJacobian< 2, 2 >  Dpoint = {} 
) const

Project point at infinity into the image Throws a CheiralityException if point behind image plane iff GTSAM_THROW_CHEIRALITY_EXCEPTION

Parameters
point3D point in world coordinates
Returns
the intrinsic coordinates of the projected point

Definition at line 138 of file CalibratedCamera.cpp.

◆ projectSafe()

pair< Point2, bool > gtsam::PinholeBase::projectSafe ( const Point3 pw) const

Project a point into the image and check depth.

Definition at line 109 of file CalibratedCamera.cpp.

◆ rotation()

const Rot3& gtsam::PinholeBase::rotation ( ) const
inline

get rotation

Definition at line 159 of file CalibratedCamera.h.

◆ translation()

const Point3& gtsam::PinholeBase::translation ( ) const
inline

get translation

Definition at line 164 of file CalibratedCamera.h.

◆ translationInterval()

static std::pair<size_t, size_t> gtsam::PinholeBase::translationInterval ( )
inlinestatic

Return the start and end indices (inclusive) of the translation component of the exponential map parameterization

Returns
a pair of [start, end] indices into the tangent space vector

Definition at line 225 of file CalibratedCamera.h.

Member Data Documentation

◆ pose_

Pose3 gtsam::PinholeBase::pose_
private

3D pose of camera

Definition at line 71 of file CalibratedCamera.h.


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


gtsam
Author(s):
autogenerated on Tue Jul 4 2023 02:47:06