Node.hh
Go to the documentation of this file.
1 /*
2  * Copyright (C) 2012 Open Source Robotics Foundation
3  *
4  * Licensed under the Apache License, Version 2.0 (the "License");
5  * you may not use this file except in compliance with the License.
6  * You may obtain a copy of the License at
7  *
8  * http://www.apache.org/licenses/LICENSE-2.0
9  *
10  * Unless required by applicable law or agreed to in writing, software
11  * distributed under the License is distributed on an "AS IS" BASIS,
12  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13  * See the License for the specific language governing permissions and
14  * limitations under the License.
15  *
16 */
17 
18 #ifndef GAZEBO_TRANSPORT_NODE_HH_
19 #define GAZEBO_TRANSPORT_NODE_HH_
20 
21 #ifndef Q_MOC_RUN
22 #include <tbb/task.h>
23 #endif
24 #include <boost/bind.hpp>
25 #include <boost/enable_shared_from_this.hpp>
26 #include <map>
27 #include <list>
28 #include <string>
29 #include <vector>
30 
33 #include "gazebo/util/system.hh"
34 
35 namespace gazebo
36 {
37  namespace transport
38  {
41  class GZ_TRANSPORT_VISIBLE PublishTask : public tbb::task
42  {
46  public: PublishTask(transport::PublisherPtr _pub,
47  const google::protobuf::Message &_message)
48  : pub(_pub)
49  {
50  this->msg = _message.New();
51  this->msg->CopyFrom(_message);
52  }
53 
56  public: tbb::task *execute()
57  {
58  this->pub->WaitForConnection();
59  this->pub->Publish(*this->msg, true);
60  this->pub->SendMessage();
61  delete this->msg;
62  this->pub.reset();
63  return NULL;
64  }
65 
67  private: transport::PublisherPtr pub;
68 
70  private: google::protobuf::Message *msg;
71  };
73 
76 
80  class GZ_TRANSPORT_VISIBLE Node :
81  public boost::enable_shared_from_this<Node>
82  {
84  public: Node();
85 
87  public: virtual ~Node();
88 
97  public: void Init(const std::string &_space ="");
98 
110  public: bool TryInit(
111  const common::Time &_maxWait = common::Time(1, 0));
112 
117  public: bool IsInitialized() const;
118 
120  public: void Fini();
121 
124  public: std::string GetTopicNamespace() const;
125 
129  public: std::string DecodeTopicName(const std::string &_topic);
130 
134  public: std::string EncodeTopicName(const std::string &_topic);
135 
138  public: unsigned int GetId() const;
139 
142  public: void ProcessPublishers();
143 
145  public: void ProcessIncoming();
146 
150  public: bool HasLatchedSubscriber(const std::string &_topic) const;
151 
152 
159  public: template<typename M>
160  void Publish(const std::string &_topic,
161  const google::protobuf::Message &_message)
162  {
163  transport::PublisherPtr pub = this->Advertise<M>(_topic);
164  PublishTask *task = new(tbb::task::allocate_root())
165  PublishTask(pub, _message);
166 
167  tbb::task::enqueue(*task);
168  return;
169  }
170 
178  public: template<typename M>
179  transport::PublisherPtr Advertise(const std::string &_topic,
180  unsigned int _queueLimit = 1000,
181  double _hzRate = 0)
182  {
183  std::string decodedTopic = this->DecodeTopicName(_topic);
184  PublisherPtr publisher =
185  transport::TopicManager::Instance()->Advertise<M>(
186  decodedTopic, _queueLimit, _hzRate);
187 
188  boost::mutex::scoped_lock lock(this->publisherMutex);
189  publisher->SetNode(shared_from_this());
190  this->publishers.push_back(publisher);
191 
192  return publisher;
193  }
194 
202  public: template<typename M, typename T>
203  SubscriberPtr Subscribe(const std::string &_topic,
204  void(T::*_fp)(const boost::shared_ptr<M const> &), T *_obj,
205  bool _latching = false)
206  {
207  SubscribeOptions ops;
208  std::string decodedTopic = this->DecodeTopicName(_topic);
209  ops.template Init<M>(decodedTopic, shared_from_this(), _latching);
210 
211  {
212  boost::recursive_mutex::scoped_lock lock(this->incomingMutex);
213  this->callbacks[decodedTopic].push_back(CallbackHelperPtr(
214  new CallbackHelperT<M>(boost::bind(_fp, _obj, _1), _latching)));
215  }
216 
217  SubscriberPtr result =
218  transport::TopicManager::Instance()->Subscribe(ops);
219 
220  result->SetCallbackId(this->callbacks[decodedTopic].back()->GetId());
221 
222  return result;
223  }
224 
231  public: template<typename M>
232  SubscriberPtr Subscribe(const std::string &_topic,
233  void(*_fp)(const boost::shared_ptr<M const> &),
234  bool _latching = false)
235  {
236  SubscribeOptions ops;
237  std::string decodedTopic = this->DecodeTopicName(_topic);
238  ops.template Init<M>(decodedTopic, shared_from_this(), _latching);
239 
240  {
241  boost::recursive_mutex::scoped_lock lock(this->incomingMutex);
242  this->callbacks[decodedTopic].push_back(
243  CallbackHelperPtr(new CallbackHelperT<M>(_fp, _latching)));
244  }
245 
246  SubscriberPtr result =
247  transport::TopicManager::Instance()->Subscribe(ops);
248 
249  result->SetCallbackId(this->callbacks[decodedTopic].back()->GetId());
250 
251  return result;
252  }
253 
261  template<typename T>
262  SubscriberPtr Subscribe(const std::string &_topic,
263  void(T::*_fp)(const std::string &), T *_obj,
264  bool _latching = false)
265  {
266  SubscribeOptions ops;
267  std::string decodedTopic = this->DecodeTopicName(_topic);
268  ops.Init(decodedTopic, shared_from_this(), _latching);
269 
270  {
271  boost::recursive_mutex::scoped_lock lock(this->incomingMutex);
272  this->callbacks[decodedTopic].push_back(CallbackHelperPtr(
273  new RawCallbackHelper(boost::bind(_fp, _obj, _1))));
274  }
275 
276  SubscriberPtr result =
277  transport::TopicManager::Instance()->Subscribe(ops);
278 
279  result->SetCallbackId(this->callbacks[decodedTopic].back()->GetId());
280 
281  return result;
282  }
283 
284 
291  SubscriberPtr Subscribe(const std::string &_topic,
292  void(*_fp)(const std::string &), bool _latching = false)
293  {
294  SubscribeOptions ops;
295  std::string decodedTopic = this->DecodeTopicName(_topic);
296  ops.Init(decodedTopic, shared_from_this(), _latching);
297 
298  {
299  boost::recursive_mutex::scoped_lock lock(this->incomingMutex);
300  this->callbacks[decodedTopic].push_back(
302  }
303 
304  SubscriberPtr result =
305  transport::TopicManager::Instance()->Subscribe(ops);
306 
307  result->SetCallbackId(this->callbacks[decodedTopic].back()->GetId());
308 
309  return result;
310  }
311 
316  public: bool HandleData(const std::string &_topic,
317  const std::string &_msg);
318 
323  public: bool HandleMessage(const std::string &_topic, MessagePtr _msg);
324 
331  public: void InsertLatchedMsg(const std::string &_topic,
332  const std::string &_msg);
333 
340  public: void InsertLatchedMsg(const std::string &_topic,
341  MessagePtr _msg);
342 
346  public: std::string GetMsgType(const std::string &_topic) const;
347 
353  public: void RemoveCallback(const std::string &_topic, unsigned int _id);
354 
366  private: bool PrivateInit(const std::string &_space,
367  const common::Time &_maxWait,
368  const bool _fallbackToDefault);
369 
370  private: std::string topicNamespace;
371  private: std::vector<PublisherPtr> publishers;
372  private: std::vector<PublisherPtr>::iterator publishersIter;
373  private: static unsigned int idCounter;
374  private: unsigned int id;
375 
376  private: typedef std::list<CallbackHelperPtr> Callback_L;
377  private: typedef std::map<std::string, Callback_L> Callback_M;
378  private: Callback_M callbacks;
379  private: std::map<std::string, std::list<std::string> > incomingMsgs;
380 
382  private: std::map<std::string, std::list<MessagePtr> > incomingMsgsLocal;
383 
384  private: boost::mutex publisherMutex;
385  private: boost::mutex publisherDeleteMutex;
386  private: boost::recursive_mutex incomingMutex;
387 
390  private: boost::recursive_mutex processIncomingMutex;
391 
392  private: bool initialized;
393  };
395  }
396 }
397 #endif
Options for a subscription.
Definition: SubscribeOptions.hh:35
transport::PublisherPtr Advertise(const std::string &_topic, unsigned int _queueLimit=1000, double _hzRate=0)
Adverise a topic.
Definition: Node.hh:179
Forward declarations for the common classes.
Definition: Animation.hh:26
SubscriberPtr Subscribe(const std::string &_topic, void(T::*_fp)(const std::string &), T *_obj, bool _latching=false)
Subscribe to a topic using a class method as the callback.
Definition: Node.hh:262
boost::shared_ptr< google::protobuf::Message > MessagePtr
Definition: TransportTypes.hh:45
Forward declarations for transport.
boost::shared_ptr< Publisher > PublisherPtr
Definition: TransportTypes.hh:49
boost::shared_ptr< Subscriber > SubscriberPtr
Definition: TransportTypes.hh:53
boost::shared_ptr< CallbackHelper > CallbackHelperPtr
boost shared pointer to transport::CallbackHelper
Definition: CallbackHelper.hh:105
SubscriberPtr Subscribe(const std::string &_topic, void(T::*_fp)(const boost::shared_ptr< M const > &), T *_obj, bool _latching=false)
Subscribe to a topic using a class method as the callback.
Definition: Node.hh:203
Callback helper Template.
Definition: CallbackHelper.hh:111
SubscriberPtr Subscribe(const std::string &_topic, void(*_fp)(const boost::shared_ptr< M const > &), bool _latching=false)
Subscribe to a topic using a bare function as the callback.
Definition: Node.hh:232
A node can advertise and subscribe topics, publish on advertised topics and listen to subscribed topi...
Definition: Node.hh:80
#define NULL
Definition: CommonTypes.hh:31
SubscriberPtr Subscribe(const std::string &_topic, void(*_fp)(const std::string &), bool _latching=false)
Subscribe to a topic using a bare function as the callback.
Definition: Node.hh:291
GAZEBO_VISIBLE void Init(google::protobuf::Message &_message, const std::string &_id="")
Initialize a message.
void Publish(const std::string &_topic, const google::protobuf::Message &_message)
A convenience function for a one-time publication of a message.
Definition: Node.hh:160
Used to connect publishers to subscribers, where the subscriber wants the raw data from the publisher...
Definition: CallbackHelper.hh:177
void Init(const std::string &_topic, NodePtr _node, bool _latching)
Initialize the options.
Definition: SubscribeOptions.hh:48
A Time class, can be used to hold wall- or sim-time.
Definition: Time.hh:44
static TopicManager * Instance()
Get an instance of the singleton.
Definition: SingletonT.hh:36