ImageTransport

Seeing what the robot sees is one of the most important features of any user interface. To enable this, this library provides the ImageTransportSubscription. It allows easy subscription of camera messages and provides them in a QML native format as a VideoSource.

Example:

ImageTransportSubscription {
  id: imageSubscription
  // Enter a valid image topic here
  topic: "/front_rgbd_cam/color/image_rect_color"
  // This is the default transport, change if compressed is not available
  defaultTransport: "compressed"
}

VideoOutput {
  anchors.fill: parent
  // Can be used in increments of 90 to rotate the video
  orientation: 90
  source: imageSubscription
}

The ImageTransportSubscription can be used as the source of a VideoOutput to display the camera images as they are received. Additionally, it can be configured to show a blank image after x milliseconds using the timeout property which is set to 3000ms (3s) by default. This can be disabled by setting the timeout to 0. If you do not want the full camera rate, you can throttle the rate by setting throttleRate to a value greater than 0 (which is the default and disables throttling). E.g. a rate of 0.2 would show a new frame every 5 seconds. Since there is no ROS functionality for a throttled subscription, this means the image_transport::Subscriber is shut down and newly subscribed for each frame. This comes at some overhead, hence, it should only be used to throttle to low rates <1. To avoid all throttled subscribers subscribing at the same time causing huge network spikes, the throttled rates are load balanced by default. This can be disabled globally using ImageTransportManager::setLoadBalancingEnabled which is available in QML using the singleton ImageTransportManager.

API

class ImageTransportSubscription : public QObjectRos2

Properties

QAbstractVideoSurface * videoSurface

Interface for QML. This is the surface the images are passed to.

QString topic

The image base topic (without image_raw etc.). This value may change once the subscriber is connected and private topic names or remappings were evaluated.

QString defaultTransport

The default transport passed as transport hint. May be overridden by a parameter. (Default: compressed)

bool subscribed

Whether or not this ImageTransportSubscriber is subscribed to the given topic (readonly)

int networkLatency

The latency from the sender to the received time in ms not including the conversion latency before displaying. This latency is based on the ROS time of the sending and receiving machines, hence, they need to be synchronized. (readonly)

int processingLatency

The latency (in ms) from the reception of the image until it is in a displayable format. (readonly)

int latency

The full latency (in ms) from the camera to your display excluding drawing time. (readonly)

double framerate

The framerate of the received camera frames in frames per second. (readonly)

int timeout

The timeout when no image is received until a blank frame is served. Set to 0 to disable and always show last frame. Default is 3000 ms.

double throttleRate

The update rate to throttle image receiving in images per second. Set to 0 to disable throttling. Default is 0 (disabled).

bool enabled

Whether the subscriber is active or not. Setting to false will shut down subscribers.

class ImageTransportManagerSingletonWrapper : public QObject

Public Functions

void setLoadBalancingEnabled(bool value)

Sets whether the manager should try to balance throttled subscriptions_ to ensure they don’t update at the same time which would result in network spikes.