Skip to content

Commit 43b2260

Browse files
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 6bf5975 commit 43b2260

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_;
@@ -286,7 +287,7 @@ void VisualizationManager::unlockRender()
286287

287288
ros::CallbackQueueInterface* VisualizationManager::getUpdateQueue()
288289
{
289-
return ros::getGlobalCallbackQueue();
290+
return &private_->update_queue_;
290291
}
291292

292293
void VisualizationManager::startUpdate()
@@ -344,7 +345,7 @@ void VisualizationManager::onUpdate()
344345
resetTime();
345346
}
346347

347-
ros::spinOnce();
348+
private_->update_queue_.callAvailable(ros::WallDuration(0.01));
348349

349350
Q_EMIT preUpdate();
350351

0 commit comments

Comments
 (0)