dlr::computerVision::CameraIntrinsicsPinhole Class Reference

This class represents calibration parameters for a simple pinhole camera model, as described in [1]. More...

#include <cameraIntrinsicsPinhole.h>

Inheritance diagram for dlr::computerVision::CameraIntrinsicsPinhole:
[legend]
Collaboration diagram for dlr::computerVision::CameraIntrinsicsPinhole:
[legend]

List of all members.

Public Member Functions

 CameraIntrinsicsPinhole ()
 The default constructor initializes the CameraIntrinsicsPinhole instance to a consistent (but not terribly useful) state.
 CameraIntrinsicsPinhole (size_t numPixelsX, size_t numPixelsY, double focalLength, double pixelSizeX, double pixelSizeY, double centerU, double centerV)
 This constructor allows the caller to explicitly set the camera intrinsic parameters.
virtual ~CameraIntrinsicsPinhole ()
 Destructor.
virtual dlr::numeric::Vector2D project (const dlr::numeric::Vector3D &point) const
 This member function takes a point in 3D camera coordinates and projects it into pixel coordinates.
std::istream & readFromStream (std::istream &inputStream)
 This member function sets the calibration from an input stream.
virtual dlr::geometry::Ray3D reverseProject (const dlr::numeric::Vector2D &pixelPosition, bool normalize=true) const
 This member function takes a point in 2D pixel coordinates and returns a ray in 3D camera coordinates passing through all of the 3D points that project to the specified 2D position.
std::ostream & writeToStream (std::ostream &outputStream) const
 This member function writes the calibration to an outputstream in a format which is compatible with member function readFromStream().
virtual geometry::Ray3D reverseProject (const dlr::numeric::Index2D &pixelPosition, bool normalize=true) const
 This function returns a ray in 3D camera coordinates starting at the camera focus, and passing through the center of the specified pixel.

Protected Attributes

double m_centerU
double m_centerV
double m_kX
double m_kY
size_t m_numPixelsX
size_t m_numPixelsY


Detailed Description

This class represents calibration parameters for a simple pinhole camera model, as described in [1].

There are two coordinate systems associated with the pinhole camera: the 3D camera coordinate system, and the 2D pixel coordinate system.

The camera coordinate system is right-handed, and has its origin at the focus of the camera. The Z axis is perpendicular to the image plane, points in the direction of the camera field of view, and intersects the image plane at (0, 0, focalLength). The X axis runs parallel to the rows of the image, increasing from the left of the image to the right. The Y axis runs parallel to the columns of the image, increasing from the top of the image to the bottom. We generally consider X, Y, Z to have units of meters, although nothing in the implementation of this class requires this.

The pixel coordinate system has its origin at one corner of the image. We call the two axes U and V. The U axis points along the first row of the image. The U axis is parallel to, and increases along, the X axis of the camera coordinate system. The V axis points along the first column, parallel to (and increasing along) the Y axis of the camera coordinate system. U and V have units of pixels. The pixel at indices (r, c) in the image (that is, the pixel at row r and column c) has its four corners at (u, v) coordinates (c, r), (c + 1, r), (c, r + 1), and (c + 1, r + 1). For example, the upper left pixel in the image (row 0, column 0) has its upper left corner at (u, v) = (0, 0) and its center at (u, v) = (0.5, 0.5).

When displaying an image, our convention is to orient the display so that the origin of the pixel coordinate system is at the top left of the display, with the U axis pointing to the right and the V axis pointing down.

Definition at line 64 of file cameraIntrinsicsPinhole.h.


Constructor & Destructor Documentation

dlr::computerVision::CameraIntrinsicsPinhole::CameraIntrinsicsPinhole (  ) 

The default constructor initializes the CameraIntrinsicsPinhole instance to a consistent (but not terribly useful) state.

Definition at line 31 of file cameraIntrinsicsPinhole.cpp.

dlr::computerVision::CameraIntrinsicsPinhole::CameraIntrinsicsPinhole ( size_t  numPixelsX,
size_t  numPixelsY,
double  focalLength,
double  pixelSizeX,
double  pixelSizeY,
double  centerU,
double  centerV 
)

This constructor allows the caller to explicitly set the camera intrinsic parameters.

Parameters:
numPixelsX This argument specifies how many columns there are in the camera images.
numPixelsY This argument specifies how many rows there are in the camera images.
focalLength This argument the distance from the camera focus to the image plane. Generally this number should be positive, indicating that the the image plane lies at a positive Z coordinate in the 3D camera coordinate frame. Our convention is to specify it in units of meters, but you can use whatever unit you like, provided you use the same unit for arguments pixelSizeX and pixelSizeY.
pixelSizeX This argument specifies the width of an individual pixel. In other words, pixelSizeX is the distance between the centers of adjacent pixels in the same row. Our convention is to specify it in units of meters, but you can use whatever unit you like, provided you use the same unit for arguments focalLength and pixelSizeY.
pixelSizeY This argument specifies the height of an individual pixel. In other words, pixelSizeX is the distance between the centers of adjacent pixels in the same column. Our convention is to specify it in units of meters, but you can use whatever unit you like, provided you use the same unit for arguments focalLength and pixelSizeX.
centerU This argument and the next specify the position in pixel coordinates at which the Z axis passes through the image plane.
centerV This argument and the previous specify the position in pixel coordinates at which the Z axis passes through the image plane.

Definition at line 47 of file cameraIntrinsicsPinhole.cpp.

virtual dlr::computerVision::CameraIntrinsicsPinhole::~CameraIntrinsicsPinhole (  )  [inline, virtual]

Destructor.

Definition at line 128 of file cameraIntrinsicsPinhole.h.


Member Function Documentation

Vector2D dlr::computerVision::CameraIntrinsicsPinhole::project ( const dlr::numeric::Vector3D &  point  )  const [virtual]

This member function takes a point in 3D camera coordinates and projects it into pixel coordinates.

Parameters:
point This argument specifies the 3D point to be projected.
Returns:
The return value gives the point in pixel coordinates to which the input point will project.

Implements dlr::computerVision::CameraIntrinsics.

Definition at line 71 of file cameraIntrinsicsPinhole.cpp.

std::istream & dlr::computerVision::CameraIntrinsicsPinhole::readFromStream ( std::istream &  inputStream  ) 

This member function sets the calibration from an input stream.

*this is modified only if the read was successful, otherwise it is not modified, and failbit is set in the stream state.

Parameters:
inputStream This is the stream from which to read the data.
Returns:
The return value is a reference to inputStream.

Definition at line 82 of file cameraIntrinsicsPinhole.cpp.

Referenced by dlr::computerVision::operator>>().

virtual dlr::geometry::Ray3D dlr::computerVision::CameraIntrinsicsPinhole::reverseProject ( const dlr::numeric::Vector2D &  pixelPosition,
bool  normalize = true 
) const [virtual]

This member function takes a point in 2D pixel coordinates and returns a ray in 3D camera coordinates passing through all of the 3D points that project to the specified 2D position.

Parameters:
pixelPosition This argument is the point to be projected out into 3D camera coordinates.
normalize This argument indicates whether the returned vector should be normalized to unit length. Setting this to false saves a few arithmetic operations.
Returns:
The return value is the ray in 3D camera coordinates corresponding to the input 2D point.

Implements dlr::computerVision::CameraIntrinsics.

std::ostream & dlr::computerVision::CameraIntrinsicsPinhole::writeToStream ( std::ostream &  outputStream  )  const

This member function writes the calibration to an outputstream in a format which is compatible with member function readFromStream().

Parameters:
outputStream This is the stream to which to write the data.
Returns:
The return value is a reference to outputStream.

Definition at line 161 of file cameraIntrinsicsPinhole.cpp.

Referenced by dlr::computerVision::operator<<().

dlr::geometry::Ray3D dlr::computerVision::CameraIntrinsics::reverseProject ( const dlr::numeric::Index2D &  pixelPosition,
bool  normalize = true 
) const [inline, virtual, inherited]

This function returns a ray in 3D camera coordinates starting at the camera focus, and passing through the center of the specified pixel.

Parameters:
pixelPosition This argument is the pixel through which the ray should pass.
normalize This argument indicates whether the ray should be normalized to unit length before being returned.
Returns:
The return value is the resulting ray.

Definition at line 131 of file cameraIntrinsics.h.


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

Generated on Tue Jan 6 23:24:57 2009 for dlrComputerVision Utility Library by  doxygen 1.5.6