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(msg)

Convert compressed depth image to proper depth format.

Module Contents

class robokudo.io.camera_interface.CameraInterface(camera_config)

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.

Variables:
  • _has_new_data – Whether new data is available

  • camera_config – Camera configuration object

  • rk_logger – RoboKudo logger instance

_has_new_data = False
camera_config
rk_logger
has_new_data()

Check if new data is available.

Returns:

True if new data is available, False otherwise

Return type:

bool

abstract 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.

Parameters:

cas (robokudo.cas.CAS) – The CAS where the data should be placed in

class robokudo.io.camera_interface.ROSCameraInterface(camera_config, 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.

Variables:
  • lookup_viewpoint – Whether to look up camera transforms

  • tf_from – Transform source frame

  • tf_to – Transform target frame

  • transform_listener – ROS transform listener

node = None
lookup_transform()

Look up the camera transform from TF.

Returns:

True if transform lookup succeeded, False otherwise

Return type:

bool

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.

robokudo.io.camera_interface.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/

Parameters:

msg (sensor_msgs.msg.CompressedImage) – Compressed depth image message

Returns:

Depth image as numpy array

Return type:

numpy.ndarray

Raises:

Exception – If compression type is wrong or decoding fails

class robokudo.io.camera_interface.KinectCameraInterface(camera_config)

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.

Variables:
  • color_subscriber – Color image subscriber

  • depth_subscriber – Depth image subscriber

  • cam_info_subscriber – Camera info subscriber

  • color – Latest color image

  • depth – Latest depth image

  • cam_info – Latest camera calibration

  • cam_intrinsic – Open3D camera intrinsics

  • color2depth_ratio – Ratio between color and depth image sizes

  • cam_translation – Camera translation from TF

  • cam_quaternion – Camera rotation from TF

  • timestamp – Latest message timestamp

  • lock – Thread synchronization lock

cam_info_subscriber
color = None
depth = None
cam_info = None
cam_intrinsic = None
color2depth_ratio = None
cam_translation = None
cam_quaternion = None
timestamp = None
lock
compressed_depth_configured()

Check if compressed depth images are configured.

Returns:

True if compressed depth is configured, False otherwise

Return type:

bool

compressed_color_configured()

Check if compressed color images are configured.

Returns:

True if compressed color is configured, False otherwise

Return type:

bool

get_node()
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.

Parameters:
  • color_data (sensor_msgs.msg.Image or sensor_msgs.msg.CompressedImage) – Color image message

  • depth_data (sensor_msgs.msg.Image or sensor_msgs.msg.CompressedImage) – Depth image message

  • cam_info (sensor_msgs.msg.CameraInfo) – Camera calibration message

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.

Parameters:

cas (robokudo.cas.CAS) – The CAS where the data should be placed in