From 3566276a76f7de9098cbf5cc2a5727fbde749986 Mon Sep 17 00:00:00 2001 From: Stefan Fabian Date: Fri, 16 Aug 2024 20:58:43 +0200 Subject: [PATCH] Removed throttling of image topics. 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. --- docs/pages/ImageTransport.rst | 16 +- examples/image_subscription.qml | 24 +- .../image_transport_manager.hpp | 27 +- .../image_transport_subscription.hpp | 12 +- src/image_transport_manager.cpp | 309 ++---------------- src/image_transport_subscription.cpp | 13 +- 6 files changed, 58 insertions(+), 343 deletions(-) diff --git a/docs/pages/ImageTransport.rst b/docs/pages/ImageTransport.rst index ea0b946..679656b 100644 --- a/docs/pages/ImageTransport.rst +++ b/docs/pages/ImageTransport.rst @@ -30,22 +30,12 @@ The :cpp:class:`ImageTransportSubscription ` -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: diff --git a/examples/image_subscription.qml b/examples/image_subscription.qml index 7714b18..7e8fe47 100644 --- a/examples/image_subscription.qml +++ b/examples/image_subscription.qml @@ -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 @@ -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: { diff --git a/include/qml_ros2_plugin/image_transport_manager.hpp b/include/qml_ros2_plugin/image_transport_manager.hpp index 082c910..dd629d7 100644 --- a/include/qml_ros2_plugin/image_transport_manager.hpp +++ b/include/qml_ros2_plugin/image_transport_manager.hpp @@ -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. @@ -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! * @@ -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 &callback, - QAbstractVideoSurface *surface = nullptr, int throttle_interval = 0 ); + QAbstractVideoSurface *surface = nullptr ); private: - std::map> subscriptions_; - std::unique_ptr load_balancer_; + std::shared_ptr subscription_manager_; friend class ImageTransportSubscriptionHandle; }; @@ -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; @@ -101,7 +79,6 @@ class ImageTransportSubscriptionHandle QAbstractVideoSurface *surface = nullptr; std::function callback; double framerate_ = 0; - int throttle_interval = 0; int network_latency = -1; int processing_latency = -1; diff --git a/include/qml_ros2_plugin/image_transport_subscription.hpp b/include/qml_ros2_plugin/image_transport_subscription.hpp index 4928ffb..fce5202 100644 --- a/include/qml_ros2_plugin/image_transport_subscription.hpp +++ b/include/qml_ros2_plugin/image_transport_subscription.hpp @@ -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: @@ -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 ); diff --git a/src/image_transport_manager.cpp b/src/image_transport_manager.cpp index 98d08c7..155f329 100644 --- a/src/image_transport_manager.cpp +++ b/src/image_transport_manager.cpp @@ -26,60 +26,6 @@ struct ImageTransportManager::SubscriptionManager { std::unique_ptr transport; }; -class ImageTransportManager::LoadBalancer : public QObject -{ - Q_OBJECT -public: - LoadBalancer() - { - connect( &timer_, &QTimer::timeout, this, &ImageTransportManager::LoadBalancer::onTimeout ); - timer_.setInterval( 33 ); - timer_.setSingleShot( false ); - timer_.start(); - } - - void setEnabled( bool value ) { load_balancing_enabled_ = value; } - - void notifyImageReceived( ImageTransportManager::Subscription *subscription, - long throttle_interval ); - - void registerThrottledSubscription( ImageTransportManager::Subscription *subscription ); - - void unregister( ImageTransportManager::Subscription *subscription ); - -private slots: - - void onTimeout() - { - // Triggers subscription for all expired timeouts and restarts the timer unless no more timeouts are active - std::lock_guard lock( mutex_ ); - using namespace std::chrono; - size_t i = 0; - long now = - duration_cast( system_clock::now().time_since_epoch() ).count(); - std::vector ready; - for ( ; i < timeouts_.size(); ++i ) { - if ( timeouts_[i].first > now ) - break; - ready.push_back( timeouts_[i].second ); - } - for ( auto &sub : ready ) triggerSubscription( sub ); - } - -private: - void triggerSubscription( ImageTransportManager::Subscription *subscription ); - - void insertTimeout( long desired_throttle_interval, - ImageTransportManager::Subscription *subscription ); - - QTimer timer_; - std::set waiting_subscriptions_; - std::vector new_subscriptions_; - std::vector> timeouts_; - std::mutex mutex_; - bool load_balancing_enabled_ = true; -}; - class ImageTransportManager::Subscription final : public QObject { Q_OBJECT @@ -90,41 +36,9 @@ class ImageTransportManager::Subscription final : public QObject ImageTransportManager *manager = nullptr; quint32 queue_size = 0; - Subscription( image_transport::TransportHints hints ) : hints( std::move( hints ) ) { } - - ~Subscription() final - { - if ( throttled_ ) - manager->load_balancer_->unregister( this ); - } + explicit Subscription( image_transport::TransportHints hints ) : hints( std::move( hints ) ) { } - int getThrottleInterval() const - { - int interval = std::accumulate( - subscription_handles_.begin(), subscription_handles_.end(), std::numeric_limits::max(), - []( int current, const std::weak_ptr &sub_weak ) { - std::shared_ptr sub = sub_weak.lock(); - if ( sub == nullptr ) - return current; - return std::min( current, sub->throttle_interval ); - } ); - return interval == std::numeric_limits::max() ? current_throttle_interval_ : interval; - } - - void updateThrottling() - { - int min_interval = getThrottleInterval(); - if ( min_interval <= 0 ) { - if ( throttled_ ) - manager->load_balancer_->unregister( this ); - throttled_ = false; - if ( !subscriber_ ) - subscribe(); - } else if ( !throttled_ ) { - throttled_ = true; - manager->load_balancer_->registerThrottledSubscription( this ); - } - } + ~Subscription() override = default; void subscribe() { @@ -143,11 +57,10 @@ class ImageTransportManager::Subscription final : public QObject void addSubscription( const std::shared_ptr &sub ) { - std::lock_guard subscriptions_lock( subscriptions_mutex_ ); + std::lock_guard subscriptions_lock( subscriptions_mutex_ ); subscriptions_.push_back( sub.get() ); subscription_handles_.push_back( sub ); updateSupportedFormats(); - updateThrottling(); // If this was the first subscription, subscribe if ( subscriptions_.size() == 1 ) subscribe(); @@ -155,7 +68,7 @@ class ImageTransportManager::Subscription final : public QObject void removeSubscription( const ImageTransportSubscriptionHandle *sub ) { - std::lock_guard subscriptions_lock( subscriptions_mutex_ ); + std::lock_guard subscriptions_lock( subscriptions_mutex_ ); auto it = std::find_if( subscriptions_.begin(), subscriptions_.end(), [sub]( const ImageTransportSubscriptionHandle *handle ) { return handle == sub; } ); @@ -168,7 +81,6 @@ class ImageTransportManager::Subscription final : public QObject subscriptions_.erase( it ); subscription_handles_.erase( subscription_handles_.begin() + index ); updateSupportedFormats(); - updateThrottling(); } std::string getTopic() const @@ -185,50 +97,19 @@ class ImageTransportManager::Subscription final : public QObject private: void imageCallback( const sensor_msgs::msg::Image::ConstSharedPtr &image ) { - // Ignore image if timestamp did not differ which seems to be a bug of some gazebo camera plugins when throttling - if ( throttled_ && rclcpp::Time( image->header.stamp ).nanoseconds() != 0 && - last_image_ != nullptr && last_image_->header.stamp == image->header.stamp ) - return; - rclcpp::Time received_stamp = clock_.now(); - // Check if we have to throttle - int interval = getThrottleInterval(); - if ( throttled_ ) { - if ( interval != 0 && interval > camera_base_interval_ ) { - { - std::lock_guard lock( subscribe_mutex_ ); - subscriber_.shutdown(); - } - manager->load_balancer_->notifyImageReceived( this, interval ); - } else { - // No need to throttle - manager->load_balancer_->unregister( this ); - throttled_ = false; - } - } else if ( interval != 0 && interval > camera_base_interval_ * - 1.1 ) // 10% off for hysteresis to prevent oscillation - { - // Need to throttle now - { - std::lock_guard lock( subscribe_mutex_ ); - subscriber_.shutdown(); - } - manager->load_balancer_->registerThrottledSubscription( this ); - throttled_ = true; - } QList formats; { - std::lock_guard subscription_lock( subscriptions_mutex_ ); + std::lock_guard subscription_lock( subscriptions_mutex_ ); if ( subscription_handles_.empty() ) return; formats = supported_formats_; } - auto buffer = new ImageBuffer( image, formats ); + auto buffer = std::make_unique( image, formats ); { - std::lock_guard image_lock( image_mutex_ ); - if ( !throttled_ && last_image_ != nullptr ) { - // Update the base interval only if we are not throttled + std::lock_guard image_lock( image_mutex_ ); + if (last_image_ != nullptr ) { if ( rclcpp::Time( last_image_->header.stamp ).nanoseconds() == 0 ) camera_base_interval_ = static_cast( ( received_stamp - last_received_stamp_ ).nanoseconds() / ( 1000 * 1000 ) ); @@ -236,13 +117,10 @@ class ImageTransportManager::Subscription final : public QObject camera_base_interval_ = static_cast( ( rclcpp::Time( image->header.stamp ) - last_image_->header.stamp ).nanoseconds() / ( 1000 * 1000 ) ); - } else if ( throttled_ ) { - current_throttle_interval_ = interval; } last_received_stamp_ = received_stamp; last_image_ = image; - delete last_buffer_; - last_buffer_ = buffer; + last_buffer_ = std::move( buffer ); } // Deliver frames on UI thread QMetaObject::invokeMethod( this, "imageDelivery", Qt::AutoConnection ); @@ -255,20 +133,20 @@ class ImageTransportManager::Subscription final : public QObject rclcpp::Time received; int base_interval; { - std::lock_guard image_lock( image_mutex_ ); + std::lock_guard image_lock( image_mutex_ ); if ( last_buffer_ == nullptr || last_image_ == nullptr ) return; - buffer = last_buffer_; + buffer = last_buffer_.release(); image = last_image_; received = last_received_stamp_; - base_interval = throttled_ ? current_throttle_interval_ : camera_base_interval_; + base_interval = camera_base_interval_; last_buffer_ = nullptr; } QVideoFrame frame( buffer, QSize( image->width, image->height ), buffer->format() ); std::vector> subscribers; { // This nested lock makes sure that our destruction of the subscription pointer will not lead to a deadlock - std::lock_guard subscriptions_lock( subscriptions_mutex_ ); + std::lock_guard subscriptions_lock( subscriptions_mutex_ ); for ( const auto &sub_weak : subscription_handles_ ) { if ( sub_weak.expired() ) continue; @@ -280,7 +158,7 @@ class ImageTransportManager::Subscription final : public QObject ? static_cast( ( received - image_stamp ).seconds() * 1000 ) : -1; network_latency_average_.add( network_latency ); - int processing_latency = static_cast( ( clock_.now() - received ).seconds() * 1000 ); + auto processing_latency = static_cast( ( clock_.now() - received ).seconds() * 1000 ); processing_latency_average_.add( processing_latency ); image_interval_average_.add( base_interval ); for ( const auto &sub : subscribers ) { @@ -328,122 +206,17 @@ class ImageTransportManager::Subscription final : public QObject rclcpp::Clock clock_ = rclcpp::Clock( RCL_ROS_TIME ); rclcpp::Time last_received_stamp_; sensor_msgs::msg::Image::ConstSharedPtr last_image_; - ImageBuffer *last_buffer_ = nullptr; + std::unique_ptr last_buffer_ = nullptr; int camera_base_interval_ = 0; - int current_throttle_interval_ = 0; - bool throttled_ = false; }; -// ============================= Load Balancing ============================= -void ImageTransportManager::LoadBalancer::notifyImageReceived( - ImageTransportManager::Subscription *subscription, long throttle_interval ) -{ - std::lock_guard lock( mutex_ ); - waiting_subscriptions_.erase( subscription ); - insertTimeout( throttle_interval, subscription ); - if ( !waiting_subscriptions_.empty() && !new_subscriptions_.empty() ) { - // Can trigger the next camera if we have new subscriptions - triggerSubscription( new_subscriptions_.front() ); - } -} - -void ImageTransportManager::LoadBalancer::registerThrottledSubscription( Subscription *subscription ) -{ - std::lock_guard lock( mutex_ ); - for ( auto &timeout : timeouts_ ) - if ( timeout.second == subscription ) - return; - insertTimeout( subscription->getThrottleInterval(), subscription ); - if ( !waiting_subscriptions_.empty() ) { - new_subscriptions_.push_back( subscription ); - return; - } - triggerSubscription( subscription ); -} - -void ImageTransportManager::LoadBalancer::unregister( ImageTransportManager::Subscription *subscription ) -{ - std::lock_guard lock( mutex_ ); - waiting_subscriptions_.erase( subscription ); - new_subscriptions_.erase( - std::remove( new_subscriptions_.begin(), new_subscriptions_.end(), subscription ), - new_subscriptions_.end() ); - timeouts_.erase( - std::remove_if( timeouts_.begin(), timeouts_.end(), - [subscription]( auto item ) { return item.second == subscription; } ), - timeouts_.end() ); -} - -void ImageTransportManager::LoadBalancer::triggerSubscription( - ImageTransportManager::Subscription *subscription ) -{ - new_subscriptions_.erase( - std::remove( new_subscriptions_.begin(), new_subscriptions_.end(), subscription ), - new_subscriptions_.end() ); - timeouts_.erase( - std::remove_if( timeouts_.begin(), timeouts_.end(), - [subscription]( auto item ) { return item.second == subscription; } ), - timeouts_.end() ); - - waiting_subscriptions_.insert( subscription ); - subscription->subscribe(); -} - -void ImageTransportManager::LoadBalancer::insertTimeout( - const long desired_throttle_interval, ImageTransportManager::Subscription *subscription ) -{ - const auto now = std::chrono::duration_cast( - std::chrono::system_clock::now().time_since_epoch() ) - .count(); - long timeout = now + desired_throttle_interval; - if ( !load_balancing_enabled_ ) { - std::pair value( timeout, subscription ); - timeouts_.insert( std::upper_bound( timeouts_.begin(), timeouts_.end(), value, - []( auto a, auto b ) { return a.first < b.first; } ), - value ); - return; - } - long largest_gap = timeouts_.empty() ? 0 : timeouts_[0].first - now; - size_t ind_largest_gap = 0; - // Very unsophisticated method. We just find the largest gap before the desired interval and insert the desired_throttle_interval in the middle - for ( size_t i = 1; i < timeouts_.size(); ++i ) { - if ( timeouts_[i - 1].first > timeout ) - break; - long gap; - // Gap is either between two timeouts or between now and the first desired_throttle_interval that is not in the past - if ( timeouts_[i - 1].first < now ) { - if ( timeouts_[i].first <= now ) - continue; - gap = timeouts_[i].first - now; - } else { - gap = timeouts_[i].first > timeout ? timeout - timeouts_[i - 1].first - : timeouts_[i].first - timeouts_[i - 1].first; - } - if ( gap <= largest_gap ) - continue; - ind_largest_gap = i; - largest_gap = gap; - } - // Update timeout if inserting it with the desired timeout wouldn't create a larger gap (which can only happen if it is inserted at the end) - if ( !timeouts_.empty() && timeout - timeouts_.back().first < largest_gap / 2 ) { - timeout = timeouts_[ind_largest_gap].first - largest_gap / 2; - } - // We insert the desired_throttle_interval in the table so that the timeouts are sorted or before now - std::pair value( timeout, subscription ); - timeouts_.insert( std::upper_bound( timeouts_.begin(), timeouts_.end(), value, - []( auto a, auto b ) { return a.first < b.first; } ), - value ); -} - ImageTransportSubscriptionHandle::~ImageTransportSubscriptionHandle() { - subscription->removeSubscription( this ); -} - -void ImageTransportSubscriptionHandle::updateThrottleInterval( int interval ) -{ - throttle_interval = interval; - subscription->updateThrottling(); + try { + subscription->removeSubscription( this ); + } catch ( std::exception &ex ) { + QML_ROS2_PLUGIN_ERROR( "Error while removing subscription: %s", ex.what() ); + } } std::string ImageTransportSubscriptionHandle::getTopic() const { return subscription->getTopic(); } @@ -459,10 +232,7 @@ int ImageTransportSubscriptionHandle::processingLatency() const { return process double ImageTransportSubscriptionHandle::framerate() const { return framerate_; } -ImageTransportManager::ImageTransportManager() -{ - load_balancer_ = std::make_unique(); -} +ImageTransportManager::ImageTransportManager() = default; ImageTransportManager &ImageTransportManager::getInstance() { @@ -470,22 +240,16 @@ ImageTransportManager &ImageTransportManager::getInstance() return manager; } -std::shared_ptr -ImageTransportManager::subscribe( const rclcpp::Node::SharedPtr &node, const QString &qtopic, - quint32 queue_size, - const image_transport::TransportHints &transport_hints, - const std::function &callback, - QAbstractVideoSurface *surface, int throttle_interval ) +std::shared_ptr ImageTransportManager::subscribe( + const rclcpp::Node::SharedPtr &node, const QString &qtopic, quint32 queue_size, + const image_transport::TransportHints &transport_hints, + const std::function &callback, QAbstractVideoSurface *surface ) { - std::string ns = - ""; // Support for namespaces like in qml_ros_plugin might be added in the future or dropped completely - std::string topic = qtopic.toStdString(); - auto it = subscriptions_.find( ns ); - if ( it == subscriptions_.end() ) { - it = subscriptions_.insert( { topic, std::make_shared( node ) } ).first; + if ( subscription_manager_ == nullptr ) { + subscription_manager_ = std::make_shared( node ); } - std::shared_ptr &subscription_manager = it->second; - std::vector> &subscriptions = subscription_manager->subscriptions; + std::string topic = qtopic.toStdString(); + std::vector> &subscriptions = subscription_manager_->subscriptions; try { size_t i = 0; for ( ; i < subscriptions.size(); ++i ) { @@ -495,11 +259,10 @@ ImageTransportManager::subscribe( const rclcpp::Node::SharedPtr &node, const QSt auto handle = std::make_shared(); handle->surface = surface; handle->callback = callback; - handle->throttle_interval = throttle_interval; if ( i == subscriptions.size() ) { - auto sub = new Subscription( transport_hints ); + auto sub = std::make_shared( transport_hints ); sub->manager = this; - sub->subscription_manager = subscription_manager; + sub->subscription_manager = subscription_manager_; sub->topic = topic; sub->queue_size = queue_size; subscriptions.emplace_back( sub ); @@ -514,16 +277,6 @@ ImageTransportManager::subscribe( const rclcpp::Node::SharedPtr &node, const QSt } return nullptr; } - -void ImageTransportManager::setLoadBalancingEnabled( bool value ) -{ - load_balancer_->setEnabled( value ); -} - -void ImageTransportManagerSingletonWrapper::setLoadBalancingEnabled( bool value ) -{ - ImageTransportManager::getInstance().setLoadBalancingEnabled( value ); -} } // namespace qml_ros2_plugin #include "image_transport_manager.moc" diff --git a/src/image_transport_subscription.cpp b/src/image_transport_subscription.cpp index 28ca8e6..268d92e 100644 --- a/src/image_transport_subscription.cpp +++ b/src/image_transport_subscription.cpp @@ -71,7 +71,7 @@ void ImageTransportSubscription::initSubscriber() image_transport::TransportHints transport_hints( node.get(), default_transport_.toStdString() ); subscription_ = ImageTransportManager::getInstance().subscribe( node, topic_, queue_size_, transport_hints, - [this]( const QVideoFrame &frame ) { presentFrame( frame ); }, surface_, throttle_interval_ ); + [this]( const QVideoFrame &frame ) { presentFrame( frame ); }, surface_ ); subscribed_ = subscription_ != nullptr; if ( !was_subscribed ) emit subscribedChanged(); @@ -210,17 +210,6 @@ void ImageTransportSubscription::setTimeout( int value ) emit timeoutChanged(); } -double ImageTransportSubscription::throttleRate() const { return 1000.0 / throttle_interval_; } - -void ImageTransportSubscription::setThrottleRate( double value ) -{ - throttle_interval_ = value == 0 ? 0 : static_cast( 1000 / value ); - if ( subscription_ ) { - subscription_->updateThrottleInterval( throttle_interval_ ); - } - emit throttleRateChanged(); -} - bool ImageTransportSubscription::enabled() const { return enabled_; } void ImageTransportSubscription::setEnabled( bool value )