Skip to content

Commit

Permalink
Removed throttling of image topics.
Browse files Browse the repository at this point in the history
It was a good solution to a problem caused by a bad solution. This makes it by implication a bad solution. I've decided that it makes more sense to address the original issue and this shouldn't be part of the library.
If you need throttled image topics create a throttled publisher or better don't use ROS for images if network is an issue.
  • Loading branch information
StefanFabian committed Aug 16, 2024
1 parent b4e98de commit 3566276
Show file tree
Hide file tree
Showing 6 changed files with 58 additions and 343 deletions.
16 changes: 3 additions & 13 deletions docs/pages/ImageTransport.rst
Original file line number Diff line number Diff line change
Expand Up @@ -30,22 +30,12 @@ The :cpp:class:`ImageTransportSubscription <qml_ros2_plugin::ImageTransportSubsc
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
:cpp:func:`ImageTransportManager::setLoadBalancingEnabled <qml_ros2_plugin::ImageTransportManagerSingletonWrapper::setLoadBalancingEnabled>`
which is available in QML using the singleton ``ImageTransportManager``.

The QML ROS2 plugin internally keeps track of all image transport subscriptions and will only create one
shared subscription per topic to avoid unnecessary computation and bandwidth overhead.

API
---

.. doxygenclass:: qml_ros2_plugin::ImageTransportSubscription
:members:

.. doxygenclass:: qml_ros2_plugin::ImageTransportManagerSingletonWrapper
:members:
24 changes: 18 additions & 6 deletions examples/image_subscription.qml
Original file line number Diff line number Diff line change
Expand Up @@ -13,11 +13,12 @@ ApplicationWindow {
// This connection makes sure the application exits if this ROS node is requested to shutdown
Connections {
target: Ros2

function onShutdown() {
Qt.quit()
}
}

ImageTransportSubscription {
id: imageSubscription
// Enter a valid image topic here
Expand All @@ -26,12 +27,23 @@ ApplicationWindow {
// Requires the compressed_image_transport package to be installed
defaultTransport: "compressed"
}

VideoOutput {
GridLayout {
anchors.fill: parent
// Can be used in increments of 90 to rotate the video
orientation: 0
source: imageSubscription
anchors.margins: 12
columns: 1
Text {
text: "For this example,\n run the following in a separate terminal:"
}
TextInput {
readOnly: true
selectByMouse: true
text: "ros2 run examples_rclcpp_minimal_service service_main"
}
VideoOutput {
// Can be used in increments of 90 to rotate the video
orientation: 0
source: imageSubscription
}
}

Component.onCompleted: {
Expand Down
27 changes: 2 additions & 25 deletions include/qml_ros2_plugin/image_transport_manager.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -12,14 +12,6 @@ namespace qml_ros2_plugin
{
class ImageTransportSubscriptionHandle;

class ImageTransportManagerSingletonWrapper : public QObject
{
Q_OBJECT
public:
//! @copydoc ImageTransportManager::setLoadBalancingEnabled
Q_INVOKABLE void setLoadBalancingEnabled( bool value );
};

/*!
* Encapsulates the image transport communication to share the subscription resources, avoiding multiple conversions of
* the same image and subscription overhead if multiple cameras are set to throttle.
Expand All @@ -32,15 +24,9 @@ class ImageTransportManager

class Subscription;

class LoadBalancer;

public:
static ImageTransportManager &getInstance();

//! 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.
void setLoadBalancingEnabled( bool value );

/*!
* Note: Can only be called with a ready NodeHandle!
*
Expand All @@ -60,11 +46,10 @@ class ImageTransportManager
subscribe( const rclcpp::Node::SharedPtr &node, const QString &qtopic, quint32 queue_size,
const image_transport::TransportHints &transport_hints,
const std::function<void( const QVideoFrame & )> &callback,
QAbstractVideoSurface *surface = nullptr, int throttle_interval = 0 );
QAbstractVideoSurface *surface = nullptr );

private:
std::map<std::string, std::shared_ptr<SubscriptionManager>> subscriptions_;
std::unique_ptr<LoadBalancer> load_balancer_;
std::shared_ptr<SubscriptionManager> subscription_manager_;

friend class ImageTransportSubscriptionHandle;
};
Expand All @@ -74,13 +59,6 @@ class ImageTransportSubscriptionHandle
public:
~ImageTransportSubscriptionHandle();

//! The interval in ms the subscription waits between receiving images.
int throttleInterval() const { return throttle_interval; }

//! Set the interval in ms the subscription may wait between images.
//! The images may still arrive at a higher rate if other subscriptions request it.
void updateThrottleInterval( int interval );

//! The subscribed topic. Once subscribed this is the full topic name without the transport.
std::string getTopic() const;

Expand All @@ -101,7 +79,6 @@ class ImageTransportSubscriptionHandle
QAbstractVideoSurface *surface = nullptr;
std::function<void( const QVideoFrame & )> callback;
double framerate_ = 0;
int throttle_interval = 0;
int network_latency = -1;
int processing_latency = -1;

Expand Down
12 changes: 3 additions & 9 deletions include/qml_ros2_plugin/image_transport_subscription.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -32,21 +32,19 @@ class ImageTransportSubscription : public QObjectRos2
defaultTransportChanged )
//! Whether or not this ImageTransportSubscriber is subscribed to the given topic (readonly)
Q_PROPERTY( bool subscribed READ subscribed NOTIFY subscribedChanged )
//! 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)
//! The latency from the sender to the received time in ms not including the conversion latency before displaying. (readonly)
//! This is computed based on the timestamp and relies on your system clock being synchronized with the camera host.
Q_PROPERTY( int networkLatency READ networkLatency NOTIFY networkLatencyChanged )
//! The latency (in ms) from the reception of the image until it is in a displayable format. (readonly)
Q_PROPERTY( int processingLatency READ processingLatency NOTIFY processingLatencyChanged )
//! The full latency (in ms) from the camera to your display excluding drawing time. (readonly)
//! This is computed based on the timestamp and relies on your system clock being synchronized with the camera host.
Q_PROPERTY( int latency READ latency NOTIFY latencyChanged )
//! The framerate of the received camera frames in frames per second. (readonly)
Q_PROPERTY( double framerate READ framerate NOTIFY framerateChanged )
//! 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.
Q_PROPERTY( int timeout READ timeout WRITE setTimeout NOTIFY timeoutChanged )
//! The update rate to throttle image receiving in images per second. Set to 0 to disable
//! throttling. Default is 0 (disabled).
Q_PROPERTY( double throttleRate READ throttleRate WRITE setThrottleRate NOTIFY throttleRateChanged )
//! Whether the subscriber is active or not. Setting to false will shut down subscribers
Q_PROPERTY( bool enabled READ enabled WRITE setEnabled NOTIFY enabledChanged )
public:
Expand All @@ -72,10 +70,6 @@ class ImageTransportSubscription : public QObjectRos2

void setTimeout( int value );

double throttleRate() const;

void setThrottleRate( double value );

bool enabled() const;

void setEnabled( bool value );
Expand Down
Loading

0 comments on commit 3566276

Please sign in to comment.