35 #include <gtest/gtest.h>
41 #include <std_msgs/UInt32.h>
43 #include <boost/thread.hpp>
45 using namespace rosrt;
65 boost::thread t(boost::bind(
publishThread, boost::ref(pub), boost::ref(done)));
75 std_msgs::UInt32ConstPtr msg = sub.
poll();
78 ASSERT_GT((int32_t)msg->data, last);
95 boost::thread t(boost::bind(
publishThread, boost::ref(pub), boost::ref(done)));
97 const size_t sub_count = 10;
99 uint32_t counts[sub_count];
100 int32_t lasts[sub_count];
101 for (
size_t i = 0; i < sub_count; ++i)
111 bool all_done =
false;
116 for (
size_t i = 0; i < sub_count; ++i)
118 std_msgs::UInt32ConstPtr msg = subs[i].
poll();
121 ASSERT_GT((int32_t)msg->data, lasts[i]);
122 lasts[i] = msg->data;
126 if (counts[i] < 10000)
141 const size_t sub_count = 10;
145 boost::thread_group tg;
149 uint32_t counts[sub_count];
150 int32_t lasts[sub_count];
151 for (
size_t i = 0; i < sub_count; ++i)
153 std::stringstream topic;
154 topic <<
"test" << i;
155 pubs[i] = nh.
advertise<std_msgs::UInt32>(topic.str(), 1);
156 tg.create_thread(boost::bind(
publishThread, boost::ref(pubs[i]), boost::ref(done)));
165 bool all_done =
false;
170 for (
size_t i = 0; i < sub_count; ++i)
172 std_msgs::UInt32ConstPtr msg = subs[i].
poll();
175 ASSERT_GT((int32_t)msg->data, lasts[i]);
176 lasts[i] = msg->data;
180 if (counts[i] < 10000)
195 const int count = 10000;
200 std_msgs::UInt32ConstPtr msg = sub.
poll();
203 if (last >= (int32_t)msg->data)
205 ROS_ERROR_STREAM(
"Thread " << boost::this_thread::get_id() <<
" last is greater than msg " << last <<
" >= " << msg->data);
216 if (my_count >= count)
236 boost::thread t(boost::bind(
publishThread, boost::ref(pub), boost::ref(done)));
237 boost::thread_group tg;
239 const size_t sub_count = 10;
241 bool failed[sub_count];
242 for (
size_t i = 0; i < sub_count; ++i)
248 tg.create_thread(boost::bind(
subscribeThread, boost::ref(subs[i]), boost::ref(failed[i])));
255 for (
size_t i = 0; i < sub_count; ++i)
257 EXPECT_FALSE(failed[i]);
261 int main(
int argc,
char** argv)
263 ros::init(argc, argv,
"test_rt_subscriber");
264 testing::InitGoogleTest(&argc, argv);
269 return RUN_ALL_TESTS();