subscribe_star.cpp
Go to the documentation of this file.
1 /*
2  * Copyright (c) 2010, Willow Garage, Inc.
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  *
8  * * Redistributions of source code must retain the above copyright
9  * notice, this list of conditions and the following disclaimer.
10  * * Redistributions in binary form must reproduce the above copyright
11  * notice, this list of conditions and the following disclaimer in the
12  * documentation and/or other materials provided with the distribution.
13  * * Neither the name of Willow Garage, Inc. nor the names of its
14  * contributors may be used to endorse or promote products derived from
15  * this software without specific prior written permission.
16  *
17  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
18  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
19  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
20  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
21  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
22  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
23  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
24  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
25  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
26  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
27  * POSSIBILITY OF SUCH DAMAGE.
28  */
29 
30 /*
31  * Author: Josh Faust
32  */
33 
34 #include <gtest/gtest.h>
35 
36 #include <ros/ros.h>
37 #include <ros/connection_manager.h>
38 
39 #include "test_roscpp/TestEmpty.h"
40 #include "test_roscpp/TestArray.h"
41 
42 #include <std_srvs/Empty.h>
43 
45 {
46 };
49 
50 namespace ros
51 {
52 namespace message_traits
53 {
54 
55 template<>
57 {
58  static const char* value() { return "*"; }
59  static const char* value(const AnyMessage&) { return "*"; }
60 };
61 
62 template<>
64 {
65  static const char* value() { return "*"; }
66  static const char* value(const AnyMessage&) { return "*"; }
67 };
68 
69 template<>
71 {
72 };
73 
74 }
75 
76 namespace serialization
77 {
78 template<>
80 {
81  template<typename Stream, typename T>
82  static void allInOne(Stream, T)
83  {
84  }
85 
87 };
88 }
89 }
90 
91 struct AnyHelper
92 {
94  : count(0)
95  {
96  }
97 
98  void cb(const AnyMessageConstPtr&)
99  {
100  ++count;
101  }
102 
103  uint32_t count;
104 };
105 
106 
107 TEST(SubscribeStar, simpleSubFirstIntra)
108 {
109  ros::NodeHandle nh;
110  AnyHelper h;
111  ros::Subscriber sub = nh.subscribe("test_star_intra", 0, &AnyHelper::cb, &h);
112  ros::Publisher pub = nh.advertise<test_roscpp::TestEmpty>("test_star_intra", 0);
113 
114  EXPECT_EQ(pub.getNumSubscribers(), 1U);
115  EXPECT_EQ(sub.getNumPublishers(), 1U);
116 
117  AnyMessagePtr msg(boost::make_shared<AnyMessage>());
118  pub.publish(msg);
119  ros::spinOnce();
120  EXPECT_EQ(h.count, 1U);
121 }
122 
123 TEST(SubscribeStar, simplePubFirstIntra)
124 {
125  ros::NodeHandle nh;
126  AnyHelper h;
127  ros::Publisher pub = nh.advertise<test_roscpp::TestEmpty>("test_star_intra", 0);
128  ros::Subscriber sub = nh.subscribe("test_star_intra", 0, &AnyHelper::cb, &h);
129 
130  EXPECT_EQ(pub.getNumSubscribers(), 1U);
131  EXPECT_EQ(sub.getNumPublishers(), 1U);
132 
133  AnyMessagePtr msg(boost::make_shared<AnyMessage>());
134  pub.publish(msg);
135  ros::spinOnce();
136  EXPECT_EQ(h.count, 1U);
137 }
138 
139 void emptyCallback(const test_roscpp::TestEmptyConstPtr&)
140 {
141 
142 }
143 
144 TEST(SubscribeStar, multipleSubsStarFirstIntra)
145 {
146  ros::NodeHandle nh;
147  AnyHelper h;
148  ros::Subscriber sub = nh.subscribe("test_star_intra", 0, &AnyHelper::cb, &h);
149  ros::Subscriber sub2 = nh.subscribe("test_star_intra", 0, emptyCallback);
150 
151  ros::Publisher pub = nh.advertise<test_roscpp::TestEmpty>("test_star_intra", 0);
152  EXPECT_EQ(pub.getNumSubscribers(), 1U);
153  EXPECT_EQ(sub.getNumPublishers(), 1U);
154  EXPECT_EQ(sub2.getNumPublishers(), 1U);
155 
156  pub.shutdown();
157  pub = nh.advertise<test_roscpp::TestArray>("test_star_intra", 0);
158  EXPECT_EQ(pub.getNumSubscribers(), 0U);
159  EXPECT_EQ(sub.getNumPublishers(), 0U);
160  EXPECT_EQ(sub2.getNumPublishers(), 0U);
161 }
162 
163 TEST(SubscribeStar, multipleSubsConcreteFirstIntra)
164 {
165  ros::NodeHandle nh;
166  AnyHelper h;
167  ros::Subscriber sub2 = nh.subscribe("test_star_intra", 0, emptyCallback);
168  ros::Subscriber sub = nh.subscribe("test_star_intra", 0, &AnyHelper::cb, &h);
169 
170  ros::Publisher pub = nh.advertise<test_roscpp::TestEmpty>("test_star_intra", 0);
171  EXPECT_EQ(pub.getNumSubscribers(), 1U);
172  EXPECT_EQ(sub.getNumPublishers(), 1U);
173  EXPECT_EQ(sub2.getNumPublishers(), 1U);
174 
175  pub.shutdown();
176  pub = nh.advertise<test_roscpp::TestArray>("test_star_intra", 0);
177  EXPECT_EQ(pub.getNumSubscribers(), 0U);
178  EXPECT_EQ(sub.getNumPublishers(), 0U);
179  EXPECT_EQ(sub2.getNumPublishers(), 0U);
180 }
181 
182 TEST(SubscribeStar, multipleShutdownConcreteIntra)
183 {
184  ros::NodeHandle nh;
185  AnyHelper h;
186  ros::Subscriber sub = nh.subscribe("test_star_intra", 0, &AnyHelper::cb, &h);
187  ros::Subscriber sub2 = nh.subscribe("test_star_intra", 0, emptyCallback);
188  sub2.shutdown();
189 
190  ros::Publisher pub = nh.advertise<test_roscpp::TestEmpty>("test_star_intra", 0);
191  EXPECT_EQ(pub.getNumSubscribers(), 1U);
192  EXPECT_EQ(sub.getNumPublishers(), 1U);
193 
194  pub.shutdown();
195  pub = nh.advertise<test_roscpp::TestArray>("test_star_intra", 0);
196  EXPECT_EQ(pub.getNumSubscribers(), 0U);
197  EXPECT_EQ(sub.getNumPublishers(), 0U);
198 }
199 
200 TEST(SubscribeStar, simpleInter)
201 {
202  ros::NodeHandle nh;
203  AnyHelper h;
204  ros::Subscriber sub = nh.subscribe("test_star_inter", 0, &AnyHelper::cb, &h);
205 
206  ros::WallDuration(1.0).sleep();
207  ros::spinOnce();
208 
209  EXPECT_EQ(sub.getNumPublishers(), 1U);
210  EXPECT_GT(h.count, 0U);
211 }
212 
213 TEST(SubscribeStar, simpleInterUDP)
214 {
215  ros::NodeHandle nh;
216  AnyHelper h;
217  ros::Subscriber sub = nh.subscribe("test_star_inter", 0, &AnyHelper::cb, &h, ros::TransportHints().udp());
218 
219  ros::WallDuration(1.0).sleep();
220  ros::spinOnce();
221 
222  EXPECT_EQ(sub.getNumPublishers(), 1U);
223  EXPECT_GT(h.count, 0U);
224 }
225 
226 // must be the last test as it makes the service node exit
227 TEST(SubscribeStar, switchTypeInter)
228 {
229  ros::NodeHandle nh;
230  AnyHelper h;
231  ros::Subscriber sub = nh.subscribe("test_star_inter", 0, &AnyHelper::cb, &h);
232  ros::Subscriber sub2 = nh.subscribe("test_star_inter", 0, emptyCallback);
233 
234  ros::WallDuration(1.0).sleep();
235  ros::spinOnce();
236 
237  ASSERT_EQ(sub.getNumPublishers(), 1U);
238  ASSERT_EQ(sub2.getNumPublishers(), 1U);
239 
240  std_srvs::Empty srv;
241  // by invoking the service call the service node will exit with FATAL
242  ASSERT_TRUE(ros::service::call("switch_publisher_type", srv));
243 
244  ros::WallDuration(1.0).sleep();
245  ros::spinOnce();
246 
247  ASSERT_EQ(sub.getNumPublishers(), 0U);
248  ASSERT_EQ(sub2.getNumPublishers(), 0U);
249 }
250 
251 // disabled because switchTypeInter will stop the other node intentionally
252 //TEST(SubscribeStar, switchTypeInterUDP)
253 //{
254 // ros::NodeHandle nh;
255 // AnyHelper h;
256 // ros::Subscriber sub = nh.subscribe("test_star_inter", 0, &AnyHelper::cb, &h, ros::TransportHints().udp());
257 // ros::Subscriber sub2 = nh.subscribe("test_star_inter", 0, emptyCallback, ros::TransportHints().udp());
258 //
259 // ros::WallDuration(1.0).sleep();
260 // ros::spinOnce();
261 //
262 // ASSERT_EQ(sub.getNumPublishers(), 1U);
263 // ASSERT_EQ(sub2.getNumPublishers(), 1U);
264 //
265 // std_srvs::Empty srv;
266 // // by invoking the service call the service node will exit with FATAL
267 // ASSERT_TRUE(ros::service::call("switch_publisher_type", srv));
268 //
269 // ros::WallDuration(1.0).sleep();
270 // ros::spinOnce();
271 //
272 // ASSERT_EQ(sub.getNumPublishers(), 0U);
273 // ASSERT_EQ(sub2.getNumPublishers(), 0U);
274 //}
275 
276 int main(int argc, char** argv)
277 {
278  testing::InitGoogleTest(&argc, argv);
279  ros::init(argc, argv, "subscribe_star");
280  ros::NodeHandle nh;
281  return RUN_ALL_TESTS();
282 }
boost::shared_ptr< AnyMessage > AnyMessagePtr
void publish(const boost::shared_ptr< M > &message) const
static const char * value(const AnyMessage &)
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
static const char * value(const AnyMessage &)
#define ROS_DECLARE_ALLINONE_SERIALIZER
bool call(const std::string &service_name, MReq &req, MRes &res)
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
bool sleep() const
uint32_t count
uint32_t getNumPublishers() const
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
void emptyCallback(const test_roscpp::TestEmptyConstPtr &)
void cb(const AnyMessageConstPtr &)
TEST(SubscribeStar, simpleSubFirstIntra)
uint32_t getNumSubscribers() const
ROSCPP_DECL void spinOnce()
boost::shared_ptr< AnyMessage const > AnyMessageConstPtr
int main(int argc, char **argv)


test_roscpp
Author(s): Morgan Quigley, Josh Faust, Brian Gerkey, Troy Straszheim, Dirk Thomas
autogenerated on Mon Nov 2 2020 03:52:46