32 #include <gtest/gtest.h> 35 # include <uuid/uuid.h> 42 #include <test_bond/TestBond.h> 46 const char TOPIC[] =
"test_bond_topic";
52 uuid_generate_random(uuid);
54 uuid_unparse(uuid, uuid_str);
55 return std::string(uuid_str);
60 UuidToStringA(&uuid, &str);
61 std::string return_string(reinterpret_cast<char *>(str));
76 TEST(ExerciseBondCpp, normal)
78 std::string
id =
genId();
83 test_bond::TestBond::Request req;
84 test_bond::TestBond::Response resp;
88 ASSERT_TRUE(cli.
call(req, resp));
95 TEST(ExerciseBondCpp, remoteNeverConnects)
97 std::string
id =
genId();
105 TEST(ExerciseBondCpp, heartbeatTimeout)
107 std::string
id =
genId();
111 test_bond::TestBond::Request req;
112 test_bond::TestBond::Response resp;
116 req.inhibit_death_message =
true;
117 ASSERT_TRUE(cli.
call(req, resp));
125 TEST(ExerciseBondCpp, cleanLocalDeath)
127 std::string
id =
genId();
131 test_bond::TestBond::Request req;
132 test_bond::TestBond::Response resp;
136 ASSERT_TRUE(cli.
call(req, resp));
145 TEST(ExerciseBondCpp, localDeathNoAck)
147 std::string
id =
genId();
151 test_bond::TestBond::Request req;
152 test_bond::TestBond::Response resp;
156 req.inhibit_death_message =
true;
157 ASSERT_TRUE(cli.
call(req, resp));
166 TEST(ExerciseBondCpp, remoteIgnoresLocalDeath)
168 std::string
id =
genId();
172 test_bond::TestBond::Request req;
173 test_bond::TestBond::Response resp;
177 req.inhibit_death =
true;
178 ASSERT_TRUE(cli.
call(req, resp));
188 int main(
int argc,
char ** argv)
190 testing::InitGoogleTest(&argc, argv);
191 ros::init(argc, argv,
"exercise_bondcpp",
true);
195 int ret = RUN_ALL_TESTS();
ServiceClient serviceClient(const std::string &service_name, bool persistent=false, const M_string &header_values=M_string())
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
bool call(MReq &req, MRes &res)
bool waitUntilBroken(ros::Duration timeout=ros::Duration(-1))
bool waitUntilFormed(ros::Duration timeout=ros::Duration(-1))
TEST(ExerciseBondCpp, normal)
bool waitForExistence(ros::Duration timeout=ros::Duration(-1))
int main(int argc, char **argv)
ros::ServiceClient getService()