topic_proxy.h
Go to the documentation of this file.
1 //=================================================================================================
2 // Copyright (c) 2013, Johannes Meyer, TU Darmstadt
3 // All rights reserved.
4 
5 // Redistribution and use in source and binary forms, with or without
6 // modification, are permitted provided that the following conditions are met:
7 // * Redistributions of source code must retain the above copyright
8 // notice, this list of conditions and the following disclaimer.
9 // * Redistributions in binary form must reproduce the above copyright
10 // notice, this list of conditions and the following disclaimer in the
11 // documentation and/or other materials provided with the distribution.
12 // * Neither the name of the Flight Systems and Automatic Control group,
13 // TU Darmstadt, nor the names of its contributors may be used to
14 // endorse or promote products derived from this software without
15 // specific prior written permission.
16 
17 // THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
18 // ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
19 // WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
20 // DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER BE LIABLE FOR ANY
21 // DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
22 // (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
23 // LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
24 // ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
25 // (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
26 // SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
27 //=================================================================================================
28 
29 #ifndef TOPIC_PROXY_H
30 #define TOPIC_PROXY_H
31 
33 
34 #include <topic_proxy/GetMessage.h>
35 #include <topic_proxy/PublishMessage.h>
36 
37 namespace topic_proxy
38 {
39 
40 extern const uint32_t g_default_port;
41 extern const std::string g_get_message_service;
42 extern const std::string g_publish_message_service;
43 
45 {
46 private:
47  std::string host_;
48  uint16_t port_;
49 
50 public:
51  TopicProxy();
52  TopicProxy(const std::string& host, uint32_t port = 0);
53  virtual ~TopicProxy();
54 
55  bool connect();
56  void shutdown();
57 
58  const std::string& getHost() const { return host_; }
59  uint16_t getTCPPort() const { return port_; }
60 
61  template <class M> boost::shared_ptr<const M> getMessage(const std::string& topic, ros::Duration timeout = ros::Duration(), bool compressed = false);
62  template <class M> void publishMessage(const M& message, const std::string& topic, bool compressed = false);
63 
64 protected:
66  MessageInstanceConstPtr send(GetMessage::Request&);
67 
69  bool send(PublishMessage::Request&);
70 };
71 
72 template <class M>
73 boost::shared_ptr<const M> TopicProxy::getMessage(const std::string& topic, ros::Duration timeout, bool compressed)
74 {
75  GetMessage::Request request;
76  request.topic = topic;
77  request.compressed = compressed;
78  request.timeout = timeout;
79 
80  MessageInstanceConstPtr result = send(request);
81  if (!result) return boost::shared_ptr<const M>();
82  return result ? result->blob.instantiate<const M>() : boost::shared_ptr<const M>();
83 }
84 
85 template <class M>
86 void TopicProxy::publishMessage(const M& message, const std::string& topic, bool compressed)
87 {
88  PublishMessage::Request request;
89  request.message.topic = topic;
90  request.message.md5sum = ros::message_traits::md5sum<M>(message);
91  request.message.type = ros::message_traits::datatype<M>(message);
92  request.message.message_definition = ros::message_traits::definition<M>(message);
93  request.message.blob.setCompressed(compressed);
94  request.message.blob.serialize(message);
95 
96  return send(request);
97 }
98 
99 } // namespace topic_proxy
100 
101 #endif // TOPIC_PROXY_H
boost::shared_ptr< const M > getMessage(const std::string &topic, ros::Duration timeout=ros::Duration(), bool compressed=false)
Definition: topic_proxy.h:73
ServiceClient get_message_
Definition: topic_proxy.h:65
const uint32_t g_default_port
Definition: topic_proxy.cpp:18
const std::string g_get_message_service
Definition: topic_proxy.cpp:16
const std::string g_publish_message_service
Definition: topic_proxy.cpp:17
uint16_t getTCPPort() const
Definition: topic_proxy.h:59
const std::string & getHost() const
Definition: topic_proxy.h:58
MessageInstanceConstPtr send(GetMessage::Request &)
Definition: topic_proxy.cpp:47
ServiceClient publish_message_
Definition: topic_proxy.h:68
void publishMessage(const M &message, const std::string &topic, bool compressed=false)
Definition: topic_proxy.h:86


topic_proxy
Author(s): Johannes Meyer
autogenerated on Sat Jul 27 2019 03:35:25