diff --git a/rviz_common/include/rviz_common/message_filter_display.hpp b/rviz_common/include/rviz_common/message_filter_display.hpp index 64d619705..bbb79efad 100644 --- a/rviz_common/include/rviz_common/message_filter_display.hpp +++ b/rviz_common/include/rviz_common/message_filter_display.hpp @@ -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(msg)); - } - - void processTypeErasedMessage(std::shared_ptr type_erased_msg) - { - auto msg = std::static_pointer_cast(type_erased_msg); - ++messages_received_; setStatus( properties::StatusProperty::Ok, diff --git a/rviz_common/include/rviz_common/ros_topic_display.hpp b/rviz_common/include/rviz_common/ros_topic_display.hpp index fdbce90b6..01fe05e44 100644 --- a/rviz_common/include/rviz_common/ros_topic_display.hpp +++ b/rviz_common/include/rviz_common/ros_topic_display.hpp @@ -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>` 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) - namespace rviz_common { @@ -72,8 +66,6 @@ class RVIZ_COMMON_PUBLIC _RosTopicDisplay : public Display : rviz_ros_node_(), qos_profile(5) { - qRegisterMetaType>(); - topic_property_ = new properties::RosTopicProperty( "Topic", "", "", "", this, SLOT(updateTopic())); @@ -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)), - this, - SLOT(processTypeErasedMessage(std::shared_ptr)), - // Force queued connections regardless of QObject thread affinity - Qt::QueuedConnection); } -Q_SIGNALS: - void typeErasedMessageTaken(std::shared_ptr type_erased_message); - protected Q_SLOTS: - void processTypeErasedMessage(std::shared_ptr type_erased_message) - { - (void)type_erased_message; - } - virtual void transformerChangedCallback() { }