00001 #ifndef _UTILITIES_MESSAGE_SUBSCRIBER_H_ 00002 #define _UTILITIES_MESSAGE_SUBSCRIBER_H_ 00003 00004 #include <QMap> 00005 #include <QObject> 00006 #include <QString> 00007 #include <QMetaMethod> 00008 #include <ros/node_handle.h> 00009 #include "utilities/message.h" 00010 #include <variant_topic_tools/Subscriber.h> 00011 00012 namespace utilities 00013 { 00014 class MessageSubscriber : public QObject 00015 { 00016 Q_OBJECT 00017 public: 00018 enum Property 00019 { 00020 QueueSize 00021 }; 00022 MessageSubscriber(QObject* parent = 0, 00023 const ros::NodeHandle& nh = ros::NodeHandle("~")); 00024 ~MessageSubscriber(); 00025 const ros::NodeHandle& getNodeHandle() const; 00026 void setTopic(const QString& topic); 00027 const QString& getTopic() const; 00028 void setQueueSize(size_t queue_size); 00029 size_t getQueueSize() const; 00030 size_t getNumPublishers() const; 00031 bool isValid() const; 00032 bool event(QEvent* event); 00033 00034 signals: 00035 void subscribed(const QString& topic); 00036 void messageReceived(const QString& topic, const Message& message); 00037 void unsubscribed(const QString& topic); 00038 void aboutToBeDestroyed(); 00039 00040 private: 00041 ros::NodeHandle nh_; 00042 QString topic_; 00043 size_t queue_size_; 00044 variant_topic_tools::Subscriber subscriber_; 00045 void subscribe(); 00046 void unsubscribe(); 00047 void callback(const variant_topic_tools::MessageVariant& variant, 00048 const ros::Time& receipt_time); 00049 #if QT_VERSION >= QT_VERSION_CHECK(5, 0, 0) 00050 void connectNotify(const QMetaMethod& signal); 00051 void disconnectNotify(const QMetaMethod& signal); 00052 #else 00053 void connectNotify(const char* signal); 00054 void disconnectNotify(const char* signal); 00055 #endif 00056 }; 00057 } 00058 00059 #endif // _UTILITIES_MESSAGE_SUBSCRIBER_H_