32 nodeHandle_(nodeHandle) {
51 QObject* receiver,
const char* method,
const PropertyMap& properties,
52 Qt::ConnectionType type) {
53 QMap<QString, MessageSubscriber*>::iterator it =
subscribers_.find(topic);
55 size_t queueSize = 100;
63 it.value()->setQueueSize(queueSize);
64 it.value()->setTopic(topic);
66 connect(it.value(), SIGNAL(aboutToBeDestroyed()),
this,
69 else if (it.value()->getQueueSize() < queueSize)
70 it.value()->setQueueSize(queueSize);
72 return receiver->connect(it.value(), SIGNAL(messageReceived(
const 73 QString&,
const Message&)), method, type);
77 receiver,
const char* method) {
78 QMap<QString, MessageSubscriber*>::iterator it =
subscribers_.find(topic);
81 return it.value()->disconnect(SIGNAL(messageReceived(
const QString&,
82 const Message&)), receiver, method);
93 for (QMap<QString, MessageSubscriber*>::iterator it =
subscribers_.begin();
bool subscribe(const QString &topic, QObject *receiver, const char *method, const PropertyMap &properties=PropertyMap(), Qt::ConnectionType type=Qt::AutoConnection)
void subscriberAboutToBeDestroyed()
ros::NodeHandle nodeHandle_
virtual ~MessageSubscriberRegistry()
QMap< int, QVariant > PropertyMap
QMap< QString, MessageSubscriber * > subscribers_
MessageSubscriberRegistry(QObject *parent=0, const ros::NodeHandle &nodeHandle=ros::NodeHandle("~"))
const ros::NodeHandle & getNodeHandle() const
bool unsubscribe(const QString &topic, QObject *receiver, const char *method=0)