Camera Intrinsics¶
CameraIntrinsics¶
-
class
perception.
CameraIntrinsics
(frame, fx, fy=None, cx=0.0, cy=0.0, skew=0.0, height=None, width=None)¶ Bases:
object
A set of intrinsic parameters for a camera. This class is used to project and deproject points.
-
__init__
(frame, fx, fy=None, cx=0.0, cy=0.0, skew=0.0, height=None, width=None)¶ Initialize a CameraIntrinsics model.
Parameters: - frame (
str
) – The frame of reference for the point cloud. - fx (float) – The x-axis focal length of the camera in pixels.
- fy (float) – The y-axis focal length of the camera in pixels.
- cx (float) – The x-axis optical center of the camera in pixels.
- cy (float) – The y-axis optical center of the camera in pixels.
- skew (float) – The skew of the camera in pixels.
- height (float) – The height of the camera image in pixels.
- width (float) – The width of the camera image in pixels
- frame (
-
frame
¶ str
– The frame of reference for the point cloud.
-
fx
¶ float – The x-axis focal length of the camera in pixels.
-
fy
¶ float – The y-axis focal length of the camera in pixels.
-
cx
¶ float – The x-axis optical center of the camera in pixels.
-
cy
¶ float – The y-axis optical center of the camera in pixels.
-
skew
¶ float – The skew of the camera in pixels.
-
height
¶ float – The height of the camera image in pixels.
-
width
¶ float – The width of the camera image in pixels
-
proj_matrix
¶ numpy.ndarray
– The 3x3 projection matrix for this camera.
-
K
¶ numpy.ndarray
– The 3x3 projection matrix for this camera.
-
crop
(height, width, crop_ci, crop_cj)¶ Convert to new camera intrinsics for crop of image from original camera.
Parameters: - height (int) – height of crop window
- width (int) – width of crop window
- crop_ci (int) – row of crop window center
- crop_cj (int) – col of crop window center
Returns: camera intrinsics for cropped window
Return type: CameraIntrinsics
-
resize
(scale)¶ Convert to new camera intrinsics with parameters for resized image.
Parameters: scale (float) – the amount to rescale the intrinsics Returns: camera intrinsics for resized image Return type: CameraIntrinsics
-
project
(point_cloud, round_px=True)¶ Projects a point cloud onto the camera image plane.
Parameters: - point_cloud (
autolab_core.PointCloud
orautolab_core.Point
) – A PointCloud or Point to project onto the camera image plane. - round_px (bool) – If True, projections are rounded to the nearest pixel.
Returns: A corresponding set of image coordinates representing the given PointCloud’s projections onto the camera image plane. If the input was a single Point, returns a 2D Point in the camera plane.
Return type: autolab_core.ImageCoords
orautolab_core.Point
Raises: ValueError
– If the input is not a PointCloud or Point in the same reference frame as the camera.- point_cloud (
-
project_to_image
(point_cloud, round_px=True)¶ Projects a point cloud onto the camera image plane and creates a depth image. Zero depth means no point projected into the camera at that pixel location (i.e. infinite depth).
Parameters: - point_cloud (
autolab_core.PointCloud
orautolab_core.Point
) – A PointCloud or Point to project onto the camera image plane. - round_px (bool) – If True, projections are rounded to the nearest pixel.
Returns: A DepthImage generated from projecting the point cloud into the camera.
Return type: DepthImage
Raises: ValueError
– If the input is not a PointCloud or Point in the same reference frame as the camera.- point_cloud (
-
deproject
(depth_image)¶ Deprojects a DepthImage into a PointCloud.
Parameters: depth_image ( DepthImage
) – The 2D depth image to projet into a point cloud.Returns: A 3D point cloud created from the depth image. Return type: autolab_core.PointCloud
Raises: ValueError
– If depth_image is not a valid DepthImage in the same reference frame as the camera.
-
deproject_to_image
(depth_image)¶ Deprojects a DepthImage into a PointCloudImage.
Parameters: depth_image ( DepthImage
) – The 2D depth image to projet into a point cloud.Returns: A point cloud image created from the depth image. Return type: PointCloudImage
Raises: ValueError
– If depth_image is not a valid DepthImage in the same reference frame as the camera.
-
deproject_pixel
(depth, pixel)¶ Deprojects a single pixel with a given depth into a 3D point.
Parameters: - depth (float) – The depth value at the given pixel location.
- pixel (
autolab_core.Point
) – A 2D point representing the pixel’s location in the camera image.
Returns: The projected 3D point.
Return type: autolab_core.Point
Raises: ValueError
– If pixel is not a valid 2D Point in the same reference frame as the camera.
-
save
(filename)¶ Save the CameraIntrinsics object to a .intr file.
Parameters: filename ( str
) – The .intr file to save the object to.Raises: ValueError
– If filename does not have the .intr extension.
-
static
load
(filename)¶ Load a CameraIntrinsics object from a file.
Parameters: filename ( str
) – The .intr file to load the object from.Returns: The CameraIntrinsics object loaded from the file. Return type: CameraIntrinsics
Raises: ValueError
– If filename does not have the .intr extension.
-