message_subscriber_registry.cpp
Go to the documentation of this file.
00001 #include <QMetaType>
00002 #include "utilities/message_subscriber_registry.h"
00003 
00004 namespace utilities
00005 {
00006 MessageSubscriberRegistry::MessageSubscriberRegistry(QObject* parent,
00007                                                      const ros::NodeHandle& nh)
00008     : MessageBroker(parent), nh_(nh)
00009 {
00010 }
00011 
00012 MessageSubscriberRegistry::~MessageSubscriberRegistry() {}
00013 
00014 const ros::NodeHandle& MessageSubscriberRegistry::getNodeHandle() const
00015 {
00016   return nh_;
00017 }
00018 
00019 bool MessageSubscriberRegistry::subscribe(const QString& topic,
00020                                           QObject* receiver, const char* method,
00021                                           const PropertyMap& properties,
00022                                           Qt::ConnectionType type)
00023 {
00024   iterator it(subscribers_.find(topic));
00025   size_t queue_size(100);
00026   if (properties.contains(MessageSubscriber::QueueSize))
00027   {
00028     queue_size = properties[MessageSubscriber::QueueSize].toULongLong();
00029   }
00030   MessageSubscriber* subscriber = it != subscribers_.end() ? *it : NULL;
00031   if (!subscriber)
00032   {
00033     subscriber = new MessageSubscriber(this, getNodeHandle());
00034     subscribers_.insert(topic, subscriber);
00035     subscriber->setQueueSize(queue_size);
00036     subscriber->setTopic(topic);
00037     connect(subscriber, SIGNAL(aboutToBeDestroyed()), this,
00038             SLOT(subscriberAboutToBeDestroyed()));
00039   }
00040   else if (subscriber->getQueueSize() < queue_size)
00041   {
00042     subscriber->setQueueSize(queue_size);
00043   }
00044   return receiver->connect(
00045       subscriber, SIGNAL(messageReceived(const QString&, const Message&)),
00046       method, type);
00047 }
00048 
00049 bool MessageSubscriberRegistry::unsubscribe(const QString& topic,
00050                                             QObject* receiver,
00051                                             const char* method)
00052 {
00053   iterator it = subscribers_.find(topic);
00054   MessageSubscriber* subscriber = it != subscribers_.end() ? *it : NULL;
00055   return subscriber &&
00056          subscriber->disconnect(
00057              SIGNAL(messageReceived(const QString&, const Message&)), receiver,
00058              method);
00059 }
00060 
00061 void MessageSubscriberRegistry::subscriberAboutToBeDestroyed()
00062 {
00063   for (iterator it = subscribers_.begin(); it != subscribers_.end(); it++)
00064   {
00065     if (*it == static_cast<MessageSubscriber*>(sender()))
00066     {
00067       subscribers_.erase(it);
00068       break;
00069     }
00070   }
00071 }
00072 }


rqt_mrta
Author(s): Adriano Henrique Rossette Leite
autogenerated on Thu Jun 6 2019 18:50:52