Skip to content

Commit eb4fe6a

Browse files
simonschmeisserSimon Schmeisser
authored andcommitted
use separate queue that is synchronous
while the documentation suggests this, getUpdateQueue returns the global callback queue which might be processed in different threads if AsyncSpinner is used or other threads call ros::spinOnce
1 parent ba536b2 commit eb4fe6a

File tree

1 file changed

+3
-2
lines changed

1 file changed

+3
-2
lines changed

src/rviz/visualization_manager.cpp

Lines changed: 3 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -111,6 +111,7 @@ class VisualizationManagerPrivate
111111
{
112112
public:
113113
ros::CallbackQueue threaded_queue_;
114+
ros::CallbackQueue update_queue_;
114115
boost::thread_group threaded_queue_threads_;
115116
ros::NodeHandle update_nh_;
116117
ros::NodeHandle threaded_nh_;
@@ -269,7 +270,7 @@ void VisualizationManager::unlockRender()
269270

270271
ros::CallbackQueueInterface* VisualizationManager::getUpdateQueue()
271272
{
272-
return ros::getGlobalCallbackQueue();
273+
return &private_->update_queue_;
273274
}
274275

275276
void VisualizationManager::startUpdate()
@@ -330,7 +331,7 @@ void VisualizationManager::onUpdate()
330331
resetTime();
331332
}
332333

333-
ros::spinOnce();
334+
private_->update_queue_.callAvailable(ros::WallDuration(0.01));
334335

335336
Q_EMIT preUpdate();
336337

0 commit comments

Comments
 (0)