19 #include <QApplication> 21 #include <variant_topic_tools/MessageType.h> 36 nodeHandle_(nodeHandle),
103 return QObject::event(event);
107 variant_topic_tools::MessageType type;
135 QApplication::postEvent(
this, messageEvent);
138 #if QT_VERSION >= QT_VERSION_CHECK(5,0,0) 146 if (!receivers(QMetaObject::normalizedSignature(
158 if ((QByteArray(signal) == QMetaObject::normalizedSignature(
165 if (!receivers(QMetaObject::normalizedSignature(
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("~"))
const QString & getTopic() const
size_t getNumPublishers() const
variant_topic_tools::Subscriber subscriber_
void connectNotify(const QMetaMethod &signal)
static const QEvent::Type Type
void disconnectNotify(const QMetaMethod &signal)
void setTopic(const QString &topic)
void setQueueSize(size_t queueSize)
void aboutToBeDestroyed()
bool event(QEvent *event)
void setReceiptTime(const ros::Time &receiptTime)
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)
void setVariant(const variant_topic_tools::MessageVariant &variant)
size_t getQueueSize() const