symforce.cam.linear_camera_cal module#

class LinearCameraCal(focal_length, principal_point, distortion_coeffs=())[source]#

Bases: CameraCal

Standard pinhole camera w/ four parameters [fx, fy, cx, cy].

(fx, fy) representing focal length; (cx, cy) representing principal point.

Parameters:
NUM_DISTORTION_COEFFS = 0#
static project(point, epsilon=0.0)[source]#

Linearly project the 3D point by dividing by the depth.

Points behind the camera (z <= 0 in the camera frame) are marked as invalid.

Parameters:
Returns:
  • value_if_is_valid – Result of projection if the point is valid

  • is_valid – 1 if the point is valid; 0 otherwise

Return type:

Tuple[Matrix21, float]

pixel_from_unit_depth(unit_depth_coords)[source]#

Convert point in unit-depth image plane to pixel coords by applying camera matrix.

Parameters:

unit_depth_coords (Matrix21) –

Return type:

Matrix21

unit_depth_from_pixel(pixel)[source]#

Convert point in pixel coordinates to unit-depth image plane by applying K_inv.

Parameters:

pixel (Matrix21) –

Return type:

Matrix21

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]