subscribe_retry_tcp.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/TestArray.h"
00040 #include "roscpp/Empty.h"
00041 
00042 int32_t g_count = 0;
00043 void callback(const test_roscpp::TestArrayConstPtr& msg)
00044 {
00045   ++g_count;
00046 }
00047 
00048 TEST(SubscribeRetryTCP, localDisconnect)
00049 {
00050   g_count = 0;
00051   ros::NodeHandle nh;
00052   ros::Subscriber sub = nh.subscribe("roscpp/pubsub_test", 0, callback);
00053   // wait for initial messages to arrive
00054   ros::WallTime start = ros::WallTime::now();
00055   while (g_count == 0 && ros::WallTime::now() - start < ros::WallDuration(5.0))
00056   {
00057     ros::WallDuration(0.01).sleep();
00058     ros::spinOnce();
00059   }
00060 
00061   ASSERT_GT(g_count, 0);
00062 
00063   ros::ConnectionManager::instance()->clear(ros::Connection::TransportDisconnect);
00064 
00065   // spin to make sure all previous messages have arrived
00066   ros::spinOnce();
00067 
00068   g_count = 0;
00069   // wait for reconnect/new messages to arrive
00070   start = ros::WallTime::now();
00071   while (g_count == 0 && ros::WallTime::now() - start < ros::WallDuration(5.0))
00072   {
00073     ros::WallDuration(0.01).sleep();
00074     ros::spinOnce();
00075   }
00076 
00077   ASSERT_GT(g_count, 0);
00078 }
00079 
00080 TEST(SubscribeRetryTCP, localDisconnectNonTransportDisconnect)
00081 {
00082   g_count = 0;
00083   ros::NodeHandle nh;
00084   ros::Subscriber sub = nh.subscribe("roscpp/pubsub_test", 0, callback);
00085   // wait for initial messages to arrive
00086   ros::WallTime start = ros::WallTime::now();
00087   while (g_count == 0 && ros::WallTime::now() - start < ros::WallDuration(5.0))
00088   {
00089     ros::WallDuration(0.01).sleep();
00090     ros::spinOnce();
00091   }
00092 
00093   ASSERT_GT(g_count, 0);
00094 
00095   ros::ConnectionManager::instance()->clear(ros::Connection::HeaderError);
00096 
00097   // spin for a bit to make sure all previous messages have arrived
00098   start = ros::WallTime::now();
00099   while (ros::WallTime::now() - start < ros::WallDuration(1.0))
00100   {
00101     ros::WallDuration(0.01).sleep();
00102     ros::spinOnce();
00103   }
00104 
00105   g_count = 0;
00106   // make sure we did not reconnect
00107   start = ros::WallTime::now();
00108   while (g_count == 0 && ros::WallTime::now() - start < ros::WallDuration(5.0))
00109   {
00110     ros::WallDuration(0.01).sleep();
00111     ros::spinOnce();
00112   }
00113 
00114   ASSERT_EQ(g_count, 0);
00115 }
00116 
00117 TEST(SubscribeRetryTCP, remoteDisconnect)
00118 {
00119   g_count = 0;
00120   ros::NodeHandle nh;
00121   ros::Subscriber sub = nh.subscribe("roscpp/pubsub_test", 0, callback);
00122   // wait for initial messages to arrive
00123   ros::WallTime start = ros::WallTime::now();
00124   while (g_count == 0 && ros::WallTime::now() - start < ros::WallDuration(5.0))
00125   {
00126     ros::WallDuration(0.01).sleep();
00127     ros::spinOnce();
00128   }
00129 
00130   ASSERT_GT(g_count, 0);
00131 
00132   roscpp::Empty::Request req;
00133   roscpp::Empty::Response resp;
00134   ros::service::call("/publish_constantly/debug/close_all_connections", req, resp);
00135 
00136   // spin to make sure all previous messages have arrived
00137   ros::spinOnce();
00138 
00139   g_count = 0;
00140   // wait for reconnect/new messages to arrive
00141   start = ros::WallTime::now();
00142   while (g_count == 0 && ros::WallTime::now() - start < ros::WallDuration(5.0))
00143   {
00144     ros::WallDuration(0.01).sleep();
00145     ros::spinOnce();
00146   }
00147 
00148   ASSERT_GT(g_count, 0);
00149 }
00150 
00151 int main(int argc, char** argv)
00152 {
00153   testing::InitGoogleTest(&argc, argv);
00154   ros::init(argc, argv, "subscribe_retry_tcp");
00155   ros::NodeHandle nh;
00156   return RUN_ALL_TESTS();
00157 }


test_roscpp
Author(s): Morgan Quigley, Josh Faust, Brian Gerkey, Troy Straszheim
autogenerated on Mon Oct 6 2014 11:47:21