Skip to content

Commit fe94cf5

Browse files
authored
Parametrizing service execution timeout (#340)
* Parametrizing service execution timeout Signed-off-by: Marco Bassa <[email protected]>
1 parent e9b044b commit fe94cf5

File tree

4 files changed

+22
-8
lines changed

4 files changed

+22
-8
lines changed

include/ros1_bridge/factory.hpp

Lines changed: 9 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -294,7 +294,8 @@ class ServiceFactory : public ServiceFactoryInterface
294294

295295
bool forward_1_to_2(
296296
rclcpp::ClientBase::SharedPtr cli, rclcpp::Logger logger,
297-
const ROS1Request & request1, ROS1Response & response1)
297+
const ROS1Request & request1, ROS1Response & response1,
298+
int service_execution_timeout)
298299
{
299300
auto client = std::dynamic_pointer_cast<rclcpp::Client<ROS2_T>>(cli);
300301
if (!client) {
@@ -311,28 +312,31 @@ class ServiceFactory : public ServiceFactoryInterface
311312
}
312313
RCLCPP_WARN(logger, "Waiting for ROS 2 service %s...", cli->get_service_name());
313314
}
314-
auto timeout = std::chrono::seconds(5);
315+
auto timeout = std::chrono::seconds(service_execution_timeout);
315316
auto future = client->async_send_request(request2);
316317
auto status = future.wait_for(timeout);
317318
if (status == std::future_status::ready) {
318319
auto response2 = future.get();
319320
translate_2_to_1(*response2, response1);
320321
} else {
321-
RCLCPP_ERROR(logger, "Failed to get response from ROS 2 service %s", cli->get_service_name());
322+
RCLCPP_ERROR(
323+
logger, "Failed to get response from ROS 2 service %s within %d seconds",
324+
cli->get_service_name(), service_execution_timeout);
322325
return false;
323326
}
324327
return true;
325328
}
326329

327330
ServiceBridge1to2 service_bridge_1_to_2(
328-
ros::NodeHandle & ros1_node, rclcpp::Node::SharedPtr ros2_node, const std::string & name)
331+
ros::NodeHandle & ros1_node, rclcpp::Node::SharedPtr ros2_node, const std::string & name,
332+
int service_execution_timeout)
329333
{
330334
ServiceBridge1to2 bridge;
331335
bridge.client = ros2_node->create_client<ROS2_T>(name);
332336
auto m = &ServiceFactory<ROS1_T, ROS2_T>::forward_1_to_2;
333337
auto f = std::bind(
334338
m, this, bridge.client, ros2_node->get_logger(), std::placeholders::_1,
335-
std::placeholders::_2);
339+
std::placeholders::_2, service_execution_timeout);
336340
bridge.server = ros1_node.advertiseService<ROS1Request, ROS1Response>(name, f);
337341
return bridge;
338342
}

include/ros1_bridge/factory_interface.hpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -123,7 +123,7 @@ class ServiceFactoryInterface
123123
{
124124
public:
125125
virtual ServiceBridge1to2 service_bridge_1_to_2(
126-
ros::NodeHandle &, rclcpp::Node::SharedPtr, const std::string &) = 0;
126+
ros::NodeHandle &, rclcpp::Node::SharedPtr, const std::string &, int) = 0;
127127

128128
virtual ServiceBridge2to1 service_bridge_2_to_1(
129129
ros::NodeHandle &, rclcpp::Node::SharedPtr, const std::string &) = 0;

src/dynamic_bridge.cpp

Lines changed: 6 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -327,6 +327,10 @@ void update_bridge(
327327
}
328328
}
329329

330+
int service_execution_timeout{5};
331+
ros1_node.getParamCached(
332+
"ros1_bridge/dynamic_bridge/service_execution_timeout", service_execution_timeout);
333+
330334
// create bridges for ros2 services
331335
for (auto & service : ros2_services) {
332336
auto & name = service.first;
@@ -339,7 +343,8 @@ void update_bridge(
339343
"ros2", details.at("package"), details.at("name"));
340344
if (factory) {
341345
try {
342-
service_bridges_1_to_2[name] = factory->service_bridge_1_to_2(ros1_node, ros2_node, name);
346+
service_bridges_1_to_2[name] = factory->service_bridge_1_to_2(
347+
ros1_node, ros2_node, name, service_execution_timeout);
343348
printf("Created 1 to 2 bridge for service %s\n", name.data());
344349
} catch (std::runtime_error & e) {
345350
fprintf(stderr, "Failed to created a bridge: %s\n", e.what());

src/parameter_bridge.cpp

Lines changed: 6 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -58,6 +58,8 @@ int main(int argc, char * argv[])
5858
// type: the type of the service to bridge (e.g. 'pkgname/srv/SrvName')
5959
const char * services_1_to_2_parameter_name = "services_1_to_2";
6060
const char * services_2_to_1_parameter_name = "services_2_to_1";
61+
const char * service_execution_timeout_parameter_name =
62+
"ros1_bridge/parameter_bridge/service_execution_timeout";
6163
if (argc > 1) {
6264
topics_parameter_name = argv[1];
6365
}
@@ -110,6 +112,9 @@ int main(int argc, char * argv[])
110112
ros1_node.getParam(services_1_to_2_parameter_name, services_1_to_2) &&
111113
services_1_to_2.getType() == XmlRpc::XmlRpcValue::TypeArray)
112114
{
115+
int service_execution_timeout{5};
116+
ros1_node.getParamCached(
117+
service_execution_timeout_parameter_name, service_execution_timeout);
113118
for (size_t i = 0; i < static_cast<size_t>(services_1_to_2.size()); ++i) {
114119
std::string service_name = static_cast<std::string>(services_1_to_2[i]["service"]);
115120
std::string type_name = static_cast<std::string>(services_1_to_2[i]["type"]);
@@ -143,7 +148,7 @@ int main(int argc, char * argv[])
143148
try {
144149
service_bridges_1_to_2.push_back(
145150
factory->service_bridge_1_to_2(
146-
ros1_node, ros2_node, service_name));
151+
ros1_node, ros2_node, service_name, service_execution_timeout));
147152
printf("Created 1 to 2 bridge for service %s\n", service_name.c_str());
148153
} catch (std::runtime_error & e) {
149154
fprintf(

0 commit comments

Comments
 (0)