Skip to content

Commit

Permalink
Fixed issue where spinning would not stop before application exit.
Browse files Browse the repository at this point in the history
Refactoring.
  • Loading branch information
StefanFabian committed May 11, 2021
1 parent 4c91238 commit 77d4dff
Show file tree
Hide file tree
Showing 4 changed files with 47 additions and 9 deletions.
2 changes: 2 additions & 0 deletions include/qml_ros_plugin/image_transport_manager.h
Original file line number Diff line number Diff line change
Expand Up @@ -9,6 +9,7 @@

#include <image_transport/image_transport.h>
#include <QAbstractVideoSurface>
#include <mutex>

namespace qml_ros_plugin
{
Expand Down Expand Up @@ -67,6 +68,7 @@ class ImageTransportManager

std::map<std::string, std::shared_ptr<SubscriptionManager>> subscriptions_;
std::vector<long> timeouts_;
std::mutex load_balancer_mutex_;
bool load_balancing_enabled_ = true;

friend class ImageTransportSubscriptionHandle;
Expand Down
7 changes: 7 additions & 0 deletions include/qml_ros_plugin/ros.h
Original file line number Diff line number Diff line change
Expand Up @@ -151,6 +151,12 @@ Q_OBJECT
*/
std::shared_ptr<ros::CallbackQueue> callbackQueue();

//! Increases the spin counter and if it was 0, starts spinning.
void startSpinning();

//! Decreases the spin counter and if it gets to 0, stops spinning.
void stopSpinning();

signals:

//! Emitted once when ROS was initialized.
Expand All @@ -174,6 +180,7 @@ protected slots:
std::shared_ptr<ros::CallbackQueue> callback_queue_;
std::unique_ptr<ros::AsyncSpinner> spinner_;
int threads_;
std::atomic<int> count_start_spinning_;
bool initialized_;
};

Expand Down
16 changes: 11 additions & 5 deletions src/image_transport_manager.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -22,7 +22,7 @@ struct ImageTransportManager::SubscriptionManager
std::unique_ptr<image_transport::ImageTransport> transport;
};

class ImageTransportManager::Subscription : public QObject
class ImageTransportManager::Subscription final : public QObject
{
Q_OBJECT
public:
Expand All @@ -38,6 +38,11 @@ Q_OBJECT
QObject::connect( &throttle_timer, &QTimer::timeout, this, &ImageTransportManager::Subscription::subscribe );
}

~Subscription() final
{
throttle_timer.stop();
}

int getThrottleInterval()
{
return std::accumulate( subscription_handles_.begin(), subscription_handles_.end(), std::numeric_limits<int>::max(),
Expand All @@ -52,7 +57,7 @@ Q_OBJECT
void updateTimer()
{
int min_interval = getThrottleInterval();
if ( min_interval == 0 )
if ( min_interval <= 0 )
{
throttle_timer.stop();
if ( !subscriber_ ) subscribe();
Expand All @@ -67,7 +72,7 @@ Q_OBJECT
{
int interval = getThrottleInterval();
int timeout = interval == 0 ? 0 : manager->getLoadBalancedTimeout( interval );
if ( timeout == 0 ) subscribe();
if ( timeout <= 0 ) subscribe();
else throttle_timer.start( timeout );
}

Expand Down Expand Up @@ -293,11 +298,12 @@ ImageTransportManager::subscribe( const NodeHandle::Ptr &nh, const QString &qtop
int ImageTransportManager::getLoadBalancedTimeout( int desired_throttle_interval )
{
if ( !load_balancing_enabled_ ) return desired_throttle_interval;
std::lock_guard<std::mutex> load_balancing_lock( load_balancer_mutex_ );
long now = std::chrono::duration_cast<std::chrono::milliseconds>(
std::chrono::system_clock::now().time_since_epoch()).count();
long timeout = now + desired_throttle_interval;
long largest_gap = 0;
size_t ind_largest_gap = timeouts_.empty() ? 0 : timeouts_[0] - now;
long largest_gap = timeouts_.empty() ? 0 : timeouts_[0] - now;
size_t ind_largest_gap = 0;
// Very unsophisticated method. We just find the largest gap before the desired interval and insert the timeout in the middle
for ( size_t i = 1; i < timeouts_.size(); ++i )
{
Expand Down
31 changes: 27 additions & 4 deletions src/ros.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -199,16 +199,35 @@ void RosQml::updateSpinner()
return;
}
spinner_.reset( new ros::AsyncSpinner( threads_, callback_queue_.get()));
spinner_->start();
if ( count_start_spinning_ > 0 ) spinner_->start();
}

Console RosQml::console() const { return {}; }

Package RosQml::package() const { return {}; }

std::shared_ptr<ros::CallbackQueue> RosQml::callbackQueue()
std::shared_ptr<ros::CallbackQueue> RosQml::callbackQueue() { return callback_queue_; }

void RosQml::startSpinning()
{
if ( count_start_spinning_++ == 0 )
{
if ( spinner_ ) spinner_->start();
}
}

void RosQml::stopSpinning()
{
return callback_queue_;
int count = --count_start_spinning_;
if ( count == 0 )
{
if ( spinner_ ) spinner_->stop();
}
else if ( count < 0 )
{
ROS_ERROR_NAMED( "qml_ros_plugin", "Stop spinning was called more often than start spinning! This is a bug!" );
count_start_spinning_ += -count;
}
}

/***************************************************************************************************/
Expand All @@ -219,9 +238,13 @@ RosQmlSingletonWrapper::RosQmlSingletonWrapper()
{
connect( &RosQml::getInstance(), &RosQml::initialized, this, &RosQmlSingletonWrapper::initialized );
connect( &RosQml::getInstance(), &RosQml::shutdown, this, &RosQmlSingletonWrapper::shutdown );
RosQml::getInstance().startSpinning();
}

RosQmlSingletonWrapper::~RosQmlSingletonWrapper() = default;
RosQmlSingletonWrapper::~RosQmlSingletonWrapper()
{
RosQml::getInstance().stopSpinning();
}

bool RosQmlSingletonWrapper::isInitialized() const
{
Expand Down

0 comments on commit 77d4dff

Please sign in to comment.