Skip to content

Commit

Permalink
Synchronously call ros::spinOnce in rviz itself
Browse files Browse the repository at this point in the history
  • Loading branch information
simonschmeisser authored and Simon Schmeisser committed Apr 5, 2021
1 parent eb4fe6a commit acd7516
Showing 1 changed file with 7 additions and 0 deletions.
7 changes: 7 additions & 0 deletions src/rviz/visualizer_app.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -226,6 +226,13 @@ bool VisualizerApp::init(int argc, char** argv)
save_config_service_ =
private_nh.advertiseService("save_config", &VisualizerApp::saveConfigCallback, this);

//process any callbacks that don't use the designated callback queues of VisualizationManager
// but don't interfere with library users
QTimer* synchronous_global_timer = new QTimer(this);
synchronous_global_timer->setInterval(10);
synchronous_global_timer->setTimerType(Qt::VeryCoarseTimer);
connect(synchronous_global_timer, &QTimer::timeout, this, [](){ros::spinOnce();});

#if CATCH_EXCEPTIONS
}
catch (std::exception& e)
Expand Down

0 comments on commit acd7516

Please sign in to comment.