Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Synchronous updates #1475

Open
wants to merge 2 commits into
base: noetic-devel
Choose a base branch
from
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
5 changes: 3 additions & 2 deletions src/rviz/visualization_manager.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -111,6 +111,7 @@ class VisualizationManagerPrivate
{
public:
ros::CallbackQueue threaded_queue_;
ros::CallbackQueue update_queue_;
boost::thread_group threaded_queue_threads_;
ros::NodeHandle update_nh_;
ros::NodeHandle threaded_nh_;
Expand Down Expand Up @@ -269,7 +270,7 @@ void VisualizationManager::unlockRender()

ros::CallbackQueueInterface* VisualizationManager::getUpdateQueue()
{
return ros::getGlobalCallbackQueue();
return &private_->update_queue_;
}

void VisualizationManager::startUpdate()
Expand Down Expand Up @@ -330,7 +331,7 @@ void VisualizationManager::onUpdate()
resetTime();
}

ros::spinOnce();
private_->update_queue_.callAvailable(ros::WallDuration(0.01));
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Suggested change
private_->update_queue_.callAvailable(ros::WallDuration(0.01));
private_->update_queue_.callAvailable(ros::WallDuration());
ros::getGlobalCallbackQueue()->callAvailable(ros::WallDuration());


Q_EMIT preUpdate();

Expand Down
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
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Why do you want to handle the global queue differently?

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

VisualizerApp is used by the rviz binary but not by library users. Handling the global queue here will make sure that plugins that rely on it won't see any difference. For library users it allows not handling the global queue in the main thread.

// 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