multiple_subscriptions.cpp
Go to the documentation of this file.
00001 /*
00002  * Copyright (C) 2008, Morgan Quigley and Willow Garage, Inc.
00003  * 
00004  * Redistribution and use in source and binary forms, with or without
00005  * modification, are permitted provided that the following conditions are met:
00006  *   * Redistributions of source code must retain the above copyright notice,
00007  *     this list of conditions and the following disclaimer.
00008  *   * Redistributions in binary form must reproduce the above copyright
00009  *     notice, this list of conditions and the following disclaimer in the
00010  *     documentation and/or other materials provided with the distribution.
00011  *   * Neither the names of Stanford University or Willow Garage, Inc. nor the names of its
00012  *     contributors may be used to endorse or promote products derived from
00013  *     this software without specific prior written permission.
00014  *
00015  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
00016  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
00017  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
00018  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
00019  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
00020  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
00021  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
00022  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
00023  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
00024  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00025  * POSSIBILITY OF SUCH DAMAGE.
00026  */
00027 
00028 /* Author: Morgan Quigley */
00029 
00030 /*
00031  * Subscribe to a topic multiple times
00032  */
00033 
00034 #include <string>
00035 #include <gtest/gtest.h>
00036 #include <time.h>
00037 #include <stdlib.h>
00038 #include "ros/ros.h"
00039 #include <test_roscpp/TestArray.h>
00040 #include <test_roscpp/TestEmpty.h>
00041 
00042 int g_argc;
00043 char** g_argv;
00044 
00045 class Subscriptions : public testing::Test
00046 {
00047   public:
00048     ros::NodeHandle nh_;
00049     bool got_it[4], should_have_it[4];
00050     ros::Subscriber subs_[4];
00051     ros::Subscriber verify_sub_;
00052     ros::Subscriber reset_sub_;
00053     bool test_ready;
00054     int n_test;
00055 
00056     void cb0(const test_roscpp::TestArrayConstPtr&) { if (!test_ready) return; got_it[0] = true; }
00057     void cb1(const test_roscpp::TestArrayConstPtr&) { if (!test_ready) return; got_it[1] = true; }
00058     void cb2(const test_roscpp::TestArrayConstPtr&) { if (!test_ready) return; got_it[2] = true; }
00059     void cb3(const test_roscpp::TestArrayConstPtr&) { if (!test_ready) return; got_it[3] = true; }
00060     void cb_verify(const test_roscpp::TestArrayConstPtr&)
00061     {
00062       if (!test_ready)
00063         return;
00064       n_test++;
00065       /*
00066       ASSERT_TRUE(((should_have_it[0] ? got_it[0] : true) &&
00067                    (should_have_it[1] ? got_it[1] : true) &&
00068                    (should_have_it[2] ? got_it[2] : true) &&
00069                    (should_have_it[3] ? got_it[3] : true)));
00070       */
00071     }
00072     void cb_reset(const test_roscpp::TestArrayConstPtr&)
00073     {
00074       got_it[0] = got_it[1] = got_it[2] = got_it[3] = false; test_ready = true;
00075     }
00076 
00077   protected:
00078     bool sub(int cb_num)
00079     { 
00080       ROS_INFO("Subscribing %d", cb_num);
00081       boost::function<void(const test_roscpp::TestArrayConstPtr&)> funcs[4] =
00082       {
00083         boost::bind(&Subscriptions::cb0, this, _1),
00084         boost::bind(&Subscriptions::cb1, this, _1),
00085         boost::bind(&Subscriptions::cb2, this, _1),
00086         boost::bind(&Subscriptions::cb3, this, _1),
00087       };
00088 
00089       subs_[cb_num] = nh_.subscribe("roscpp/pubsub_test", 10, funcs[cb_num]);
00090 
00091       return subs_[cb_num];
00092     }
00093     bool sub_wrappers()
00094     {
00095       ROS_INFO("sub_wrappers");
00096       verify_sub_ = nh_.subscribe("roscpp/pubsub_test", 10, &Subscriptions::cb_verify, this);
00097       reset_sub_ = nh_.subscribe("roscpp/pubsub_test", 10, &Subscriptions::cb_reset, this);
00098       return verify_sub_ && reset_sub_;
00099     }
00100     bool unsub(int cb_num)
00101     {
00102       ROS_INFO("unsubscribing %d", cb_num);
00103       subs_[cb_num].shutdown();
00104 
00105       return true;
00106     }
00107     bool unsub_wrappers()
00108     {
00109       ROS_INFO("unsub wrappers");
00110       verify_sub_.shutdown();
00111       reset_sub_.shutdown();
00112       return true;
00113     }
00114 };
00115 
00116 TEST_F(Subscriptions, multipleSubscriptions)
00117 {
00118   test_ready = false;
00119 
00120   for (int i = 0; i < 0x10; i++)
00121   {
00122     for (int j = 0; j < 4; j++)
00123       should_have_it[j] = (i & (1 << j) ? true : false);
00124 
00125     ROS_INFO(" testing: %d, %d, %d, %d\n",
00126            should_have_it[0],
00127            should_have_it[1],
00128            should_have_it[2],
00129            should_have_it[3]);
00130 
00131     for (int j = 0; j < 4; j++)
00132       if (should_have_it[j])
00133         ASSERT_TRUE(sub(j));
00134     ASSERT_TRUE(sub_wrappers());
00135 
00136     ros::Time t_start = ros::Time::now();
00137     n_test = 0;
00138     while (n_test < 10 && ros::Time::now() - t_start < ros::Duration(5000.0))
00139     {
00140       static int count = 0;
00141       if (count++ % 10 == 0)
00142         ROS_INFO("%d/100 tests completed...\n", n_test);
00143 
00144       ros::spinOnce();
00145       ros::Duration(0.01).sleep();
00146     }
00147     
00148     for (int j = 0; j < 4; j++)
00149       if (should_have_it[j])
00150         ASSERT_TRUE(unsub(j));
00151     ASSERT_TRUE(unsub_wrappers());
00152   }
00153   SUCCEED();
00154 }
00155 
00156 void callback1(const test_roscpp::TestArrayConstPtr&)
00157 {
00158 
00159 }
00160 
00161 void callback2(const test_roscpp::TestEmptyConstPtr&)
00162 {
00163 
00164 }
00165 
00166 TEST(Subscriptions2, multipleDifferentMD5Sums)
00167 {
00168   ros::NodeHandle nh;
00169   ros::Subscriber sub1 = nh.subscribe("test", 0, callback1);
00170 
00171   try
00172   {
00173     ros::Subscriber sub2 = nh.subscribe("test", 0, callback2);
00174     FAIL();
00175   }
00176   catch (ros::ConflictingSubscriptionException&)
00177   {
00178     SUCCEED();
00179   }
00180 }
00181 
00182 int main(int argc, char** argv)
00183 {
00184   testing::InitGoogleTest(&argc, argv);
00185   ros::init(argc, argv, "multiple_subscriptions");
00186   ros::NodeHandle nh;
00187   g_argc = argc;
00188   g_argv = argv;
00189   return RUN_ALL_TESTS();
00190 }
00191 


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