CentralCamera

Perspective camera class

A concrete class for a central-projection perspective camera, a subclass of Camera.

The camera coordinate system is:

0------------> u X
|
|
|   + (principal point)
|
|   Z-axis is into the page.
v Y

This camera model assumes central projection, that is, the focal point is at z=0 and the image plane is at z=f. The image is not inverted.

Methods

project project world points and lines
K camera intrinsic matrix
C camera matrix
H camera motion to homography
invH decompose homography
F camera motion to fundamental matrix
E camera motion to essential matrix
invE decompose essential matrix
fov field of view
ray Ray3D corresponding to point
centre projective centre
plot plot projection of world point on image plane
hold control hold for image plane
ishold test figure hold for image plane
clf clear image plane
figure figure holding the image plane
mesh draw shape represented as a mesh
point draw homogeneous points on image plane
line draw homogeneous lines on image plane
plot_camera draw camera in world view
plot_line_tr draw line in theta/rho format
plot_epiline draw epipolar line
flowfield compute optical flow
visjac_p image Jacobian for point features
visjac_p_polar image Jacobian for point features in polar coordinates
visjac_l image Jacobian for line features
visjac_e image Jacobian for ellipse features
rpy set camera attitude
move clone Camera after motion
centre get world coordinate of camera centre
estpose estimate pose
delete object destructor
char convert camera parameters to string
display display camera parameters

Properties (read/write)

npix image dimensions in pixels (2x1)
pp intrinsic: principal point (2x1)
rho intrinsic: pixel dimensions (2x1) in metres
f intrinsic: focal length
k intrinsic: radial distortion vector
p intrinsic: tangential distortion parameters
distortion intrinsic: camera distortion [k1 k2 k3 p1 p2]
T extrinsic: camera pose as homogeneous transformation

Properties (read only)

nu number of pixels in u-direction
nv number of pixels in v-direction
u0 principal point u-coordinate
v0 principal point v-coordinate

Notes

See also

Camera


CentralCamera.CentralCamera

Create central projection camera object

C = CentralCamera() creates a central projection camera with canonic parameters: f=1 and name='canonic'.

C = CentralCamera(options) as above but with specified parameters.

Options

'name', N Name of camera
'focal', F Focal length [metres]
'distortion', D Distortion vector [k1 k2 k3 p1 p2]
'distortion-bouguet', D Distortion vector [k1 k2 p1 p2 k3]
'default' Default camera parameters: 1024x1024, f=8mm, 10um pixels, camera at origin, optical axis is z-axis, u- and v-axes parallel to x- and y-axes respectively.
'image', IM Display an image rather than points
'resolution', N Image plane resolution: NxN or N=[W H]
'sensor', S Image sensor size in metres (2x1)
'centre', P Principal point (2x1)
'pixel', S Pixel size: SxS or S=[W H]
'noise', SIGMA Standard deviation of additive Gaussian noise added to returned image projections
'pose', T Pose of the camera as a homogeneous transformation
'color', C Color of image plane background (default [1 1 0.8])

See also

Camera, fisheyecamera, CatadioptricCamera, SphericalCamera


CentralCamera.C

Camera matrix

C = C.C() is the 3x4 camera matrix, also known as the camera calibration or projection matrix.


CentralCamera.centre

Projective centre

p = C.centre() returns the 3D world coordinate of the projective centre of the camera.

Reference

Hartley & Zisserman, "Multiview Geometry",

See also

Ray3D


CentralCamera.E

Essential matrix

E = C.E(T) is the essential matrix relating two camera views. The first view is from the current camera pose C.T and the second is a relative motion represented by the homogeneous transformation T.

E = C.E(C2) is the essential matrix relating two camera views described by camera objects C (first view) and C2 (second view).

E = C.E(f) is the essential matrix based on the fundamental matrix f (3x3) and the intrinsic parameters of camera C.

Reference

Y.Ma, J.Kosecka, S.Soatto, S.Sastry, "An invitation to 3D", Springer, 2003. p.177

See also

CentralCamera.F, CentralCamera.invE


CentralCamera.estpose

Estimate pose from object model and camera view

T = C.estpose(xyz, uv) is an estimate of the pose of the object defined by coordinates xyz (3xN) in its own coordinate frame. uv (2xN) are the corresponding image plane coordinates.

Reference

"EPnP: An accurate O(n) solution to the PnP problem", V. Lepetit, F. Moreno-Noguer, and P. Fua, Int. Journal on Computer Vision, vol. 81, pp. 155-166, Feb. 2009.


CentralCamera.F

Fundamental matrix

F = C.F(T) is the fundamental matrix relating two camera views. The first view is from the current camera pose C.T and the second is a relative motion represented by the homogeneous transformation T.

F = C.F(C2) is the fundamental matrix relating two camera views described by camera objects C (first view) and C2 (second view).

Reference

Y.Ma, J.Kosecka, S.Soatto, S.Sastry, "An invitation to 3D", Springer, 2003. p.177

See also

CentralCamera.E


CentralCamera.flowfield

Optical flow

C.flowfield(v) displays the optical flow pattern for a sparse grid of points when the camera has a spatial velocity v (6x1).

See also

quiver


CentralCamera.fov

Camera field-of-view angles.

a = C.fov() are the field of view angles (2x1) in radians for the camera x and y (horizontal and vertical) directions.


CentralCamera.H

Homography matrix

H = C.H(T, n, d) is a 3x3 homography matrix for the camera observing the plane with normal n and at distance d, from two viewpoints. The first view is from the current camera pose C.T and the second is after a relative motion represented by the homogeneous transformation T.

See also

CentralCamera.H


CentralCamera.invE

Decompose essential matrix

s = C.invE(E) decomposes the essential matrix E (3x3) into the camera motion. In practice there are multiple solutions and s (4x4xN) is a set of homogeneous transformations representing possible camera motion.

s = C.invE(E, p) as above but only solutions in which the world point p is visible are returned.

Reference

Hartley & Zisserman, "Multiview Geometry", Chap 9, p. 259

Y.Ma, J.Kosecka, s.Soatto, s.Sastry, "An invitation to 3D", Springer, 2003. p116, p120-122

Notes

See also

CentralCamera.E


CentralCamera.invH

Decompose homography matrix

s = C.invH(H) decomposes the homography H (3x3) into the camera motion and the normal to the plane.

In practice there are multiple solutions and s is a vector of structures with elements:

Notes

Reference

Y.Ma, J.Kosecka, s.Soatto, s.Sastry, "An invitation to 3D", Springer, 2003. section 5.3

See also

CentralCamera.H


CentralCamera.K

Intrinsic parameter matrix

K = C.K() is the 3x3 intrinsic parameter matrix.


CentralCamera.plot_epiline

Plot epipolar line

C.plot_epiline(f, p) plots the epipolar lines due to the fundamental matrix f and the image points p.

C.plot_epiline(f, p, ls) as above but draw lines using the line style arguments ls.

H = C.plot_epiline(f, p) as above but return a vector of graphic handles, one per line.


CentralCamera.plot_line_tr

Plot line in theta-rho format

CentralCamera.plot_line_tr(L) plots lines on the camera's image plane that are described by columns of L with rows theta and rho respectively.

See also

Hough


CentralCamera.project

Project world points to image plane

uv = C.project(p, options) are the image plane coordinates (2xN) corresponding to the world points p (3xN).

[uv,vis] = C.project(p, options) as above but vis (SxN) is a logical matrix with elements true (1) if the point is visible, that is, it lies within the bounds of the image plane and is in front of the camera.

L = C.project(L, options) are the image plane homogeneous lines (3xN) corresponding to the world lines represented by a vector of Plucker coordinates (1xN).

Options

'Tobj', T Transform all points by the homogeneous transformation T before projecting them to the camera image plane.
'Tcam', T Set the camera pose to the homogeneous transformation T before projecting points to the camera image plane. Temporarily overrides the current camera pose C.T.

Notes

See also

Camera.plot, Plucker


CentralCamera.ray

3D ray for image point

R = C.ray(p) returns a vector of Ray3D objects, one for each point defined by the columns of p.

Reference

Hartley & Zisserman, "Multiview Geometry", p 162

See also

Ray3D


CentralCamera.visjac_e

Visual motion Jacobian for point feature

J = C.visjac_e(E, pl) is the image Jacobian (5x6) for the ellipse E (5x1) described by uˆ2 + E1vˆ2 - 2E2uv + 2E3u + 2E4v + E5 = 0. The ellipse lies in the world plane pl = (a,b,c,d) such that aX + bY + cZ + d = 0.

The Jacobian gives the rates of change of the ellipse parameters in terms of camera spatial velocity.

Reference

B. Espiau, F. Chaumette, and P. Rives, "A New Approach to Visual Servoing in Robotics", IEEE Transactions on Robotics and Automation, vol. 8, pp. 313-326, June 1992.

See also

CentralCamera.visjac_p, CentralCamera.visjac_p_polar, CentralCamera.visjac_l


CentralCamera.visjac_l

Visual motion Jacobian for line feature

J = C.visjac_l(L, pl) is the image Jacobian (2Nx6) for the image plane lines L (2xN). Each column of L is a line in theta-rho format, and the rows are theta and rho respectively.

The lines all lie in the plane pl = (a,b,c,d) such that aX + bY + cZ + d = 0.

The Jacobian gives the rates of change of the line parameters in terms of camera spatial velocity.

Reference

B. Espiau, F. Chaumette, and P. Rives, "A New Approach to Visual Servoing in Robotics", IEEE Transactions on Robotics and Automation, vol. 8, pp. 313-326, June 1992.

See also

CentralCamera.visjac_p, CentralCamera.visjac_p_polar, CentralCamera.visjac_e


CentralCamera.visjac_p

Visual motion Jacobian for point feature

J = C.visjac_p(uv, z) is the image Jacobian (2Nx6) for the image plane points uv (2xN). The depth of the points from the camera is given by z which is a scalar for all points, or a vector (Nx1) of depth for each point.

The Jacobian gives the image-plane point velocity in terms of camera spatial velocity.

Reference

"A tutorial on Visual Servo Control", Hutchinson, Hager & Corke, IEEE Trans. R&A, Vol 12(5), Oct, 1996, pp 651-670.

See also

CentralCamera.visjac_p_polar, CentralCamera.visjac_l, CentralCamera.visjac_e


CentralCamera.visjac_p_polar

Visual motion Jacobian for point feature

J = C.visjac_p_polar(rt, z) is the image Jacobian (2Nx6) for the image plane points rt (2xN) described in polar form, radius and theta. The depth of the points from the camera is given by z which is a scalar for all point, or a vector (Nx1) of depths for each point.

The Jacobian gives the image-plane polar point coordinate velocity in terms of camera spatial velocity.

Reference

"Combining Cartesian and polar coordinates in IBVS", P. I. Corke, F. Spindler, and F. Chaumette, in Proc. Int. Conf on Intelligent Robots and Systems (IROS), (St. Louis), pp. 5962-5967, Oct. 2009.

See also

CentralCamera.visjac_p, CentralCamera.visjac_l, CentralCamera.visjac_e


Machine Vision Toolbox for MATLAB © 1990-2014 Peter Corke.