robokudo.io.camera_interface

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

CameraInterface

Base class for all camera interfaces in RoboKudo.

ROSCameraInterface

Base class for ROS-based camera interfaces.

KinectCameraInterface

Interface for Kinect-style RGB-D cameras using ROS.

Functions

depth_convert_workaround(→ numpy.typing.NDArray)

Convert compressed depth image to proper depth format.

Module Contents

class robokudo.io.camera_interface.CameraInterface(camera_config: typing_extensions.Any)

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

_has_new_data: bool = False

Whether new data is available

camera_config: typing_extensions.Any

Camera configuration object

rk_logger: logging.Logger = None

RoboKudo logger instance

has_new_data() bool

Check if new data is available.

Returns:

True if new data is available, False otherwise

abstract set_data(cas: robokudo.cas.CAS) None

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.

Parameters:

cas – The CAS where the data should be placed in

class robokudo.io.camera_interface.ROSCameraInterface(camera_config: typing_extensions.Any, node: typing_extensions.Optional[rclpy.node.Node] = None)

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

node = None

ROS node for communication with ROS

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 from TF

lookup_transform() bool

Look up the camera transform from TF.

Returns:

True if transform lookup succeeded, False otherwise

store_cam_to_world_transform(cas: robokudo.cas.CAS, timestamp: builtin_interfaces.msg.Time) None

If the camera is configured to look up transforms, store the camera transform in the CAS.

Parameters:
  • cas – The CAS to store the transform in

  • timestamp – The timestamp of the transform

static store_legacy_cam_to_world_transform_from_cas(cas: robokudo.cas.CAS) None

Create legacy StampedTransform from CAS cam_to_world_transform and data_timestamp.

Parameters:

cas – The CAS to store the transform in

set_o3d_cam_intrinsics_from_ros_cam_info() None

Convert ROS camera info to Open3D camera intrinsics.

Creates an Open3D camera intrinsics object from the ROS camera calibration parameters.

robokudo.io.camera_interface.depth_convert_workaround(msg: sensor_msgs.msg.CompressedImage) numpy.typing.NDArray

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/

Parameters:

msg – Compressed depth image message

Returns:

Depth image as numpy array

Raises:

Exception – If compression type is wrong or decoding fails

class robokudo.io.camera_interface.KinectCameraInterface(camera_config: typing_extensions.Any)

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

color_subscriber: message_filters.Subscriber

Color image subscriber

depth_subscriber: message_filters.Subscriber

Depth image subscriber

cam_info_subscriber: message_filters.Subscriber

Camera info subscriber

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

Latest color image

depth: typing_extensions.Optional[numpy.typing.NDArray] = None

Latest depth image

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

Latest camera info message

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

Open3D camera intrinsics

color2depth_ratio: typing_extensions.Optional[typing_extensions.Tuple[float, float]] = None

Ratio between color and depth image sizes

timestamp: typing_extensions.Optional[float] = None

Latest message timestamp

lock: threading.Lock

Thread synchronization lock

compressed_depth_configured() bool

Check if compressed depth images are configured.

Returns:

True if compressed depth is configured, False otherwise

compressed_color_configured() bool

Check if compressed color images are configured.

Returns:

True if compressed color is configured, False otherwise

get_node() rclpy.node.Node
blackhole_callback(data: typing_extensions.Any) None

This callback is just a dummy to receive data coming from a workaround subscription to handle problems with the ApproximateTimeSynchronizer

Parameters:

data – Dummy data

callback(color_data: typing_extensions.Union[sensor_msgs.msg.Image, sensor_msgs.msg.CompressedImage], depth_data: typing_extensions.Optional[typing_extensions.Union[sensor_msgs.msg.Image, sensor_msgs.msg.CompressedImage]] = None, cam_info: typing_extensions.Optional[sensor_msgs.msg.CameraInfo] = None) 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.

Parameters:
  • color_data – Color image message

  • depth_data – Depth image message

  • cam_info – Camera calibration message

set_data(cas: robokudo.cas.CAS) None

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.

Parameters:

cas – The CAS where the data should be placed in