multiple_subscriptions.cpp
Go to the documentation of this file.
1 /*
2  * Copyright (C) 2008, Morgan Quigley and Willow Garage, Inc.
3  *
4  * Redistribution and use in source and binary forms, with or without
5  * modification, are permitted provided that the following conditions are met:
6  * * Redistributions of source code must retain the above copyright notice,
7  * this list of conditions and the following disclaimer.
8  * * Redistributions in binary form must reproduce the above copyright
9  * notice, this list of conditions and the following disclaimer in the
10  * documentation and/or other materials provided with the distribution.
11  * * Neither the names of Stanford University or Willow Garage, Inc. nor the names of its
12  * contributors may be used to endorse or promote products derived from
13  * this software without specific prior written permission.
14  *
15  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
16  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
17  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
18  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
19  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
20  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
21  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
22  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
23  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
24  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
25  * POSSIBILITY OF SUCH DAMAGE.
26  */
27 
28 /* Author: Morgan Quigley */
29 
30 /*
31  * Subscribe to a topic multiple times
32  */
33 
34 #include <string>
35 #include <gtest/gtest.h>
36 #include <time.h>
37 #include <stdlib.h>
38 #include "ros/ros.h"
39 #include <test_roscpp/TestArray.h>
40 #include <test_roscpp/TestEmpty.h>
41 
42 int g_argc;
43 char** g_argv;
44 
45 class Subscriptions : public testing::Test
46 {
47  public:
49  bool got_it[4], should_have_it[4];
53  bool test_ready;
54  int n_test;
55 
56  void cb0(const test_roscpp::TestArrayConstPtr&) { if (!test_ready) return; got_it[0] = true; }
57  void cb1(const test_roscpp::TestArrayConstPtr&) { if (!test_ready) return; got_it[1] = true; }
58  void cb2(const test_roscpp::TestArrayConstPtr&) { if (!test_ready) return; got_it[2] = true; }
59  void cb3(const test_roscpp::TestArrayConstPtr&) { if (!test_ready) return; got_it[3] = true; }
60  void cb_verify(const test_roscpp::TestArrayConstPtr&)
61  {
62  if (!test_ready)
63  return;
64  n_test++;
65  /*
66  ASSERT_TRUE(((should_have_it[0] ? got_it[0] : true) &&
67  (should_have_it[1] ? got_it[1] : true) &&
68  (should_have_it[2] ? got_it[2] : true) &&
69  (should_have_it[3] ? got_it[3] : true)));
70  */
71  }
72  void cb_reset(const test_roscpp::TestArrayConstPtr&)
73  {
74  got_it[0] = got_it[1] = got_it[2] = got_it[3] = false; test_ready = true;
75  }
76 
77  protected:
78  bool sub(int cb_num)
79  {
80  ROS_INFO("Subscribing %d", cb_num);
81  boost::function<void(const test_roscpp::TestArrayConstPtr&)> funcs[4] =
82  {
83  boost::bind(&Subscriptions::cb0, this, _1),
84  boost::bind(&Subscriptions::cb1, this, _1),
85  boost::bind(&Subscriptions::cb2, this, _1),
86  boost::bind(&Subscriptions::cb3, this, _1),
87  };
88 
89  subs_[cb_num] = nh_.subscribe("roscpp/pubsub_test", 10, funcs[cb_num]);
90 
91  return subs_[cb_num];
92  }
93  bool sub_wrappers()
94  {
95  ROS_INFO("sub_wrappers");
96  verify_sub_ = nh_.subscribe("roscpp/pubsub_test", 10, &Subscriptions::cb_verify, this);
97  reset_sub_ = nh_.subscribe("roscpp/pubsub_test", 10, &Subscriptions::cb_reset, this);
98  return verify_sub_ && reset_sub_;
99  }
100  bool unsub(int cb_num)
101  {
102  ROS_INFO("unsubscribing %d", cb_num);
103  subs_[cb_num].shutdown();
104 
105  return true;
106  }
108  {
109  ROS_INFO("unsub wrappers");
110  verify_sub_.shutdown();
111  reset_sub_.shutdown();
112  return true;
113  }
114 };
115 
116 TEST_F(Subscriptions, multipleSubscriptions)
117 {
118  test_ready = false;
119 
120  for (int i = 0; i < 0x10; i++)
121  {
122  for (int j = 0; j < 4; j++)
123  should_have_it[j] = (i & (1 << j) ? true : false);
124 
125  ROS_INFO(" testing: %d, %d, %d, %d\n",
126  should_have_it[0],
127  should_have_it[1],
128  should_have_it[2],
129  should_have_it[3]);
130 
131  for (int j = 0; j < 4; j++)
132  if (should_have_it[j])
133  ASSERT_TRUE(sub(j));
134  ASSERT_TRUE(sub_wrappers());
135 
136  ros::Time t_start = ros::Time::now();
137  n_test = 0;
138  while (n_test < 10 && ros::Time::now() - t_start < ros::Duration(5000.0))
139  {
140  static int count = 0;
141  if (count++ % 10 == 0)
142  ROS_INFO("%d/100 tests completed...\n", n_test);
143 
144  ros::spinOnce();
145  ros::Duration(0.01).sleep();
146  }
147 
148  for (int j = 0; j < 4; j++)
149  if (should_have_it[j])
150  ASSERT_TRUE(unsub(j));
151  ASSERT_TRUE(unsub_wrappers());
152  }
153  SUCCEED();
154 }
155 
156 void callback1(const test_roscpp::TestArrayConstPtr&)
157 {
158 
159 }
160 
161 void callback2(const test_roscpp::TestEmptyConstPtr&)
162 {
163 
164 }
165 
166 TEST(Subscriptions2, multipleDifferentMD5Sums)
167 {
168  ros::NodeHandle nh;
169  ros::Subscriber sub1 = nh.subscribe("test", 0, callback1);
170 
171  try
172  {
173  ros::Subscriber sub2 = nh.subscribe("test", 0, callback2);
174  FAIL();
175  }
177  {
178  SUCCEED();
179  }
180 }
181 
182 int main(int argc, char** argv)
183 {
184  testing::InitGoogleTest(&argc, argv);
185  ros::init(argc, argv, "multiple_subscriptions");
186  ros::NodeHandle nh;
187  g_argc = argc;
188  g_argv = argv;
189  return RUN_ALL_TESTS();
190 }
191 
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
void cb1(const test_roscpp::TestArrayConstPtr &)
bool sleep() const
int main(int argc, char **argv)
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
ros::Subscriber reset_sub_
void cb3(const test_roscpp::TestArrayConstPtr &)
ros::Subscriber verify_sub_
void callback1(const test_roscpp::TestArrayConstPtr &)
bool unsub(int cb_num)
bool sub(int cb_num)
void cb2(const test_roscpp::TestArrayConstPtr &)
void cb0(const test_roscpp::TestArrayConstPtr &)
#define ROS_INFO(...)
void callback2(const test_roscpp::TestEmptyConstPtr &)
TEST(Subscriptions2, multipleDifferentMD5Sums)
TEST_F(Subscriptions, multipleSubscriptions)
void cb_reset(const test_roscpp::TestArrayConstPtr &)
static Time now()
ROSCPP_DECL void spinOnce()
void cb_verify(const test_roscpp::TestArrayConstPtr &)
char ** g_argv
ros::Subscriber subs_[4]


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