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 #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("test_roscpp/pubsub_test", 0, callback);
00053
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
00066 ros::spinOnce();
00067
00068 g_count = 0;
00069
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("test_roscpp/pubsub_test", 0, callback);
00085
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
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
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("test_roscpp/pubsub_test", 0, callback);
00122
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
00137 ros::spinOnce();
00138
00139 g_count = 0;
00140
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 }