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
00033
00034
00035
00036 #include <string>
00037
00038 #include <gtest/gtest.h>
00039
00040 #include <stdlib.h>
00041
00042 #include "ros/ros.h"
00043 #include <test_roscpp/TestArray.h>
00044
00045 int g_msg_count;
00046 ros::Duration g_dt;
00047 uint32_t g_options = 0;
00048 bool g_success = false;
00049 bool g_failure = false;
00050 int32_t g_msg_i = -1;
00051
00052 void subscriberCallback(const ros::SingleSubscriberPublisher&, const ros::Publisher& pub)
00053 {
00054 test_roscpp::TestArray outmsg;
00055 for(int i=0;i<g_msg_count;i++)
00056 {
00057 outmsg.counter = i;
00058 pub.publish(outmsg);
00059 ROS_INFO("published %d", i);
00060 }
00061 }
00062
00063 void messageCallback(const test_roscpp::TestArrayConstPtr& msg)
00064 {
00065 ROS_INFO("received message %d", msg->counter);
00066 if(g_failure || g_success)
00067 return;
00068
00069 g_msg_i++;
00070 if(g_msg_i != msg->counter)
00071 {
00072 g_failure = true;
00073 ROS_INFO("failed");
00074 }
00075 else if(g_msg_i == (g_msg_count-1))
00076 {
00077 g_success = true;
00078 ROS_INFO("success");
00079 }
00080 }
00081
00082 TEST(SelfSubscribe, advSub)
00083 {
00084 ros::NodeHandle nh;
00085 ros::Duration d;
00086 d.fromNSec(10000000);
00087
00088 g_success = false;
00089 g_failure = false;
00090 g_msg_i = -1;
00091
00092 {
00093 ros::Publisher pub;
00094 pub = nh.advertise<test_roscpp::TestArray>("test_roscpp/pubsub_test", g_msg_count, boost::bind(subscriberCallback, _1, boost::ref(pub)));
00095 ASSERT_TRUE(pub);
00096 ros::Subscriber sub = nh.subscribe("test_roscpp/pubsub_test", g_msg_count, messageCallback);
00097 ASSERT_TRUE(sub);
00098 ros::Time t1(ros::Time::now()+g_dt);
00099 while(ros::Time::now() < t1 && !g_success && !g_failure)
00100 {
00101 d.sleep();
00102 ros::spinOnce();
00103 }
00104 }
00105
00106 ASSERT_TRUE(g_success);
00107 ASSERT_FALSE(g_failure);
00108
00109
00110 g_success = false;
00111 g_failure = false;
00112 g_msg_i = -1;
00113
00114 {
00115 ros::Subscriber sub = nh.subscribe("test_roscpp/pubsub_test", g_msg_count, messageCallback);
00116 ASSERT_TRUE(sub);
00117 ros::Publisher pub;
00118 pub = nh.advertise<test_roscpp::TestArray>("test_roscpp/pubsub_test", g_msg_count, boost::bind(subscriberCallback, _1, boost::ref(pub)));
00119 ASSERT_TRUE(pub);
00120
00121 ros::Time t1(ros::Time::now()+g_dt);
00122 while(ros::Time::now() < t1 && !g_success && !g_failure)
00123 {
00124 d.sleep();
00125 ros::spinOnce();
00126 }
00127 }
00128
00129
00130 ASSERT_TRUE(g_success);
00131 ASSERT_FALSE(g_failure);
00132 }
00133
00134 #define USAGE "USAGE: sub_pub <count> <time>"
00135
00136 int
00137 main(int argc, char** argv)
00138 {
00139 testing::InitGoogleTest(&argc, argv);
00140 ros::init(argc, argv, "subscribe_self");
00141
00142 if(argc != 3)
00143 {
00144 puts(USAGE);
00145 return -1;
00146 }
00147
00148 g_msg_count = atoi(argv[1]);
00149 g_dt.fromSec(atof(argv[2]));
00150
00151 ros::NodeHandle nh;
00152
00153 return RUN_ALL_TESTS();
00154 }