$search
00001 /* 00002 * Copyright (c) 2008, Willow Garage, Inc. 00003 * All rights reserved. 00004 * 00005 * Redistribution and use in source and binary forms, with or without 00006 * modification, are permitted provided that the following conditions are met: 00007 * 00008 * * Redistributions of source code must retain the above copyright 00009 * notice, this list of conditions and the following disclaimer. 00010 * * Redistributions in binary form must reproduce the above copyright 00011 * notice, this list of conditions and the following disclaimer in the 00012 * documentation and/or other materials provided with the distribution. 00013 * * Neither the name of Willow Garage, Inc. nor the names of its 00014 * contributors may be used to endorse or promote products derived from 00015 * this software without specific prior written permission. 00016 * 00017 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" 00018 * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE 00019 * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE 00020 * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE 00021 * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR 00022 * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF 00023 * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS 00024 * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN 00025 * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) 00026 * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 00027 * POSSIBILITY OF SUCH DAMAGE. 00028 */ 00029 00030 /* Author: Brian Gerkey */ 00031 00032 /* 00033 * Subscribe to a topic, expecting to get a single message. 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 // Now try the other order 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 }