19 #ifndef RQT_MULTIPLOT_MESSAGE_SUBSCRIBER_H 20 #define RQT_MULTIPLOT_MESSAGE_SUBSCRIBER_H 25 #include <QMetaMethod> 29 #include <variant_topic_tools/Subscriber.h> 73 void callback(
const variant_topic_tools::MessageVariant& variant,
76 #if QT_VERSION >= QT_VERSION_CHECK(5,0,0) void callback(const variant_topic_tools::MessageVariant &variant, const ros::Time &receiptTime)
void subscribed(const QString &topic)
MessageSubscriber(QObject *parent=0, const ros::NodeHandle &nodeHandle=ros::NodeHandle("~"))
size_t getNumPublishers() const
variant_topic_tools::Subscriber subscriber_
void connectNotify(const QMetaMethod &signal)
void disconnectNotify(const QMetaMethod &signal)
void setTopic(const QString &topic)
void setQueueSize(size_t queueSize)
void aboutToBeDestroyed()
bool event(QEvent *event)
ros::NodeHandle nodeHandle_
const QString & getTopic() const
const ros::NodeHandle & getNodeHandle() const
void messageReceived(const QString &topic, const Message &message)
void unsubscribed(const QString &topic)
size_t getQueueSize() const