MessageSubscriber.cpp
Go to the documentation of this file.
1 /******************************************************************************
2  * Copyright (C) 2015 by Ralf Kaestner *
3  * ralf.kaestner@gmail.com *
4  * *
5  * This program is free software; you can redistribute it and/or modify *
6  * it under the terms of the Lesser GNU General Public License as published by*
7  * the Free Software Foundation; either version 3 of the License, or *
8  * (at your option) any later version. *
9  * *
10  * This program is distributed in the hope that it will be useful, *
11  * but WITHOUT ANY WARRANTY; without even the implied warranty of *
12  * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the *
13  * Lesser GNU General Public License for more details. *
14  * *
15  * You should have received a copy of the Lesser GNU General Public License *
16  * along with this program. If not, see <http://www.gnu.org/licenses/>. *
17  ******************************************************************************/
18 
19 #include <QApplication>
20 
21 #include <variant_topic_tools/MessageType.h>
22 
24 
26 
27 namespace rqt_multiplot {
28 
29 /*****************************************************************************/
30 /* Constructors and Destructor */
31 /*****************************************************************************/
32 
34  nodeHandle) :
35  QObject(parent),
36  nodeHandle_(nodeHandle),
37  queueSize_(100) {
38 }
39 
41 }
42 
43 /*****************************************************************************/
44 /* Accessors */
45 /*****************************************************************************/
46 
48  return nodeHandle_;
49 }
50 
51 const QString& MessageSubscriber::getTopic() const {
52  return topic_;
53 }
54 
55 void MessageSubscriber::setTopic(const QString& topic) {
56  if (topic != topic_) {
57  topic_ = topic;
58 
59  if (subscriber_) {
60  unsubscribe();
61  subscribe();
62  }
63  }
64 }
65 
66 void MessageSubscriber::setQueueSize(size_t queueSize) {
67  if (queueSize != queueSize_) {
68  queueSize_ = queueSize;
69 
70  if (subscriber_) {
71  unsubscribe();
72  subscribe();
73  }
74  }
75 }
76 
78  return queueSize_;
79 }
80 
82  return subscriber_.getNumPublishers();
83 }
84 
86  return subscriber_;
87 }
88 
89 /*****************************************************************************/
90 /* Methods */
91 /*****************************************************************************/
92 
94  if (event->type() == MessageEvent::Type) {
95  MessageEvent* messageEvent = static_cast<MessageEvent*>(event);
96 
97  emit messageReceived(messageEvent->getTopic(), messageEvent->
98  getMessage());
99 
100  return true;
101  }
102 
103  return QObject::event(event);
104 }
105 
107  variant_topic_tools::MessageType type;
108 
109  subscriber_ = type.subscribe(nodeHandle_, topic_.toStdString(), queueSize_,
110  boost::bind(&MessageSubscriber::callback, this, _1, _2));
111 
112  if (subscriber_)
113  emit subscribed(topic_);
114 }
115 
117  if (subscriber_) {
118  subscriber_.shutdown();
119 
120  QApplication::removePostedEvents(this, MessageEvent::Type);
121 
122  emit unsubscribed(topic_);
123  }
124 }
125 
126 void MessageSubscriber::callback(const variant_topic_tools::MessageVariant&
127  variant, const ros::Time& receiptTime) {
128  Message message;
129 
130  message.setReceiptTime(receiptTime);
131  message.setVariant(variant);
132 
133  MessageEvent* messageEvent = new MessageEvent(topic_, message);
134 
135  QApplication::postEvent(this, messageEvent);
136 }
137 
138 #if QT_VERSION >= QT_VERSION_CHECK(5,0,0)
139 void MessageSubscriber::connectNotify(const QMetaMethod& signal) {
140  if (signal == QMetaMethod::fromSignal(&MessageSubscriber::messageReceived) &&
141  !subscriber_)
142  subscribe();
143 }
144 
145 void MessageSubscriber::disconnectNotify(const QMetaMethod& signal) {
146  if (!receivers(QMetaObject::normalizedSignature(
147  SIGNAL(messageReceived(const QString&, const Message&))))) {
148  if (subscriber_)
149  unsubscribe();
150 
151  emit aboutToBeDestroyed();
152 
153  deleteLater();
154  }
155 }
156 #else
157 void MessageSubscriber::connectNotify(const char* signal) {
158  if ((QByteArray(signal) == QMetaObject::normalizedSignature(
159  SIGNAL(messageReceived(const QString&, const Message&)))) &&
160  !subscriber_)
161  subscribe();
162 }
163 
164 void MessageSubscriber::disconnectNotify(const char* signal) {
165  if (!receivers(QMetaObject::normalizedSignature(
166  SIGNAL(messageReceived(const QString&, const Message&))))) {
167  if (subscriber_)
168  unsubscribe();
169 
170  emit aboutToBeDestroyed();
171 
172  deleteLater();
173  }
174 }
175 #endif
176 
177 }
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
variant_topic_tools::Subscriber subscriber_
void connectNotify(const QMetaMethod &signal)
static const QEvent::Type Type
Definition: MessageEvent.h:31
void disconnectNotify(const QMetaMethod &signal)
void setTopic(const QString &topic)
void setQueueSize(size_t queueSize)
void setReceiptTime(const ros::Time &receiptTime)
Definition: Message.cpp:42
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)
Definition: Message.cpp:50


rqt_multiplot
Author(s): Ralf Kaestner
autogenerated on Wed Jul 10 2019 03:49:44