subscribe_n_fast.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 int g_argc;
47 char** g_argv;
48 
49 class Subscriptions : public testing::Test
50 {
51  public:
52  // A node is needed to make a service call
54  bool success;
55  bool failure;
56  std::string transport;
57  bool reliable;
61 
62  void MsgCallback(const test_roscpp::TestArray::ConstPtr& msg)
63  {
64  if (failure || success)
65  return;
66 
67  printf("received message %d\n", msg->counter);
68  msgs_received++;
69  if (reliable)
70  {
71  if (msgs_received != msg->counter)
72  {
73  failure = true;
74  puts("failed");
75  }
76  if (msgs_received == (msgs_expected - 1))
77  {
78  success = true;
79  puts("success");
80  }
81  }
82  else
83  {
84  if (msgs_received > msg->counter)
85  {
86  failure = true;
87  printf("failed: %d > %d\n", msgs_received, msg->counter);
88  }
89  if (msgs_received > (0.01 * msgs_expected))
90  {
91  success = true;
92  puts("success");
93  }
94  }
95 
96  }
97 
98  protected:
100  void SetUp()
101  {
102  success = false;
103  failure = false;
104 
105  msgs_received = -1;
106  ASSERT_TRUE(g_argc == 4);
107  transport = g_argv[1];
108  msgs_expected = atoi(g_argv[2]);
109  dt.fromSec(atof(g_argv[3]));
110  if (transport == "tcp")
111  reliable = true;
112  else if (transport == "udp")
113  reliable = false;
114  else
115  {
116  ROS_ERROR("Unknown transport: %s", transport.c_str());
117  FAIL();
118  }
119  }
120  void TearDown()
121  {
122  }
123 };
124 
125 TEST_F(Subscriptions, pubSubNFast)
126 {
127  ros::TransportHints hints;
128  if (reliable)
129  hints.reliable();
130  else
131  hints.unreliable();
132 
133  ros::Subscriber sub = n.subscribe("roscpp/pubsub_test", msgs_expected, &Subscriptions::MsgCallback, (Subscriptions *)this, hints);
134 
135  ASSERT_TRUE(sub);
136 
137  ros::Time t1(ros::Time::now() + dt);
138 
139  while(ros::Time::now() < t1 && !success)
140  {
141  ros::spinOnce();
142  ros::WallDuration(0.01).sleep();
143  }
144 
145  printf("msgs_received == %d\n", msgs_received);
146  if(success)
147  SUCCEED();
148  else
149  FAIL();
150 }
151 
152 int
153 main(int argc, char** argv)
154 {
155  testing::InitGoogleTest(&argc, argv);
156  ros::init(argc, argv, "subscriber");
157  g_argc = argc;
158  g_argv = argv;
159  return RUN_ALL_TESTS();
160 }
void MsgCallback(const test_roscpp::TestArray::ConstPtr &msg)
TransportHints & reliable()
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
ros::Duration dt
char ** g_argv
TEST_F(Subscriptions, pubSubNFast)
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
int g_argc
bool sub(int cb_num)
std::string transport
TransportHints & unreliable()
bool sleep() const
Duration & fromSec(double t)
ros::NodeHandle n
int main(int argc, char **argv)
bool failure
Definition: sub_pub.cpp:55
test_roscpp::TestEmpty msg
bool success
Definition: sub_pub.cpp:54
static Time now()
ROSCPP_DECL void spinOnce()
#define ROS_ERROR(...)


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