35 #include <gtest/gtest.h> 39 #include <test_roscpp/TestArray.h> 40 #include <test_roscpp/TestEmpty.h> 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&)
72 void cb_reset(
const test_roscpp::TestArrayConstPtr&)
74 got_it[0] = got_it[1] = got_it[2] = got_it[3] =
false; test_ready =
true;
81 boost::function<void(const test_roscpp::TestArrayConstPtr&)> funcs[4] =
89 subs_[cb_num] = nh_.
subscribe(
"roscpp/pubsub_test", 10, funcs[cb_num]);
102 ROS_INFO(
"unsubscribing %d", cb_num);
120 for (
int i = 0; i < 0x10; i++)
122 for (
int j = 0; j < 4; j++)
125 ROS_INFO(
" testing: %d, %d, %d, %d\n",
131 for (
int j = 0; j < 4; j++)
140 static int count = 0;
141 if (count++ % 10 == 0)
148 for (
int j = 0; j < 4; j++)
150 ASSERT_TRUE(
unsub(j));
166 TEST(Subscriptions2, multipleDifferentMD5Sums)
182 int main(
int argc,
char** argv)
184 testing::InitGoogleTest(&argc, argv);
185 ros::init(argc, argv,
"multiple_subscriptions");
189 return RUN_ALL_TESTS();
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 &)
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 &)
void cb2(const test_roscpp::TestArrayConstPtr &)
void cb0(const test_roscpp::TestArrayConstPtr &)
void callback2(const test_roscpp::TestEmptyConstPtr &)
TEST(Subscriptions2, multipleDifferentMD5Sums)
TEST_F(Subscriptions, multipleSubscriptions)
void cb_reset(const test_roscpp::TestArrayConstPtr &)
ROSCPP_DECL void spinOnce()
void cb_verify(const test_roscpp::TestArrayConstPtr &)