sub_pub.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 <ros/callback_queue.h>
45 #include <test_roscpp/TestArray.h>
46 
49 uint32_t g_options;
50 
51 class Subscriptions : public testing::Test
52 {
53  public:
54  bool success;
55  bool failure;
56  int msg_i;
58 
59  void messageCallback(const test_roscpp::TestArrayConstPtr& msg)
60  {
61  if(failure || success)
62  return;
63 
64  //printf("received message %d\n", msg.counter);
65  if (msg_i == -1)
66  {
67  msg_i = msg->counter - 1;
68  }
69 
70  msg_i++;
71  //ROS_INFO("msg_i=%d, counter=%d", msg_i, msg->counter);
72  if(msg_i != msg->counter)
73  {
74  failure = true;
75  ROS_INFO("failed");
76  }
77  else if(msg_i == (g_msg_count-1))
78  {
79  success = true;
80  ROS_INFO("success");
81  }
82  else
83  {
84  pub_.publish(msg);
85  }
86  }
87 
89  {
90  test_roscpp::TestArray msg;
91  msg.counter = 0;
92  pub_.publish(msg);
93  }
94 
95  protected:
96  void SetUp()
97  {
98  success = false;
99  failure = false;
100 
101  msg_i = -1;
102  }
103  void TearDown()
104  {
105 
106  }
107 };
108 
110 {
111  ros::NodeHandle nh;
112  ros::Subscriber sub = nh.subscribe("roscpp/pubsub_test", 0, &Subscriptions::messageCallback, (Subscriptions*)this);
113  ASSERT_TRUE(sub);
114  pub_ = nh.advertise<test_roscpp::TestArray>("roscpp/subpub_test", 0, boost::bind(&Subscriptions::subscriberCallback, this, _1));
115  ASSERT_TRUE(pub_);
116  ros::Time t1(ros::Time::now()+g_dt);
117 
118  while(ros::Time::now() < t1 && !success && !failure)
119  {
121  }
122 
123  if(success)
124  SUCCEED();
125  else
126  FAIL();
127 }
128 
129 #define USAGE "USAGE: sub_pub <count> <time>"
130 
131 int
132 main(int argc, char** argv)
133 {
134  testing::InitGoogleTest(&argc, argv);
135  ros::init(argc, argv, "sub_pub");
136 
137  if(argc != 3)
138  {
139  puts(USAGE);
140  return -1;
141  }
142  g_msg_count = atoi(argv[1]);
143  g_dt.fromSec(atof(argv[2]));
144 
145  ros::NodeHandle nh;
146 
147  return RUN_ALL_TESTS();
148 }
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())
uint32_t g_options
Definition: sub_pub.cpp:49
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
ros::Publisher pub_
Definition: sub_pub.cpp:57
bool sub(int cb_num)
ros::Duration g_dt
Definition: sub_pub.cpp:48
ROSCPP_DECL CallbackQueue * getGlobalCallbackQueue()
void subscriberCallback(const ros::SingleSubscriberPublisher &)
Definition: sub_pub.cpp:88
Duration & fromSec(double t)
#define ROS_INFO(...)
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
int main(int argc, char **argv)
Definition: sub_pub.cpp:132
bool failure
Definition: sub_pub.cpp:55
test_roscpp::TestEmpty msg
#define USAGE
Definition: sub_pub.cpp:129
bool success
Definition: sub_pub.cpp:54
static Time now()
TEST_F(Subscriptions, subPub)
Definition: sub_pub.cpp:109
void SetUp()
Definition: sub_pub.cpp:96
int g_msg_count
Definition: sub_pub.cpp:47
void TearDown()
Definition: sub_pub.cpp:103
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