subscribe_star.cpp
Go to the documentation of this file.
00001 /*
00002  * Copyright (c) 2010, 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 /*
00031  * Author: Josh Faust
00032  */
00033 
00034 #include <gtest/gtest.h>
00035 
00036 #include <ros/ros.h>
00037 #include <ros/connection_manager.h>
00038 
00039 #include "test_roscpp/TestEmpty.h"
00040 #include "test_roscpp/TestArray.h"
00041 
00042 #include <std_srvs/Empty.h>
00043 
00044 class AnyMessage
00045 {
00046 };
00047 typedef boost::shared_ptr<AnyMessage> AnyMessagePtr;
00048 typedef boost::shared_ptr<AnyMessage const> AnyMessageConstPtr;
00049 
00050 namespace ros
00051 {
00052 namespace message_traits
00053 {
00054 
00055 template<>
00056 struct MD5Sum<AnyMessage>
00057 {
00058   static const char* value() { return "*"; }
00059   static const char* value(const AnyMessage&) { return "*"; }
00060 };
00061 
00062 template<>
00063 struct DataType<AnyMessage>
00064 {
00065   static const char* value() { return "*"; }
00066   static const char* value(const AnyMessage&) { return "*"; }
00067 };
00068 
00069 template<>
00070 struct Definition<AnyMessage>
00071 {
00072 };
00073 
00074 }
00075 
00076 namespace serialization
00077 {
00078 template<>
00079 struct Serializer<AnyMessage>
00080 {
00081   template<typename Stream, typename T>
00082   static void allInOne(Stream s, T t)
00083   {
00084   }
00085 
00086   ROS_DECLARE_ALLINONE_SERIALIZER;
00087 };
00088 }
00089 }
00090 
00091 struct AnyHelper
00092 {
00093   AnyHelper()
00094   : count(0)
00095   {
00096   }
00097 
00098   void cb(const AnyMessageConstPtr& msg)
00099   {
00100     ++count;
00101   }
00102 
00103   uint32_t count;
00104 };
00105 
00106 
00107 TEST(SubscribeStar, simpleSubFirstIntra)
00108 {
00109   ros::NodeHandle nh;
00110   AnyHelper h;
00111   ros::Subscriber sub = nh.subscribe("test_star_intra", 0, &AnyHelper::cb, &h);
00112   ros::Publisher pub = nh.advertise<test_roscpp::TestEmpty>("test_star_intra", 0);
00113 
00114   EXPECT_EQ(pub.getNumSubscribers(), 1U);
00115   EXPECT_EQ(sub.getNumPublishers(), 1U);
00116 
00117   AnyMessagePtr msg(new AnyMessage);
00118   pub.publish(msg);
00119   ros::spinOnce();
00120   EXPECT_EQ(h.count, 1U);
00121 }
00122 
00123 TEST(SubscribeStar, simplePubFirstIntra)
00124 {
00125   ros::NodeHandle nh;
00126   AnyHelper h;
00127   ros::Publisher pub = nh.advertise<test_roscpp::TestEmpty>("test_star_intra", 0);
00128   ros::Subscriber sub = nh.subscribe("test_star_intra", 0, &AnyHelper::cb, &h);
00129 
00130   EXPECT_EQ(pub.getNumSubscribers(), 1U);
00131   EXPECT_EQ(sub.getNumPublishers(), 1U);
00132 
00133   AnyMessagePtr msg(new AnyMessage);
00134   pub.publish(msg);
00135   ros::spinOnce();
00136   EXPECT_EQ(h.count, 1U);
00137 }
00138 
00139 void emptyCallback(const test_roscpp::TestEmptyConstPtr&)
00140 {
00141 
00142 }
00143 
00144 TEST(SubscribeStar, multipleSubsStarFirstIntra)
00145 {
00146   ros::NodeHandle nh;
00147   AnyHelper h;
00148   ros::Subscriber sub = nh.subscribe("test_star_intra", 0, &AnyHelper::cb, &h);
00149   ros::Subscriber sub2 = nh.subscribe("test_star_intra", 0, emptyCallback);
00150 
00151   ros::Publisher pub = nh.advertise<test_roscpp::TestEmpty>("test_star_intra", 0);
00152   EXPECT_EQ(pub.getNumSubscribers(), 1U);
00153   EXPECT_EQ(sub.getNumPublishers(), 1U);
00154   EXPECT_EQ(sub2.getNumPublishers(), 1U);
00155 
00156   pub.shutdown();
00157   pub = nh.advertise<test_roscpp::TestArray>("test_star_intra", 0);
00158   EXPECT_EQ(pub.getNumSubscribers(), 0U);
00159   EXPECT_EQ(sub.getNumPublishers(), 0U);
00160   EXPECT_EQ(sub2.getNumPublishers(), 0U);
00161 }
00162 
00163 TEST(SubscribeStar, multipleSubsConcreteFirstIntra)
00164 {
00165   ros::NodeHandle nh;
00166   AnyHelper h;
00167   ros::Subscriber sub2 = nh.subscribe("test_star_intra", 0, emptyCallback);
00168   ros::Subscriber sub = nh.subscribe("test_star_intra", 0, &AnyHelper::cb, &h);
00169 
00170   ros::Publisher pub = nh.advertise<test_roscpp::TestEmpty>("test_star_intra", 0);
00171   EXPECT_EQ(pub.getNumSubscribers(), 1U);
00172   EXPECT_EQ(sub.getNumPublishers(), 1U);
00173   EXPECT_EQ(sub2.getNumPublishers(), 1U);
00174 
00175   pub.shutdown();
00176   pub = nh.advertise<test_roscpp::TestArray>("test_star_intra", 0);
00177   EXPECT_EQ(pub.getNumSubscribers(), 0U);
00178   EXPECT_EQ(sub.getNumPublishers(), 0U);
00179   EXPECT_EQ(sub2.getNumPublishers(), 0U);
00180 }
00181 
00182 TEST(SubscribeStar, multipleShutdownConcreteIntra)
00183 {
00184   ros::NodeHandle nh;
00185   AnyHelper h;
00186   ros::Subscriber sub = nh.subscribe("test_star_intra", 0, &AnyHelper::cb, &h);
00187   ros::Subscriber sub2 = nh.subscribe("test_star_intra", 0, emptyCallback);
00188   sub2.shutdown();
00189 
00190   ros::Publisher pub = nh.advertise<test_roscpp::TestEmpty>("test_star_intra", 0);
00191   EXPECT_EQ(pub.getNumSubscribers(), 1U);
00192   EXPECT_EQ(sub.getNumPublishers(), 1U);
00193 
00194   pub.shutdown();
00195   pub = nh.advertise<test_roscpp::TestArray>("test_star_intra", 0);
00196   EXPECT_EQ(pub.getNumSubscribers(), 0U);
00197   EXPECT_EQ(sub.getNumPublishers(), 0U);
00198 }
00199 
00200 TEST(SubscribeStar, simpleInter)
00201 {
00202   ros::NodeHandle nh;
00203   AnyHelper h;
00204   ros::Subscriber sub = nh.subscribe("test_star_inter", 0, &AnyHelper::cb, &h);
00205 
00206   ros::WallDuration(1.0).sleep();
00207   ros::spinOnce();
00208 
00209   EXPECT_EQ(sub.getNumPublishers(), 1U);
00210   EXPECT_GT(h.count, 0U);
00211 }
00212 
00213 TEST(SubscribeStar, simpleInterUDP)
00214 {
00215   ros::NodeHandle nh;
00216   AnyHelper h;
00217   ros::Subscriber sub = nh.subscribe("test_star_inter", 0, &AnyHelper::cb, &h, ros::TransportHints().udp());
00218 
00219   ros::WallDuration(1.0).sleep();
00220   ros::spinOnce();
00221 
00222   EXPECT_EQ(sub.getNumPublishers(), 1U);
00223   EXPECT_GT(h.count, 0U);
00224 }
00225 
00226 // must be the last test as it makes the service node exit
00227 TEST(SubscribeStar, switchTypeInter)
00228 {
00229   ros::NodeHandle nh;
00230   AnyHelper h;
00231   ros::Subscriber sub = nh.subscribe("test_star_inter", 0, &AnyHelper::cb, &h);
00232   ros::Subscriber sub2 = nh.subscribe("test_star_inter", 0, emptyCallback);
00233 
00234   ros::WallDuration(1.0).sleep();
00235   ros::spinOnce();
00236 
00237   ASSERT_EQ(sub.getNumPublishers(), 1U);
00238   ASSERT_EQ(sub2.getNumPublishers(), 1U);
00239 
00240   std_srvs::Empty srv;
00241   // by invoking the service call the service node will exit with FATAL
00242   ASSERT_TRUE(ros::service::call("switch_publisher_type", srv));
00243 
00244   ros::WallDuration(1.0).sleep();
00245   ros::spinOnce();
00246 
00247   ASSERT_EQ(sub.getNumPublishers(), 0U);
00248   ASSERT_EQ(sub2.getNumPublishers(), 0U);
00249 }
00250 
00251 // disabled because switchTypeInter will stop the other node intentionally
00252 //TEST(SubscribeStar, switchTypeInterUDP)
00253 //{
00254 //  ros::NodeHandle nh;
00255 //  AnyHelper h;
00256 //  ros::Subscriber sub = nh.subscribe("test_star_inter", 0, &AnyHelper::cb, &h, ros::TransportHints().udp());
00257 //  ros::Subscriber sub2 = nh.subscribe("test_star_inter", 0, emptyCallback, ros::TransportHints().udp());
00258 //
00259 //  ros::WallDuration(1.0).sleep();
00260 //  ros::spinOnce();
00261 //
00262 //  ASSERT_EQ(sub.getNumPublishers(), 1U);
00263 //  ASSERT_EQ(sub2.getNumPublishers(), 1U);
00264 //
00265 //  std_srvs::Empty srv;
00266 //  // by invoking the service call the service node will exit with FATAL
00267 //  ASSERT_TRUE(ros::service::call("switch_publisher_type", srv));
00268 //
00269 //  ros::WallDuration(1.0).sleep();
00270 //  ros::spinOnce();
00271 //
00272 //  ASSERT_EQ(sub.getNumPublishers(), 0U);
00273 //  ASSERT_EQ(sub2.getNumPublishers(), 0U);
00274 //}
00275 
00276 int main(int argc, char** argv)
00277 {
00278   testing::InitGoogleTest(&argc, argv);
00279   ros::init(argc, argv, "subscribe_star");
00280   ros::NodeHandle nh;
00281   return RUN_ALL_TESTS();
00282 }


test_roscpp
Author(s): Morgan Quigley, Josh Faust, Brian Gerkey, Troy Straszheim
autogenerated on Fri Aug 28 2015 12:33:59