Skip to content

Commit

Permalink
Revert "[foxy backport] Ensure rviz_common::MessageFilterDisplay proc…
Browse files Browse the repository at this point in the history
…esses messages in the main thread (#620) (#765)"

This reverts commit 154feac.
  • Loading branch information
gbalke authored Oct 8, 2021
1 parent 7cefa4b commit 57c3519
Show file tree
Hide file tree
Showing 2 changed files with 6 additions and 37 deletions.
17 changes: 6 additions & 11 deletions rviz_common/include/rviz_common/message_filter_display.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -174,23 +174,18 @@ class MessageFilterDisplay : public _RosTopicDisplay
reset();
}

/// Incoming message callback.
/**
* Checks if the message pointer
* is valid, increments messages_received_, then calls
* processMessage().
*/
void incomingMessage(const typename MessageType::ConstSharedPtr msg)
{
if (!msg) {
return;
}

// Do not process message right away, tf2_ros::MessageFilter may be
// calling back from tf2_ros::TransformListener dedicated thread.
// Use type erased signal/slot machinery to ensure messages are
// processed in the main thread.
Q_EMIT typeErasedMessageTaken(std::static_pointer_cast<const void>(msg));
}

void processTypeErasedMessage(std::shared_ptr<const void> type_erased_msg)
{
auto msg = std::static_pointer_cast<const MessageType>(type_erased_msg);

++messages_received_;
setStatus(
properties::StatusProperty::Ok,
Expand Down
26 changes: 0 additions & 26 deletions rviz_common/include/rviz_common/ros_topic_display.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -51,12 +51,6 @@
#include "rviz_common/ros_integration/ros_node_abstraction_iface.hpp"
#include "rviz_common/visibility_control.hpp"

// Required, in combination with
// `qRegisterMetaType<std::shared_ptr<const void>>` so that this
// type can be queued by Qt slots.
// See: http://doc.qt.io/qt-5/qmetatype.html#qRegisterMetaType-1
Q_DECLARE_METATYPE(std::shared_ptr<const void>)

namespace rviz_common
{

Expand All @@ -72,8 +66,6 @@ class RVIZ_COMMON_PUBLIC _RosTopicDisplay : public Display
: rviz_ros_node_(),
qos_profile(5)
{
qRegisterMetaType<std::shared_ptr<const void>>();

topic_property_ = new properties::RosTopicProperty(
"Topic", "",
"", "", this, SLOT(updateTopic()));
Expand All @@ -100,27 +92,9 @@ class RVIZ_COMMON_PUBLIC _RosTopicDisplay : public Display
this->qos_profile = profile;
updateTopic();
});

// Useful to _ROSTopicDisplay subclasses to ensure GUI updates
// are performed by the main thread only.
connect(
this,
SIGNAL(typeErasedMessageTaken(std::shared_ptr<const void>)),
this,
SLOT(processTypeErasedMessage(std::shared_ptr<const void>)),
// Force queued connections regardless of QObject thread affinity
Qt::QueuedConnection);
}

Q_SIGNALS:
void typeErasedMessageTaken(std::shared_ptr<const void> type_erased_message);

protected Q_SLOTS:
void processTypeErasedMessage(std::shared_ptr<const void> type_erased_message)
{
(void)type_erased_message;
}

virtual void transformerChangedCallback()
{
}
Expand Down

0 comments on commit 57c3519

Please sign in to comment.