robokudo.io.ros_camera_without_depth_interface ============================================== .. py:module:: robokudo.io.ros_camera_without_depth_interface .. autoapi-nested-parse:: 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 ------- .. autoapisummary:: robokudo.io.ros_camera_without_depth_interface.ROSCameraWithoutDepthInterface Module Contents --------------- .. py:class:: ROSCameraWithoutDepthInterface(camera_config) Bases: :py:obj:`robokudo.io.camera_interface.ROSCameraInterface` A 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. :ivar color_subscriber: Subscriber for RGB image topic :type color_subscriber: message_filters.Subscriber :ivar cam_info_subscriber: Subscriber for camera info topic :type cam_info_subscriber: message_filters.Subscriber :ivar color: Latest RGB image data :type color: numpy.ndarray :ivar cam_info: Latest camera calibration info :type cam_info: sensor_msgs.msg.CameraInfo :ivar cam_intrinsic: Camera intrinsic parameters in Open3D format :type cam_intrinsic: open3d.camera.PinholeCameraIntrinsic :ivar color2depth_ratio: Always (1,1) since no depth data :type color2depth_ratio: tuple :ivar cam_translation: Camera translation from TF :type cam_translation: list :ivar cam_quaternion: Camera rotation as quaternion from TF :type cam_quaternion: list :ivar timestamp: Timestamp of latest data :type timestamp: rospy.Time :ivar lock: Thread synchronization lock :type lock: threading.Lock :ivar bridge: Bridge for converting between ROS and OpenCV images :type bridge: cv_bridge.CvBridge .. py:attribute:: color_subscriber .. py:attribute:: cam_info_subscriber .. py:attribute:: color :value: None .. py:attribute:: cam_info :value: None .. py:attribute:: cam_intrinsic :value: None .. py:attribute:: color2depth_ratio :value: None .. py:attribute:: cam_translation :value: None .. py:attribute:: cam_quaternion :value: None .. py:attribute:: timestamp :value: None .. py:attribute:: lock .. py:attribute:: bridge .. py:method:: 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. :param K: Original camera intrinsic matrix of shape (3, 3) :type K: numpy.ndarray :param image_size: Original image dimensions as (width, height) :type image_size: tuple :param rotation: '90_ccw', '90_cw', '180' (default is 90° counter-clockwise) :type rotation: str, optional :return: Tuple of (new intrinsics matrix, new image dimensions) :rtype: tuple(numpy.ndarray, tuple(int, int)) :raises ValueError: If rotation type is not supported .. py:method:: rotate_image_and_intrinsics(img, K, rotation='90_ccw') Rotate an image and adjust its camera intrinsics accordingly. :param img: Input image to rotate :type img: numpy.ndarray :param K: Camera intrinsics matrix :type K: numpy.ndarray :param rotation: Type of rotation to apply, defaults to '90_ccw' :type rotation: str, optional :return: Tuple of (rotated image, new intrinsics matrix, new dimensions) :rtype: tuple(numpy.ndarray, numpy.ndarray, tuple) :raises ValueError: If rotation type is not supported .. py:method:: callback(color_data: sensor_msgs.msg.Image, cam_info: Optional[sensor_msgs.msg.CameraInfo] = 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. :param color_data: RGB image message :type color_data: sensor_msgs.msg.Image :param cam_info: Camera calibration info message, defaults to None :type cam_info: sensor_msgs.msg.CameraInfo, optional .. py:method:: 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 :param cas: Common Analysis Structure to update :type cas: robokudo.cas.CAS