sym.ops.linear_camera_cal.camera_ops module¶
- class CameraOps[source]¶
Bases:
object
Python CameraOps implementation for
symforce.cam.linear_camera_cal.LinearCameraCal
.- static focal_length(self)[source]¶
Return the focal length.
- Parameters:
self (LinearCameraCal) –
- Return type:
- static principal_point(self)[source]¶
Return the principal point.
- Parameters:
self (LinearCameraCal) –
- Return type:
- static pixel_from_camera_point(self, point, epsilon)[source]¶
Project a 3D point in the camera frame into 2D pixel coordinates.
- static pixel_from_camera_point_with_jacobians(self, point, epsilon)[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
pixel_D_cal – Derivative of pixel with respect to intrinsic calibration parameters
pixel_D_point – Derivative of pixel with respect to point
- Parameters:
self (LinearCameraCal) –
point (ndarray) –
epsilon (float) –
- Return type:
- static camera_ray_from_pixel(self, pixel, epsilon)[source]¶
Backproject a 2D pixel coordinate into a 3D ray in the camera frame.
- static camera_ray_from_pixel_with_jacobians(self, pixel, epsilon)[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
point_D_cal – Derivative of point with respect to intrinsic calibration parameters
point_D_pixel – Derivation of point with respect to pixel
- Parameters:
self (LinearCameraCal) –
pixel (ndarray) –
epsilon (float) –
- Return type: