Gazebo Transport

API Reference

14.0.0~pre1
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
43namespace 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
201 public: Node();
202
205 public: explicit Node(const NodeOptions &_options);
206
208 public: virtual ~Node();
209
218 public: template<typename MessageT>
220 const std::string &_topic,
222
235 const std::string &_topic,
236 const std::string &_msgTypeName,
238
242
252 public: template<typename MessageT>
254 const std::string &_topic,
255 void(*_callback)(const MessageT &_msg),
256 const SubscribeOptions &_opts = SubscribeOptions());
257
266 public: template<typename MessageT>
268 const std::string &_topic,
269 std::function<void(const MessageT &_msg)> _callback,
270 const SubscribeOptions &_opts = SubscribeOptions());
271
282 public: template<typename ClassT, typename MessageT>
284 const std::string &_topic,
285 void(ClassT::*_callback)(const MessageT &_msg),
286 ClassT *_obj,
287 const SubscribeOptions &_opts = SubscribeOptions());
288
299 public: template<typename MessageT>
301 const std::string &_topic,
302 void(*_callback)(const MessageT &_msg, const MessageInfo &_info),
303 const SubscribeOptions &_opts = SubscribeOptions());
304
314 public: template<typename MessageT>
316 const std::string &_topic,
317 std::function<void(const MessageT &_msg,
318 const MessageInfo &_info)> _callback,
319 const SubscribeOptions &_opts = SubscribeOptions());
320
332 public: template<typename ClassT, typename MessageT>
334 const std::string &_topic,
335 void(ClassT::*_callback)(const MessageT &_msg,
336 const MessageInfo &_info),
337 ClassT *_obj,
338 const SubscribeOptions &_opts = SubscribeOptions());
339
346
350 public: bool Unsubscribe(const std::string &_topic);
351
364 public: template<typename RequestT, typename ReplyT>
366 const std::string &_topic,
367 bool(*_callback)(const RequestT &_request, ReplyT &_reply),
369
381 public: template<typename ReplyT>
383 const std::string &_topic,
384 bool(*_callback)(ReplyT &_reply),
386
397 public: template<typename RequestT>
399 const std::string &_topic,
400 void(*_callback)(const RequestT &_request),
402
415 public: template<typename RequestT, typename ReplyT>
417 const std::string &_topic,
418 std::function<bool(const RequestT &_request,
419 ReplyT &_reply)> _callback,
421
433 public: template<typename ReplyT>
435 const std::string &_topic,
436 std::function<bool(ReplyT &_reply)> &_callback,
438
449 public: template<typename RequestT>
451 const std::string &_topic,
452 std::function<void(const RequestT &_request)> &_callback,
454
468 public: template<typename ClassT, typename RequestT, typename ReplyT>
470 const std::string &_topic,
471 bool(ClassT::*_callback)(const RequestT &_request, ReplyT &_reply),
472 ClassT *_obj,
474
487 public: template<typename ClassT, typename ReplyT>
489 const std::string &_topic,
490 bool(ClassT::*_callback)(ReplyT &_reply),
491 ClassT *_obj,
493
505 public: template<typename ClassT, typename RequestT>
507 const std::string &_topic,
508 void(ClassT::*_callback)(const RequestT &_request),
509 ClassT *_obj,
511
515
527 public: template<typename RequestT, typename ReplyT>
529 const std::string &_topic,
530 const RequestT &_request,
531 void(*_callback)(const ReplyT &_reply, const bool _result));
532
543 public: template<typename ReplyT>
545 const std::string &_topic,
546 void(*_callback)(const ReplyT &_reply, const bool _result));
547
559 public: template<typename RequestT, typename ReplyT>
561 const std::string &_topic,
562 const RequestT &_request,
563 std::function<void(const ReplyT &_reply,
564 const bool _result)> &_callback);
565
576 public: template<typename ReplyT>
578 const std::string &_topic,
579 std::function<void(const ReplyT &_reply,
580 const bool _result)> &_callback);
581
594 public: template<typename ClassT, typename RequestT, typename ReplyT>
596 const std::string &_topic,
597 const RequestT &_request,
598 void(ClassT::*_callback)(const ReplyT &_reply, const bool _result),
599 ClassT *_obj);
600
612 public: template<typename ClassT, typename ReplyT>
614 const std::string &_topic,
615 void(ClassT::*_callback)(const ReplyT &_reply, const bool _result),
616 ClassT *_obj);
617
627 public: template<typename RequestT, typename ReplyT>
629 const std::string &_topic,
630 const RequestT &_request,
631 const unsigned int &_timeout,
632 ReplyT &_reply,
633 bool &_result);
634
643 public: template<typename ReplyT>
645 const std::string &_topic,
646 const unsigned int &_timeout,
647 ReplyT &_reply,
648 bool &_result);
649
655 public: template<typename RequestT>
656 bool Request(const std::string &_topic, const RequestT &_request);
657
672 public: bool RequestRaw(const std::string &_topic,
673 const std::string &_request, const std::string &_requestType,
674 const std::string &_responseType, unsigned int _timeout,
675 std::string &_response,
676 bool &_result);
677
681 public: bool UnadvertiseSrv(const std::string &_topic);
682
689 public: void TopicList(std::vector<std::string> &_topics) const;
690
695 public: bool GZ_DEPRECATED(13) TopicInfo(const std::string &_topic,
696 std::vector<MessagePublisher> &_publishers) const;
697
703 public: bool TopicInfo(const std::string &_topic,
704 std::vector<MessagePublisher> &_publishers,
705 std::vector<MessagePublisher> &_subscribers) const;
706
713 public: void ServiceList(std::vector<std::string> &_services) const;
714
719 public: bool ServiceInfo(
720 const std::string &_service,
721 std::vector<ServicePublisher> &_publishers) const;
722
736 public: bool SubscribeRaw(
737 const std::string &_topic,
738 const RawCallback &_callback,
739 const std::string &_msgType = kGenericMessageType,
740 const SubscribeOptions &_opts = SubscribeOptions());
741
744 public: const NodeOptions &Options() const;
745
752 public: bool EnableStats(const std::string &_topic, bool _enable,
753 const std::string &_publicationTopic = "/statistics",
754 uint64_t _publicationRate = 1);
755
762 public: std::optional<TopicStatistics> TopicStats(
763 const std::string &_topic) const;
764
771 public: void AddGlobalRelay(const std::string& _relayAddress);
772
776 public: std::vector<std::string> GlobalRelays() const;
777
781 private: NodeShared *Shared() const;
782
785 private: const std::string &NodeUuid() const;
786
789 private: std::unordered_set<std::string> &TopicsSubscribed() const;
790
793 private: std::unordered_set<std::string> &SrvsAdvertised() const;
794
798 private: bool SubscribeHelper(const std::string &_fullyQualifiedTopic);
799
800#ifdef _WIN32
801// Disable warning C4251 which is triggered by
802// std::unique_ptr
803#pragma warning(push)
804#pragma warning(disable: 4251)
805#endif
809#ifdef _WIN32
810#pragma warning(pop)
811#endif
812 };
813 }
814 }
815}
816
817#include "gz/transport/detail/Node.hh"
818
819#endif