1 #include <gtest/gtest.h> 3 #include <ros1_template_msgs/Answer.h> 4 #include <std_msgs/Int32.h> 17 std::string service_name =
"fibonacci_service";
18 std::string full_service_name = node_handle.
resolveName(service_name);
20 EXPECT_TRUE(service_is_up);
22 bool persistent_service =
true;
24 service_name, persistent_service);
26 EXPECT_TRUE(service_client.
isValid());
28 ros1_template_msgs::Answer service;
29 bool call_successful = service_client.
call(service);
30 EXPECT_TRUE(call_successful);
33 int main(
int argc,
char **argv)
35 testing::InitGoogleTest(&argc, argv);
36 int time_seed =
static_cast<int>(time(0));
41 return RUN_ALL_TESTS();
ServiceClient serviceClient(const std::string &service_name, bool persistent=false, const M_string &header_values=M_string())
int main(int argc, char **argv)
std::string resolveName(const std::string &name, bool remap=true) const
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
bool call(MReq &req, MRes &res)
ROSCPP_DECL bool waitForService(const std::string &service_name, int32_t timeout)