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

MessageFilterDisplay: process messages synchronously #1560

Merged
merged 1 commit into from
Nov 16, 2020
Merged
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
13 changes: 13 additions & 0 deletions src/rviz/message_filter_display.h
Original file line number Diff line number Diff line change
Expand Up @@ -42,6 +42,8 @@
#include <rviz/display.h>
#include <rviz/rviz_export.h>

Q_DECLARE_METATYPE(boost::shared_ptr<const void>)

namespace rviz
{
/** @brief Helper superclass for MessageFilterDisplay, needed because
Expand All @@ -63,11 +65,14 @@ class RVIZ_EXPORT _RosTopicDisplay : public Display
"w.r.t. your data, but it can greatly increase memory usage as well.",
this, SLOT(updateQueueSize()));
queue_size_property_->setMin(0);
qRegisterMetaType<boost::shared_ptr<const void>>(); // required to send via queued connection
}

protected Q_SLOTS:
virtual void updateTopic() = 0;
virtual void updateQueueSize() = 0;
private Q_SLOTS:
virtual void processTypeErasedMessage(boost::shared_ptr<const void> type_erased_msg) = 0;

protected:
RosTopicProperty* topic_property_;
Expand Down Expand Up @@ -203,7 +208,15 @@ class MessageFilterDisplay : public _RosTopicDisplay
{
return;
}
// process message synchronously in main GUI thread to avoid race conditions
QMetaObject::invokeMethod(this, "processTypeErasedMessage", Qt::QueuedConnection,
Q_ARG(boost::shared_ptr<const void>,
boost::static_pointer_cast<const void>(msg)));
}

void processTypeErasedMessage(boost::shared_ptr<const void> type_erased_msg) override
{
auto msg = boost::static_pointer_cast<const MessageType>(type_erased_msg);
++messages_received_;
setStatus(StatusProperty::Ok, "Topic", QString::number(messages_received_) + " messages received");

Expand Down