robokudo.io.camera_interface ============================ .. py:module:: robokudo.io.camera_interface .. autoapi-nested-parse:: Camera interface module for RoboKudo. This module provides base classes and implementations for interfacing with various camera types in RoboKudo. It supports: * ROS camera interfaces (raw and compressed) * Kinect-style RGB-D cameras * Camera calibration handling * Transform lookups * Synchronized data acquisition * Thread-safe operation The module handles: * RGB and depth image acquisition * Camera calibration information * Camera-to-world transforms * Data synchronization * Format conversions Classes ------- .. autoapisummary:: robokudo.io.camera_interface.CameraInterface robokudo.io.camera_interface.ROSCameraInterface robokudo.io.camera_interface.KinectCameraInterface Functions --------- .. autoapisummary:: robokudo.io.camera_interface.depth_convert_workaround Module Contents --------------- .. py:class:: CameraInterface(camera_config) Bases: :py:obj:`object` Base class for all camera interfaces in RoboKudo. This class defines the basic interface that all camera implementations must provide. It handles configuration and data availability tracking. :ivar _has_new_data: Whether new data is available :type _has_new_data: bool :ivar camera_config: Camera configuration object :type camera_config: Any :ivar rk_logger: RoboKudo logger instance :type rk_logger: logging.Logger .. py:attribute:: _has_new_data :value: False .. py:attribute:: camera_config .. py:attribute:: rk_logger .. py:method:: has_new_data() Check if new data is available. :return: True if new data is available, False otherwise :rtype: bool .. py:method:: set_data(cas: robokudo.cas.CAS) :abstractmethod: This method is supposed to read in, convert (if needed) and put the data into the CAS. If you are running a CameraInterface which is getting data via callback methods, please make sure to keep callbacks light and do the main conversion work here! Callbacks should be short. :param cas: The CAS where the data should be placed in :type cas: robokudo.cas.CAS .. py:class:: ROSCameraInterface(camera_config, node=None) Bases: :py:obj:`CameraInterface` Base class for ROS-based camera interfaces. This class extends the base camera interface with ROS-specific functionality like transform lookups and camera intrinsics handling. :ivar lookup_viewpoint: Whether to look up camera transforms :type lookup_viewpoint: bool :ivar tf_from: Transform source frame :type tf_from: str :ivar tf_to: Transform target frame :type tf_to: str :ivar transform_listener: ROS transform listener :type transform_listener: tf.TransformListener .. py:attribute:: node :value: None .. py:method:: lookup_transform() Look up the camera transform from TF. :return: True if transform lookup succeeded, False otherwise :rtype: bool .. py:method:: set_o3d_cam_intrinsics_from_ros_cam_info() Convert ROS camera info to Open3D camera intrinsics. Creates an Open3D camera intrinsics object from the ROS camera calibration parameters. .. py:function:: depth_convert_workaround(msg) Convert compressed depth image to proper depth format. This is a workaround for handling compressed depth images in ROS. Source: https://answers.ros.org/question/249775/display-compresseddepth-image-python-cv2/ :param msg: Compressed depth image message :type msg: sensor_msgs.msg.CompressedImage :return: Depth image as numpy array :rtype: numpy.ndarray :raises Exception: If compression type is wrong or decoding fails .. py:class:: KinectCameraInterface(camera_config) Bases: :py:obj:`ROSCameraInterface` Interface for Kinect-style RGB-D cameras using ROS. This class implements a camera interface for RGB-D cameras that publish color and depth images through ROS topics. It supports both raw and compressed image formats. :ivar color_subscriber: Color image subscriber :type color_subscriber: message_filters.Subscriber :ivar depth_subscriber: Depth image subscriber :type depth_subscriber: message_filters.Subscriber :ivar cam_info_subscriber: Camera info subscriber :type cam_info_subscriber: message_filters.Subscriber :ivar color: Latest color image :type color: numpy.ndarray :ivar depth: Latest depth image :type depth: numpy.ndarray :ivar cam_info: Latest camera calibration :type cam_info: sensor_msgs.msg.CameraInfo :ivar cam_intrinsic: Open3D camera intrinsics :type cam_intrinsic: o3d.camera.PinholeCameraIntrinsic :ivar color2depth_ratio: Ratio between color and depth image sizes :type color2depth_ratio: tuple :ivar cam_translation: Camera translation from TF :type cam_translation: list :ivar cam_quaternion: Camera rotation from TF :type cam_quaternion: list :ivar timestamp: Latest message timestamp :type timestamp: rospy.Time :ivar lock: Thread synchronization lock :type lock: threading.Lock .. py:attribute:: cam_info_subscriber .. py:attribute:: color :value: None .. py:attribute:: depth :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:method:: compressed_depth_configured() Check if compressed depth images are configured. :return: True if compressed depth is configured, False otherwise :rtype: bool .. py:method:: compressed_color_configured() Check if compressed color images are configured. :return: True if compressed color is configured, False otherwise :rtype: bool .. py:method:: get_node() .. py:method:: blackhole_callback(data) This callback is just a dummy to receive data coming from a workaround subscription to handle problems with the ApproximateTimeSynchronizer :param data: :return: .. py:method:: debug_callback(data) .. py:method:: debug_depth_callback(data) .. py:method:: debug_cam_info_callback(data) .. py:method:: callback(color_data, depth_data=None, cam_info=None) Process synchronized camera data. This callback handles incoming color, depth, and camera info messages. It converts the data to OpenCV format and stores it for later use. 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: Color image message :type color_data: sensor_msgs.msg.Image or sensor_msgs.msg.CompressedImage :param depth_data: Depth image message :type depth_data: sensor_msgs.msg.Image or sensor_msgs.msg.CompressedImage :param cam_info: Camera calibration message :type cam_info: sensor_msgs.msg.CameraInfo .. py:method:: set_data(cas: robokudo.cas.CAS) This method is supposed to read in, convert (if needed) and put the data into the CAS. If you are running a CameraInterface which is getting data via callback methods, please make sure to keep callbacks light and do the main conversion work here! Callbacks should be short. :param cas: The CAS where the data should be placed in :type cas: robokudo.cas.CAS