robokudo.io.ros_camera_without_depth_interface¶
ROS camera interface for RGB-only cameras in RoboKudo.
This module provides an interface for ROS cameras that only provide RGB images without depth information. It supports:
Synchronized RGB image and camera info subscription
Image rotation with intrinsics adjustment
Transform lookup between camera and world frames
Thread-safe data handling
The module is used for cameras like:
Hand cameras on robotic arms
Standard USB cameras with ROS drivers
Network cameras with ROS interfaces
Classes¶
A ROS camera interface for RGB-only cameras. |
Module Contents¶
- class robokudo.io.ros_camera_without_depth_interface.ROSCameraWithoutDepthInterface(camera_config)¶
-
Bases:
robokudo.io.camera_interface.ROSCameraInterfaceA ROS camera interface for RGB-only cameras.
This class handles cameras that provide only RGB images without depth data. It synchronizes RGB images with camera calibration information and supports image rotation with proper intrinsics adjustment.
- Variables:
-
color_subscriber – Subscriber for RGB image topic
cam_info_subscriber – Subscriber for camera info topic
color – Latest RGB image data
cam_info – Latest camera calibration info
cam_intrinsic – Camera intrinsic parameters in Open3D format
color2depth_ratio – Always (1,1) since no depth data
cam_translation – Camera translation from TF
cam_quaternion – Camera rotation as quaternion from TF
timestamp – Timestamp of latest data
lock – Thread synchronization lock
bridge – Bridge for converting between ROS and OpenCV images
- color_subscriber¶
- cam_info_subscriber¶
- color = None¶
- cam_info = None¶
- cam_intrinsic = None¶
- color2depth_ratio = None¶
- cam_translation = None¶
- cam_quaternion = None¶
- timestamp = None¶
- lock¶
- bridge¶
- rotate_camera_intrinsics(K: numpy.ndarray, image_size: tuple[int, int], rotation='90_ccw') tuple[numpy.ndarray, tuple[int, int]]¶
-
Adjust camera intrinsics matrix for image rotation.
Computes the new camera intrinsics matrix and image dimensions after applying a rotation to the image. Supports 90° counter-clockwise, 90° clockwise, and 180° rotations.
- Parameters:
-
K (numpy.ndarray) – Original camera intrinsic matrix of shape (3, 3)
image_size (tuple) – Original image dimensions as (width, height)
rotation (str, optional) – ‘90_ccw’, ‘90_cw’, ‘180’ (default is 90° counter-clockwise)
- Returns:
-
Tuple of (new intrinsics matrix, new image dimensions)
- Return type:
-
tuple(numpy.ndarray, tuple(int, int))
- Raises:
-
ValueError – If rotation type is not supported
- rotate_image_and_intrinsics(img, K, rotation='90_ccw')¶
-
Rotate an image and adjust its camera intrinsics accordingly.
- Parameters:
-
img (numpy.ndarray) – Input image to rotate
K (numpy.ndarray) – Camera intrinsics matrix
rotation (str, optional) – Type of rotation to apply, defaults to ‘90_ccw’
- Returns:
-
Tuple of (rotated image, new intrinsics matrix, new dimensions)
- Return type:
-
tuple(numpy.ndarray, numpy.ndarray, tuple)
- Raises:
-
ValueError – If rotation type is not supported
- callback(color_data: sensor_msgs.msg.Image, cam_info: sensor_msgs.msg.CameraInfo | None = None)¶
-
Process synchronized RGB image and camera info messages.
TODO make this generic. handle the encoding and order properly. For standard and compressed images. this might also depend on the fix of image_transport_plugins being published as a package. Startpoint can be found at the bottom of this method.
- Parameters:
-
color_data (sensor_msgs.msg.Image) – RGB image message
cam_info (sensor_msgs.msg.CameraInfo, optional) – Camera calibration info message, defaults to None
- set_data(cas: robokudo.cas.CAS)¶
-
Update the Common Analysis Structure with latest camera data.
This method: * Applies any configured image rotation * Updates camera intrinsics accordingly * Sets RGB image, camera info, and transform data in the CAS * Handles thread synchronization
- Parameters:
-
cas (robokudo.cas.CAS) – Common Analysis Structure to update