Gazebo Transport

API Reference

12.2.2
gz/transport/Node.hh
Go to the documentation of this file.
1 /*
2  * Copyright (C) 2014 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 #ifndef GZ_TRANSPORT_NODE_HH_
18 #define GZ_TRANSPORT_NODE_HH_
19 
20 #include <algorithm>
21 #include <functional>
22 #include <memory>
23 #include <mutex>
24 #include <optional>
25 #include <string>
26 #include <unordered_set>
27 #include <vector>
28 
30 #include "gz/transport/config.hh"
31 #include "gz/transport/Export.hh"
42 
43 namespace gz
44 {
45  namespace transport
46  {
47  // Inline bracket to help doxygen filtering.
48  inline namespace GZ_TRANSPORT_VERSION_NAMESPACE {
49  //
50  // Forward declarations.
51  class NodePrivate;
52 
63  int GZ_TRANSPORT_VISIBLE rcvHwm();
64 
75  int GZ_TRANSPORT_VISIBLE sndHwm();
76 
80  void GZ_TRANSPORT_VISIBLE waitForShutdown();
81 
86  class GZ_TRANSPORT_VISIBLE Node
87  {
88  class PublisherPrivate;
89 
106  public: class GZ_TRANSPORT_VISIBLE Publisher
107  {
109  public: Publisher();
110 
113  public: explicit Publisher(const MessagePublisher &_publisher);
114 
116  public: virtual ~Publisher();
117 
121  public: operator bool();
122 
126  public: operator bool() const;
127 
131  public: bool Valid() const;
132 
138  public: bool Publish(const ProtoMsg &_msg);
139 
161  public: bool PublishRaw(
162  const std::string &_msgData,
163  const std::string &_msgType);
164 
173  public: bool ThrottledUpdateReady() const;
174 
178  private: bool UpdateThrottling();
179 
182  public: bool HasConnections() const;
183 
189 #ifdef _WIN32
190 // Disable warning C4251 which is triggered by
191 // std::shared_ptr
192 #pragma warning(push)
193 #pragma warning(disable: 4251)
194 #endif
195  private: std::shared_ptr<PublisherPrivate> dataPtr;
196 #ifdef _WIN32
197 #pragma warning(pop)
198 #endif
199  };
200 
203  public: explicit Node(const NodeOptions &_options = NodeOptions());
204 
206  public: virtual ~Node();
207 
216  public: template<typename MessageT>
217  Node::Publisher Advertise(
218  const std::string &_topic,
220 
232  public: Node::Publisher Advertise(
233  const std::string &_topic,
234  const std::string &_msgTypeName,
236 
239  public: std::vector<std::string> AdvertisedTopics() const;
240 
250  public: template<typename MessageT>
251  bool Subscribe(
252  const std::string &_topic,
253  void(*_callback)(const MessageT &_msg),
254  const SubscribeOptions &_opts = SubscribeOptions());
255 
264  public: template<typename MessageT>
265  bool Subscribe(
266  const std::string &_topic,
267  std::function<void(const MessageT &_msg)> _callback,
268  const SubscribeOptions &_opts = SubscribeOptions());
269 
280  public: template<typename ClassT, typename MessageT>
281  bool Subscribe(
282  const std::string &_topic,
283  void(ClassT::*_callback)(const MessageT &_msg),
284  ClassT *_obj,
285  const SubscribeOptions &_opts = SubscribeOptions());
286 
297  public: template<typename MessageT>
298  bool Subscribe(
299  const std::string &_topic,
300  void(*_callback)(const MessageT &_msg, const MessageInfo &_info),
301  const SubscribeOptions &_opts = SubscribeOptions());
302 
312  public: template<typename MessageT>
313  bool Subscribe(
314  const std::string &_topic,
315  std::function<void(const MessageT &_msg,
316  const MessageInfo &_info)> _callback,
317  const SubscribeOptions &_opts = SubscribeOptions());
318 
330  public: template<typename ClassT, typename MessageT>
331  bool Subscribe(
332  const std::string &_topic,
333  void(ClassT::*_callback)(const MessageT &_msg,
334  const MessageInfo &_info),
335  ClassT *_obj,
336  const SubscribeOptions &_opts = SubscribeOptions());
337 
343  public: std::vector<std::string> SubscribedTopics() const;
344 
348  public: bool Unsubscribe(const std::string &_topic);
349 
362  public: template<typename RequestT, typename ReplyT>
363  bool Advertise(
364  const std::string &_topic,
365  bool(*_callback)(const RequestT &_request, ReplyT &_reply),
367 
379  public: template<typename ReplyT>
380  bool Advertise(
381  const std::string &_topic,
382  bool(*_callback)(ReplyT &_reply),
384 
395  public: template<typename RequestT>
396  bool Advertise(
397  const std::string &_topic,
398  void(*_callback)(const RequestT &_request),
400 
413  public: template<typename RequestT, typename ReplyT>
414  bool Advertise(
415  const std::string &_topic,
416  std::function<bool(const RequestT &_request,
417  ReplyT &_reply)> _callback,
419 
431  public: template<typename ReplyT>
432  bool Advertise(
433  const std::string &_topic,
434  std::function<bool(ReplyT &_reply)> &_callback,
436 
447  public: template<typename RequestT>
448  bool Advertise(
449  const std::string &_topic,
450  std::function<void(const RequestT &_request)> &_callback,
452 
466  public: template<typename ClassT, typename RequestT, typename ReplyT>
467  bool Advertise(
468  const std::string &_topic,
469  bool(ClassT::*_callback)(const RequestT &_request, ReplyT &_reply),
470  ClassT *_obj,
472 
485  public: template<typename ClassT, typename ReplyT>
486  bool Advertise(
487  const std::string &_topic,
488  bool(ClassT::*_callback)(ReplyT &_reply),
489  ClassT *_obj,
491 
503  public: template<typename ClassT, typename RequestT>
504  bool Advertise(
505  const std::string &_topic,
506  void(ClassT::*_callback)(const RequestT &_request),
507  ClassT *_obj,
509 
512  public: std::vector<std::string> AdvertisedServices() const;
513 
525  public: template<typename RequestT, typename ReplyT>
526  bool Request(
527  const std::string &_topic,
528  const RequestT &_request,
529  void(*_callback)(const ReplyT &_reply, const bool _result));
530 
541  public: template<typename ReplyT>
542  bool Request(
543  const std::string &_topic,
544  void(*_callback)(const ReplyT &_reply, const bool _result));
545 
557  public: template<typename RequestT, typename ReplyT>
558  bool Request(
559  const std::string &_topic,
560  const RequestT &_request,
561  std::function<void(const ReplyT &_reply,
562  const bool _result)> &_callback);
563 
574  public: template<typename ReplyT>
575  bool Request(
576  const std::string &_topic,
577  std::function<void(const ReplyT &_reply,
578  const bool _result)> &_callback);
579 
592  public: template<typename ClassT, typename RequestT, typename ReplyT>
593  bool Request(
594  const std::string &_topic,
595  const RequestT &_request,
596  void(ClassT::*_callback)(const ReplyT &_reply, const bool _result),
597  ClassT *_obj);
598 
610  public: template<typename ClassT, typename ReplyT>
611  bool Request(
612  const std::string &_topic,
613  void(ClassT::*_callback)(const ReplyT &_reply, const bool _result),
614  ClassT *_obj);
615 
625  public: template<typename RequestT, typename ReplyT>
626  bool Request(
627  const std::string &_topic,
628  const RequestT &_request,
629  const unsigned int &_timeout,
630  ReplyT &_reply,
631  bool &_result);
632 
641  public: template<typename ReplyT>
642  bool Request(
643  const std::string &_topic,
644  const unsigned int &_timeout,
645  ReplyT &_reply,
646  bool &_result);
647 
653  public: template<typename RequestT>
654  bool Request(const std::string &_topic, const RequestT &_request);
655 
670  public: bool RequestRaw(const std::string &_topic,
671  const std::string &_request, const std::string &_requestType,
672  const std::string &_responseType, unsigned int _timeout,
673  std::string &_response,
674  bool &_result);
675 
679  public: bool UnadvertiseSrv(const std::string &_topic);
680 
687  public: void TopicList(std::vector<std::string> &_topics) const;
688 
693  public: bool TopicInfo(const std::string &_topic,
694  std::vector<MessagePublisher> &_publishers) const;
695 
702  public: void ServiceList(std::vector<std::string> &_services) const;
703 
708  public: bool ServiceInfo(
709  const std::string &_service,
710  std::vector<ServicePublisher> &_publishers) const;
711 
725  public: bool SubscribeRaw(
726  const std::string &_topic,
727  const RawCallback &_callback,
728  const std::string &_msgType = kGenericMessageType,
729  const SubscribeOptions &_opts = SubscribeOptions());
730 
733  public: const NodeOptions &Options() const;
734 
741  public: bool EnableStats(const std::string &_topic, bool _enable,
742  const std::string &_publicationTopic = "/statistics",
743  uint64_t _publicationRate = 1);
744 
751  public: std::optional<TopicStatistics> TopicStats(
752  const std::string &_topic) const;
753 
757  private: NodeShared *Shared() const;
758 
761  private: const std::string &NodeUuid() const;
762 
765  private: std::unordered_set<std::string> &TopicsSubscribed() const;
766 
769  private: std::unordered_set<std::string> &SrvsAdvertised() const;
770 
774  private: bool SubscribeHelper(const std::string &_fullyQualifiedTopic);
775 
776 #ifdef _WIN32
777 // Disable warning C4251 which is triggered by
778 // std::unique_ptr
779 #pragma warning(push)
780 #pragma warning(disable: 4251)
781 #endif
785 #ifdef _WIN32
786 #pragma warning(pop)
787 #endif
788  };
789  }
790  }
791 }
792 
793 #include "gz/transport/detail/Node.hh"
794 
795 #endif