relay.cpp
Go to the documentation of this file.
1 // relay just passes messages on. it can be useful if you're trying to ensure
3 // that a message doesn't get sent twice over a wireless link, by having the
4 // relay catch the message and then do the fanout on the far side of the
5 // wireless link.
6 //
7 // Copyright (C) 2009, Morgan Quigley
8 //
9 // Redistribution and use in source and binary forms, with or without
10 // modification, are permitted provided that the following conditions are met:
11 // * Redistributions of source code must retain the above copyright notice,
12 // this list of conditions and the following disclaimer.
13 // * Redistributions in binary form must reproduce the above copyright
14 // notice, this list of conditions and the following disclaimer in the
15 // documentation and/or other materials provided with the distribution.
16 // * Neither the name of Stanford University nor the names of its
17 // contributors may be used to endorse or promote products derived from
18 // this software without specific prior written permission.
19 //
20 // THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
21 // AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
22 // IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
23 // ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
24 // LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
25 // CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
26 // SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
27 // INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
28 // CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
29 // ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
30 // POSSIBILITY OF SUCH DAMAGE.
32 
33 
34 #include <cstdio>
36 #include "topic_tools/parse.h"
37 
38 using std::string;
39 using std::vector;
40 using namespace topic_tools;
41 
43 bool g_advertised = false;
48 bool g_lazy;
50 
52 void in_cb(const ros::MessageEvent<ShapeShifter>& msg_event);
53 
54 void subscribe()
55 {
56  g_sub = new ros::Subscriber(g_node->subscribe(g_input_topic, 10, &in_cb, g_th));
57 }
58 
60 {
61  // If we're in lazy subscribe mode, and the first subscriber just
62  // connected, then subscribe, #3389.
63  if(g_lazy && !g_sub)
64  {
65  ROS_DEBUG("lazy mode; resubscribing");
66  subscribe();
67  }
68 }
69 
70 void in_cb(const ros::MessageEvent<ShapeShifter>& msg_event)
71 {
73  boost::shared_ptr<const ros::M_string> const& connection_header = msg_event.getConnectionHeaderPtr();
74 
75  if (!g_advertised)
76  {
77  // If the input topic is latched, make the output topic latched, #3385.
78  bool latch = false;
79  if (connection_header)
80  {
81  ros::M_string::const_iterator it = connection_header->find("latching");
82  if((it != connection_header->end()) && (it->second == "1"))
83  {
84  ROS_DEBUG("input topic is latched; latching output topic to match");
85  latch = true;
86  }
87  }
88  g_pub = msg->advertise(*g_node, g_output_topic, 10, latch, conn_cb);
89  g_advertised = true;
90  ROS_INFO("advertised as %s\n", g_output_topic.c_str());
91  }
92  // If we're in lazy subscribe mode, and nobody's listening,
93  // then unsubscribe, #3389.
94  if(g_lazy && !g_pub.getNumSubscribers())
95  {
96  ROS_DEBUG("lazy mode; unsubscribing");
97  delete g_sub;
98  g_sub = NULL;
99  }
100  else
101  g_pub.publish(msg);
102 }
103 
104 int main(int argc, char **argv)
105 {
106  if (argc < 2)
107  {
108  printf("\nusage: relay IN_TOPIC [OUT_TOPIC]\n\n");
109  return 1;
110  }
111  std::string topic_name;
112  if(!getBaseName(string(argv[1]), topic_name))
113  return 1;
114  ros::init(argc, argv, topic_name + string("_relay"),
116  if (argc == 2)
117  g_output_topic = string(argv[1]) + string("_relay");
118  else // argc == 3
119  g_output_topic = string(argv[2]);
120  g_input_topic = string(argv[1]);
121  ros::NodeHandle n;
122  g_node = &n;
123 
124  ros::NodeHandle pnh("~");
125  bool unreliable = false;
126  pnh.getParam("unreliable", unreliable);
127  pnh.getParam("lazy", g_lazy);
128  if (unreliable)
129  g_th.unreliable().reliable(); // Prefers unreliable, but will accept reliable.
130 
131  subscribe();
132  ros::spin();
133  return 0;
134 }
135 
void in_cb(const ros::MessageEvent< ShapeShifter > &msg_event)
Definition: relay.cpp:70
ros::NodeHandle * g_node
Definition: relay.cpp:42
TransportHints & reliable()
void publish(const boost::shared_ptr< M > &message) const
bool g_advertised
Definition: relay.cpp:43
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
string g_output_topic
Definition: relay.cpp:45
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
const boost::shared_ptr< M_string > & getConnectionHeaderPtr() const
void subscribe()
Definition: relay.cpp:54
string g_input_topic
Definition: relay.cpp:44
const boost::shared_ptr< ConstMessage > & getConstMessage() const
ros::TransportHints g_th
Definition: relay.cpp:49
bool g_lazy
Definition: relay.cpp:48
TransportHints & unreliable()
TOPIC_TOOLS_DECL bool getBaseName(const std::string &full_name, std::string &base_name)
Definition: parse.cpp:40
#define ROS_INFO(...)
ros::Publisher g_pub
Definition: relay.cpp:46
ROSCPP_DECL void spin()
int main(int argc, char **argv)
Definition: relay.cpp:104
void conn_cb(const ros::SingleSubscriberPublisher &)
Definition: relay.cpp:59
uint32_t getNumSubscribers() const
bool getParam(const std::string &key, std::string &s) const
ros::Subscriber * g_sub
Definition: relay.cpp:47
#define ROS_DEBUG(...)


topic_tools
Author(s): Morgan Quigley, Brian Gerkey, Dirk Thomas
autogenerated on Mon Nov 2 2020 03:52:58