Go to the documentation of this file.
2 #include <gtest/gtest.h>
5 #include "std_srvs/Empty.h"
9 bool dummyService(std_srvs::Empty::Request &, std_srvs::Empty::Request &)
29 ROS_INFO(
"Persistent client is invalid");
41 unsigned seconds = 30;
62 ROS_INFO(
"Made it through %u loops in %u seconds", j, seconds);
66 int main(
int argc,
char **argv)
68 testing::InitGoogleTest(&argc, argv);
69 ros::init(argc, argv,
"service_deadlock");
70 return RUN_ALL_TESTS();
ROSCPP_DECL void init(const M_string &remappings, const std::string &name, uint32_t options=0)
ServiceClient serviceClient(const std::string &service_name, bool persistent=false, const M_string &header_values=M_string())
static const char SERVICE1[]
ServiceServer advertiseService(AdvertiseServiceOptions &ops)
bool dummyService(std_srvs::Empty::Request &, std_srvs::Empty::Request &)
int main(int argc, char **argv)
TEST(roscpp, ServiceDeadlocking)
bool call(const MReq &req, MRes &resp, const std::string &service_md5sum)
void call(ros::ServiceClient &client)
test_roscpp
Author(s): Morgan Quigley, Josh Faust, Brian Gerkey, Troy Straszheim, Dirk Thomas
, Jacob Perron
autogenerated on Sat Sep 14 2024 02:59:57