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 #include <bondcpp/bond.h>
00032 #include <gtest/gtest.h>
00033 #include <uuid/uuid.h>
00034 #include <ros/spinner.h>
00035
00036 #include <test_bond/TestBond.h>
00037
00038 const std::string TOPIC = "test_bond_topic";
00039
00040 std::string genId()
00041 {
00042 uuid_t uuid;
00043 uuid_generate_random(uuid);
00044 char uuid_str[40];
00045 uuid_unparse(uuid, uuid_str);
00046 return std::string(uuid_str);
00047 }
00048
00049 ros::ServiceClient getService()
00050 {
00051 ros::NodeHandle nh;
00052 ros::ServiceClient cli = nh.serviceClient<test_bond::TestBond>("test_bond");
00053 EXPECT_TRUE(cli);
00054 EXPECT_TRUE(cli.waitForExistence(ros::Duration(5.0)));
00055 return cli;
00056 }
00057
00058 TEST(ExerciseBondCpp, normal)
00059 {
00060 std::string id = genId();
00061 bond::Bond bond(TOPIC, id);
00062 ros::ServiceClient cli = getService();
00063 EXPECT_TRUE(cli.isValid());
00064 EXPECT_TRUE(cli.exists());
00065 test_bond::TestBond::Request req;
00066 test_bond::TestBond::Response resp;
00067 req.topic = TOPIC;
00068 req.id = id;
00069 req.delay_death = ros::Duration(2.0);
00070 ASSERT_TRUE(cli.call(req, resp));
00071 bond.start();
00072
00073 EXPECT_TRUE(bond.waitUntilFormed(ros::Duration(2.0)));
00074 EXPECT_TRUE(bond.waitUntilBroken(ros::Duration(5.0)));
00075 }
00076
00077 TEST(ExerciseBondCpp, remoteNeverConnects)
00078 {
00079 std::string id = genId();
00080
00081 bond::Bond bond(TOPIC, id);
00082 bond.start();
00083 EXPECT_FALSE(bond.waitUntilFormed(ros::Duration(1.0)));
00084 EXPECT_TRUE(bond.waitUntilBroken(ros::Duration(20.0)));
00085 }
00086
00087 TEST(ExerciseBondCpp, heartbeatTimeout)
00088 {
00089 std::string id = genId();
00090 bond::Bond bond(TOPIC, id);
00091
00092 ros::ServiceClient cli = getService();
00093 test_bond::TestBond::Request req;
00094 test_bond::TestBond::Response resp;
00095 req.topic = TOPIC;
00096 req.id = id;
00097 req.delay_death = ros::Duration(2.0);
00098 req.inhibit_death_message = true;
00099 ASSERT_TRUE(cli.call(req, resp));
00100
00101 bond.start();
00102
00103 EXPECT_TRUE(bond.waitUntilFormed(ros::Duration(2.0)));
00104 EXPECT_TRUE(bond.waitUntilBroken(ros::Duration(10.0)));
00105 }
00106
00107 TEST(ExerciseBondCpp, cleanLocalDeath)
00108 {
00109 std::string id = genId();
00110 bond::Bond bond(TOPIC, id);
00111
00112 ros::ServiceClient cli = getService();
00113 test_bond::TestBond::Request req;
00114 test_bond::TestBond::Response resp;
00115 req.topic = TOPIC;
00116 req.id = id;
00117 req.delay_death = ros::Duration(-1);
00118 ASSERT_TRUE(cli.call(req, resp));
00119
00120 bond.start();
00121
00122 EXPECT_TRUE(bond.waitUntilFormed(ros::Duration(2.0)));
00123 bond.breakBond();
00124 EXPECT_TRUE(bond.waitUntilBroken(ros::Duration(5.0)));
00125 }
00126
00127 TEST(ExerciseBondCpp, localDeathNoAck)
00128 {
00129 std::string id = genId();
00130 bond::Bond bond(TOPIC, id);
00131
00132 ros::ServiceClient cli = getService();
00133 test_bond::TestBond::Request req;
00134 test_bond::TestBond::Response resp;
00135 req.topic = TOPIC;
00136 req.id = id;
00137 req.delay_death = ros::Duration(-1);
00138 req.inhibit_death_message = true;
00139 ASSERT_TRUE(cli.call(req, resp));
00140
00141 bond.start();
00142
00143 EXPECT_TRUE(bond.waitUntilFormed(ros::Duration(2.0)));
00144 bond.breakBond();
00145 EXPECT_TRUE(bond.waitUntilBroken(ros::Duration(5.0)));
00146 }
00147
00148 TEST(ExerciseBondCpp, remoteIgnoresLocalDeath)
00149 {
00150 std::string id = genId();
00151 bond::Bond bond(TOPIC, id);
00152
00153 ros::ServiceClient cli = getService();
00154 test_bond::TestBond::Request req;
00155 test_bond::TestBond::Response resp;
00156 req.topic = TOPIC;
00157 req.id = id;
00158 req.delay_death = ros::Duration(-1);
00159 req.inhibit_death = true;
00160 ASSERT_TRUE(cli.call(req, resp));
00161
00162 bond.start();
00163
00164 EXPECT_TRUE(bond.waitUntilFormed(ros::Duration(2.0)));
00165 bond.breakBond();
00166 EXPECT_FALSE(bond.waitUntilBroken(ros::Duration(1.0)));
00167 EXPECT_TRUE(bond.waitUntilBroken(ros::Duration(10.0)));
00168 }
00169
00170 int main(int argc, char ** argv)
00171 {
00172 testing::InitGoogleTest(&argc, argv);
00173 ros::init(argc, argv, "exercise_bondcpp", true);
00174 ros::AsyncSpinner spinner(1);
00175 spinner.start();
00176 ros::NodeHandle nh;
00177 int ret = RUN_ALL_TESTS();
00178 spinner.stop();
00179 return ret;
00180 };