Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019 #include <QMetaType>
00020
00021 #include "rqt_multiplot/MessageSubscriberRegistry.h"
00022
00023 namespace rqt_multiplot {
00024
00025
00026
00027
00028
00029 MessageSubscriberRegistry::MessageSubscriberRegistry(QObject* parent, const
00030 ros::NodeHandle& nodeHandle) :
00031 MessageBroker(parent),
00032 nodeHandle_(nodeHandle) {
00033 }
00034
00035 MessageSubscriberRegistry::~MessageSubscriberRegistry() {
00036 }
00037
00038
00039
00040
00041
00042 const ros::NodeHandle& MessageSubscriberRegistry::getNodeHandle() const {
00043 return nodeHandle_;
00044 }
00045
00046
00047
00048
00049
00050 bool MessageSubscriberRegistry::subscribe(const QString& topic,
00051 QObject* receiver, const char* method, const PropertyMap& properties,
00052 Qt::ConnectionType type) {
00053 QMap<QString, MessageSubscriber*>::iterator it = subscribers_.find(topic);
00054
00055 size_t queueSize = 100;
00056 if (properties.contains(MessageSubscriber::QueueSize))
00057 queueSize = properties[MessageSubscriber::QueueSize].toULongLong();
00058
00059 if (it == subscribers_.end()) {
00060 it = subscribers_.insert(topic, new MessageSubscriber(this,
00061 getNodeHandle()));
00062
00063 it.value()->setQueueSize(queueSize);
00064 it.value()->setTopic(topic);
00065
00066 connect(it.value(), SIGNAL(aboutToBeDestroyed()), this,
00067 SLOT(subscriberAboutToBeDestroyed()));
00068 }
00069 else if (it.value()->getQueueSize() < queueSize)
00070 it.value()->setQueueSize(queueSize);
00071
00072 return receiver->connect(it.value(), SIGNAL(messageReceived(const
00073 QString&, const Message&)), method, type);
00074 }
00075
00076 bool MessageSubscriberRegistry::unsubscribe(const QString& topic, QObject*
00077 receiver, const char* method) {
00078 QMap<QString, MessageSubscriber*>::iterator it = subscribers_.find(topic);
00079
00080 if (it != subscribers_.end()) {
00081 return it.value()->disconnect(SIGNAL(messageReceived(const QString&,
00082 const Message&)), receiver, method);
00083 }
00084 else
00085 return false;
00086 }
00087
00088
00089
00090
00091
00092 void MessageSubscriberRegistry::subscriberAboutToBeDestroyed() {
00093 for (QMap<QString, MessageSubscriber*>::iterator it = subscribers_.begin();
00094 it != subscribers_.end(); ++it) {
00095 if (it.value() == static_cast<MessageSubscriber*>(sender())) {
00096 subscribers_.erase(it);
00097 break;
00098 }
00099 }
00100 }
00101
00102 }