subscribe_unsubscribe.cpp
Go to the documentation of this file.
1 /*
2  * Copyright (c) 2008, 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 /* Author: Brian Gerkey */
31 
32 /*
33  * Subscribe to a topic, expecting to get a single message.
34  */
35 
36 #include <string>
37 
38 #include <gtest/gtest.h>
39 
40 #include <time.h>
41 #include <stdlib.h>
42 
43 #include "ros/ros.h"
44 #include <test_roscpp/TestArray.h>
45 
46 #include <boost/thread.hpp>
47 
48 int g_argc;
49 char** g_argv;
50 
51 class Subscriptions : public testing::Test
52 {
53 public:
56 
57  void messageCallback(const test_roscpp::TestArrayConstPtr&)
58  {
59  ROS_INFO("in callback");
60 
61  if(!sub_)
62  {
63  ROS_INFO("but not subscribed!");
64  FAIL();
65  }
66  }
67 
68  void autoUnsubscribeCallback(const test_roscpp::TestArrayConstPtr&)
69  {
70  ROS_INFO("in autounsub callback");
71  sub_.shutdown();
72  }
73 
74 protected:
76 };
77 
79 {
80  sub_.shutdown();
81 
82  for(int i=0;i<100;i++)
83  {
84  if(!sub_)
85  {
86  sub_ = nh_.subscribe("roscpp/pubsub_test", 0, &Subscriptions::messageCallback, (Subscriptions*)this);
87  ASSERT_TRUE(sub_);
88  }
89  else
90  {
91  sub_.shutdown();
92  ASSERT_FALSE(sub_);
93  }
94 
95  ros::WallDuration(0.01).sleep();
96  ros::spinOnce();
97  }
98 }
99 
100 TEST_F(Subscriptions, unsubInCallback)
101 {
102  sub_ = nh_.subscribe("roscpp/pubsub_test", 0, &Subscriptions::autoUnsubscribeCallback, (Subscriptions*)this);
103 
104  while (sub_ && ros::ok())
105  {
106  ros::WallDuration(0.01).sleep();
107  ros::spinOnce();
108  }
109 }
110 
111 void spinThread(bool volatile* cont)
112 {
113  while (*cont)
114  {
115  ros::spinOnce();
116  ros::Duration(0.001).sleep();
117  }
118 }
119 
120 void unsubscribeAfterBarrierWait(boost::barrier* barrier, ros::Subscriber& sub)
121 {
122  barrier->wait();
123 
124  sub.shutdown();
125 }
126 
127 TEST_F(Subscriptions, unsubInCallbackAndOtherThread)
128 {
129  boost::barrier barrier(2);
130  for (int i = 0; i < 100; ++i)
131  {
133  sub_ = nh_.subscribe<test_roscpp::TestArray>("roscpp/pubsub_test", 1, boost::bind(unsubscribeAfterBarrierWait, &barrier, boost::ref(sub)));
134  sub = sub_;
135 
136  bool cont = true;
137  boost::thread t(spinThread, &cont);
138 
139  barrier.wait();
140 
141  sub_.shutdown();
142  cont = false;
143  t.join();
144  }
145 }
146 
147 int
148 main(int argc, char** argv)
149 {
150  testing::InitGoogleTest(&argc, argv);
151 
152  g_argc = argc;
153  g_argv = argv;
154 
155  ros::init(g_argc, g_argv, "subscribe_unsubscribe");
156 
157  if (g_argc != 1)
158  {
159  puts("Too many arguments\n");
160  return -1;
161  }
162 
163  return RUN_ALL_TESTS();
164 }
TEST_F(Subscriptions, subUnsub)
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
void messageCallback(const test_roscpp::TestArrayConstPtr &)
bool sleep() const
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
ros::Subscriber sub_
bool sub(int cb_num)
bool sleep() const
void autoUnsubscribeCallback(const test_roscpp::TestArrayConstPtr &)
#define ROS_INFO(...)
ROSCPP_DECL bool ok()
char ** g_argv
int main(int argc, char **argv)
void unsubscribeAfterBarrierWait(boost::barrier *barrier, ros::Subscriber &sub)
ROSCPP_DECL void spinOnce()
ros::WallTime t
void spinThread(bool volatile *cont)
void messageCallback(const test_roscpp::TestArrayConstPtr &msg)
Definition: sub_pub.cpp:59


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