Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032 #include <gtest/gtest.h>
00033 #include <ros/ros.h>
00034 #include <ros/callback_queue.h>
00035
00036 #include "test_roscpp/TestArray.h"
00037
00038 uint32_t g_pub_count = 0;
00039
00040 void callback(const test_roscpp::TestArrayConstPtr&)
00041 {
00042 }
00043
00044 TEST(LoadsOfPublishers, waitForAll)
00045 {
00046 ros::NodeHandle nh;
00047 ros::Subscriber sub = nh.subscribe("roscpp/pubsub_test", 1000, callback);
00048
00049 while (sub.getNumPublishers() < g_pub_count)
00050 {
00051 ros::getGlobalCallbackQueue()->callAvailable(ros::WallDuration(0.1));
00052 }
00053
00054 ros::WallDuration(10).sleep();
00055 ros::spinOnce();
00056 ASSERT_EQ(sub.getNumPublishers(), g_pub_count);
00057 }
00058
00059 struct Helper
00060 {
00061 void callback(const ros::MessageEvent<test_roscpp::TestArray>& msg_event)
00062 {
00063 alive[msg_event.getPublisherName()] = true;
00064 }
00065
00066 std::map<std::string, bool> alive;
00067 };
00068
00069 TEST(LoadsOfPublishers, receiveFromAll)
00070 {
00071 ros::NodeHandle nh;
00072 Helper helper;
00073 ros::Subscriber sub = nh.subscribe("roscpp/pubsub_test", 1000, &Helper::callback, &helper);
00074
00075 while (helper.alive.size() < g_pub_count)
00076 {
00077 ros::getGlobalCallbackQueue()->callAvailable(ros::WallDuration(0.1));
00078 }
00079 }
00080
00081 int main(int argc, char** argv)
00082 {
00083 testing::InitGoogleTest(&argc, argv);
00084 ros::init(argc, argv, "loads_of_publishers");
00085
00086 if (argc < 2)
00087 {
00088 ROS_ERROR("Not enough arguments (usage: loads_of_publishers num_publishers)");
00089 return 1;
00090 }
00091
00092 g_pub_count = atoi(argv[1]);
00093
00094 ros::NodeHandle nh;
00095
00096 return RUN_ALL_TESTS();
00097 }