subscribe_self.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 <stdlib.h>
41 
42 #include "ros/ros.h"
43 #include <test_roscpp/TestArray.h>
44 
47 uint32_t g_options = 0;
48 bool g_success = false;
49 bool g_failure = false;
50 int32_t g_msg_i = -1;
51 
53 {
54  test_roscpp::TestArray outmsg;
55  for(int i=0;i<g_msg_count;i++)
56  {
57  outmsg.counter = i;
58  pub.publish(outmsg);
59  ROS_INFO("published %d", i);
60  }
61 }
62 
63 void messageCallback(const test_roscpp::TestArrayConstPtr& msg)
64 {
65  ROS_INFO("received message %d", msg->counter);
66  if(g_failure || g_success)
67  return;
68 
69  g_msg_i++;
70  if(g_msg_i != msg->counter)
71  {
72  g_failure = true;
73  ROS_INFO("failed");
74  }
75  else if(g_msg_i == (g_msg_count-1))
76  {
77  g_success = true;
78  ROS_INFO("success");
79  }
80 }
81 
82 TEST(SelfSubscribe, advSub)
83 {
84  ros::NodeHandle nh;
86  d.fromNSec(10000000);
87 
88  g_success = false;
89  g_failure = false;
90  g_msg_i = -1;
91 
92  {
93  ros::Publisher pub;
94  pub = nh.advertise<test_roscpp::TestArray>("roscpp/pubsub_test", g_msg_count, boost::bind(subscriberCallback, _1, boost::ref(pub)));
95  ASSERT_TRUE(pub);
96  ros::Subscriber sub = nh.subscribe("roscpp/pubsub_test", g_msg_count, messageCallback);
97  ASSERT_TRUE(sub);
98  ros::Time t1(ros::Time::now()+g_dt);
99  while(ros::Time::now() < t1 && !g_success && !g_failure)
100  {
101  d.sleep();
102  ros::spinOnce();
103  }
104  }
105 
106  ASSERT_TRUE(g_success);
107  ASSERT_FALSE(g_failure);
108 
109  // Now try the other order
110  g_success = false;
111  g_failure = false;
112  g_msg_i = -1;
113 
114  {
115  ros::Subscriber sub = nh.subscribe("roscpp/pubsub_test", g_msg_count, messageCallback);
116  ASSERT_TRUE(sub);
117  ros::Publisher pub;
118  pub = nh.advertise<test_roscpp::TestArray>("roscpp/pubsub_test", g_msg_count, boost::bind(subscriberCallback, _1, boost::ref(pub)));
119  ASSERT_TRUE(pub);
120 
121  ros::Time t1(ros::Time::now()+g_dt);
122  while(ros::Time::now() < t1 && !g_success && !g_failure)
123  {
124  d.sleep();
125  ros::spinOnce();
126  }
127  }
128 
129 
130  ASSERT_TRUE(g_success);
131  ASSERT_FALSE(g_failure);
132 }
133 
134 #define USAGE "USAGE: sub_pub <count> <time>"
135 
136 int
137 main(int argc, char** argv)
138 {
139  testing::InitGoogleTest(&argc, argv);
140  ros::init(argc, argv, "subscribe_self");
141 
142  if(argc != 3)
143  {
144  puts(USAGE);
145  return -1;
146  }
147 
148  g_msg_count = atoi(argv[1]);
149  g_dt.fromSec(atof(argv[2]));
150 
151  ros::NodeHandle nh;
152 
153  return RUN_ALL_TESTS();
154 }
d
int32_t g_msg_i
uint32_t g_options
int g_msg_count
#define USAGE
void publish(const boost::shared_ptr< M > &message) const
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
bool sleep() const
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
void messageCallback(const test_roscpp::TestArrayConstPtr &msg)
bool g_success
Duration & fromSec(double t)
#define ROS_INFO(...)
bool g_failure
void subscriberCallback(const ros::SingleSubscriberPublisher &, const ros::Publisher &pub)
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
ros::Duration g_dt
Duration & fromNSec(int64_t t)
static Time now()
ROSCPP_DECL void spinOnce()
int main(int argc, char **argv)
TEST(SelfSubscribe, advSub)


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