Skip to content

Commit a9a8271

Browse files
committed
Adding tests
1 parent 4db5594 commit a9a8271

File tree

2 files changed

+42
-8
lines changed

2 files changed

+42
-8
lines changed

clients/roscpp/include/ros/service.h

Lines changed: 9 additions & 8 deletions
Original file line numberDiff line numberDiff line change
@@ -30,6 +30,7 @@
3030

3131
#include <string>
3232
#include "ros/common.h"
33+
#include "ros/duration.h"
3334
#include "ros/message.h"
3435
#include "ros/forwards.h"
3536
#include "ros/node_handle.h"
@@ -62,11 +63,11 @@ namespace service
6263
* @return true on success, false otherwise.
6364
*/
6465
template<class MReq, class MRes>
65-
bool call(const std::string& service_name, MReq& req, MRes& res)
66+
bool call(const std::string& service_name, MReq& req, MRes& res, const ros::Duration& timeout = ros::Duration(-1.0))
6667
{
6768
namespace st = service_traits;
6869
NodeHandle nh;
69-
ServiceClientOptions ops(ros::names::resolve(service_name), st::md5sum(req), false, M_string());
70+
ServiceClientOptions ops(ros::names::resolve(service_name), st::md5sum(req), false, M_string(), timeout);
7071
ServiceClient client = nh.serviceClient(ops);
7172
return client.call(req, res);
7273
}
@@ -82,12 +83,12 @@ bool call(const std::string& service_name, MReq& req, MRes& res)
8283
* @return true on success, false otherwise.
8384
*/
8485
template<class Service>
85-
bool call(const std::string& service_name, Service& service)
86+
bool call(const std::string& service_name, Service& service, const ros::Duration& timeout = ros::Duration(-1.0))
8687
{
8788
namespace st = service_traits;
8889

8990
NodeHandle nh;
90-
ServiceClientOptions ops(ros::names::resolve(service_name), st::md5sum(service), false, M_string());
91+
ServiceClientOptions ops(ros::names::resolve(service_name), st::md5sum(service), false, M_string(), timeout);
9192
ServiceClient client = nh.serviceClient(ops);
9293
return client.call(service.request, service.response);
9394
}
@@ -131,10 +132,10 @@ ROSCPP_DECL bool exists(const std::string& service_name, bool print_failure_reas
131132
* @param header_values Key/value pairs you'd like to send along in the connection handshake
132133
*/
133134
template<class MReq, class MRes>
134-
ServiceClient createClient(const std::string& service_name, bool persistent = false, const M_string& header_values = M_string())
135+
ServiceClient createClient(const std::string& service_name, bool persistent = false, const M_string& header_values = M_string(), const ros::Duration& timeout = ros::Duration(-1.0))
135136
{
136137
NodeHandle nh;
137-
ServiceClient client = nh.template serviceClient<MReq, MRes>(ros::names::resolve(service_name), persistent, header_values);
138+
ServiceClient client = nh.template serviceClient<MReq, MRes>(ros::names::resolve(service_name), persistent, header_values, timeout);
138139
return client;
139140
}
140141

@@ -149,10 +150,10 @@ ServiceClient createClient(const std::string& service_name, bool persistent = fa
149150
* @param header_values Key/value pairs you'd like to send along in the connection handshake
150151
*/
151152
template<class Service>
152-
ServiceClient createClient(const std::string& service_name, bool persistent = false, const M_string& header_values = M_string())
153+
ServiceClient createClient(const std::string& service_name, bool persistent = false, const M_string& header_values = M_string(), const ros::Duration& timeout = ros::Duration(-1.0))
153154
{
154155
NodeHandle nh;
155-
ServiceClient client = nh.template serviceClient<Service>(ros::names::resolve(service_name), persistent, header_values);
156+
ServiceClient client = nh.template serviceClient<Service>(ros::names::resolve(service_name), persistent, header_values, timeout);
156157
return client;
157158
}
158159

test/test_roscpp/test/src/service_call.cpp

Lines changed: 33 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -178,6 +178,39 @@ TEST(SrvCall, callSrvLongRunning)
178178
ASSERT_STREQ(res.str.c_str(), "CASE_flip");
179179
}
180180

181+
TEST(SrvCall, callSrvLongRunningTimeout)
182+
{
183+
test_roscpp::TestStringString::Request req;
184+
test_roscpp::TestStringString::Response res;
185+
186+
req.str = std::string("case_FLIP");
187+
188+
ASSERT_TRUE(ros::service::waitForService("service_adv_long"));
189+
ASSERT_FALSE(ros::service::call("service_adv_long", req, res, ros::Duration(1.0))); // Service delay is 2 seconds
190+
191+
ASSERT_STRNE(res.str.c_str(), "CASE_flip");
192+
}
193+
194+
TEST(SrvCall, callSrvLongRunningTimeoutRepeat)
195+
{
196+
test_roscpp::TestStringString::Request req;
197+
test_roscpp::TestStringString::Response res;
198+
199+
req.str = std::string("case_FLIP");
200+
201+
ASSERT_TRUE(ros::service::waitForService("service_adv_long"));
202+
ASSERT_FALSE(ros::service::call("service_adv_long", req, res, ros::Duration(1.0))); // Service delay is 2 seconds
203+
ASSERT_FALSE(ros::service::call("service_adv_long", req, res, ros::Duration(1.5)));
204+
ASSERT_FALSE(ros::service::call("service_adv_long", req, res, ros::Duration(0.5)));
205+
ASSERT_FALSE(ros::service::call("service_adv_long", req, res, ros::Duration(1.8)));
206+
207+
ASSERT_STRNE(res.str.c_str(), "CASE_flip");
208+
209+
ASSERT_TRUE(ros::service::call("service_adv_long", req, res, ros::Duration(2.5)));
210+
211+
ASSERT_STREQ(res.str.c_str(), "CASE_flip");
212+
}
213+
181214
TEST(SrvCall, callSrvWhichUnadvertisesInCallback)
182215
{
183216
test_roscpp::TestStringString::Request req;

0 commit comments

Comments
 (0)