symforce.cam.atan_camera_cal module

class ATANCameraCal(focal_length, principal_point, omega)[source]

Bases: CameraCal

ATAN camera with 5 parameters [fx, fy, cx, cy, omega].

(fx, fy) representing focal length, (cx, cy) representing principal point, and omega representing the distortion parameter.

See here for more details: https://hal.inria.fr/inria-00267247/file/distcalib.pdf

Parameters:
  • focal_length (T.Sequence[T.Scalar]) –

  • principal_point (T.Sequence[T.Scalar]) –

  • omega (T.Scalar) –

NUM_DISTORTION_COEFFS = 1
property omega: float
classmethod symbolic(name, **kwargs)[source]

Construct a symbolic element with the given name prefix. Kwargs are forwarded to sf.Symbol (for example, sympy assumptions).

Parameters:
  • name (str) –

  • kwargs (Any) –

Return type:

ATANCameraCal

classmethod storage_order()[source]

Return list of the names of values returned in the storage paired with the dimension of each value.

Return type:

Tuple[Tuple[str, int], …]

pixel_from_camera_point(point, epsilon=0.0)[source]

Project a 3D point in the camera frame into 2D pixel coordinates.

Returns:
  • pixel – (x, y) coordinate in pixels if valid

  • is_valid – 1 if the operation is within bounds else 0

Parameters:
Return type:

Tuple[Matrix21, float]

camera_ray_from_pixel(pixel, epsilon=0.0)[source]

Backproject a 2D pixel coordinate into a 3D ray in the camera frame.

Returns:
  • camera_ray – The ray in the camera frame (NOT normalized)

  • is_valid – 1 if the operation is within bounds else 0

Parameters:
Return type:

Tuple[Matrix31, float]