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

ROSCameraWithoutDepthInterface

A ROS camera interface for RGB-only cameras.

Module Contents

class robokudo.io.ros_camera_without_depth_interface.ROSCameraWithoutDepthInterface(camera_config: typing_extensions.Any)

Bases: 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.

color_subscriber: message_filters.Subscriber

Subscriber for RGB image topic

cam_info_subscriber: message_filters.Subscriber

Subscriber for camera info topic

color: typing_extensions.Optional[typing_extensions.Tuple[numpy.typing.NDArray]] = None

Latest RGB image data

cam_info: typing_extensions.Optional[sensor_msgs.msg.CameraInfo] = None

Latest camera calibration info

cam_intrinsic: typing_extensions.Optional[open3d.camera.PinholeCameraIntrinsic] = None

Camera intrinsic parameters in Open3D format

color2depth_ratio: typing_extensions.Optional[typing_extensions.Tuple[float, float]] = (1.0, 1.0)

Always (1.0, 1.0) since no depth data

cam_translation: typing_extensions.Optional[typing_extensions.List[float]] = None

Camera translation from TF

cam_quaternion: typing_extensions.Optional[typing_extensions.List[float]] = None

Camera rotation as quaternion from TF

timestamp: typing_extensions.Optional[float] = None

Timestamp of latest data

lock: threading.Lock

Thread synchronization lock

bridge: cv_bridge.CvBridge

Bridge for converting between ROS and OpenCV images

rotate_camera_intrinsics(K: numpy.typing.NDArray, image_size: typing_extensions.Tuple[int, int], rotation: str = '90_ccw') typing_extensions.Tuple[numpy.typing.NDArray, typing_extensions.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 – Original camera intrinsic matrix of shape (3, 3)

  • image_size – Original image dimensions as (width, height)

  • rotation – ‘90_ccw’, ‘90_cw’, ‘180’ (default is 90° counter-clockwise)

Returns:

Tuple of (new intrinsics matrix, new image dimensions)

Raises:

ValueError – If rotation type is not supported

rotate_image_and_intrinsics(img: numpy.typing.NDArray, K: numpy.typing.NDArray, rotation: str = '90_ccw') typing_extensions.Tuple[numpy.typing.NDArray, numpy.typing.NDArray, typing_extensions.Tuple[int, int]]

Rotate an image and adjust its camera intrinsics accordingly.

Parameters:
  • img – Input image to rotate

  • K – Camera intrinsics matrix

  • rotation – Type of rotation to apply, defaults to ‘90_ccw’

Returns:

Tuple of (rotated image, new intrinsics matrix, new dimensions)

Raises:

ValueError – If rotation type is not supported

callback(color_data: sensor_msgs.msg.Image, cam_info: typing_extensions.Optional[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 – RGB image message

  • cam_info – Camera calibration info message, defaults to None

set_data(cas: CAS) None

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 – Common Analysis Structure to update