Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Bug fix for fields in service calls with different names. #347

Open
wants to merge 6 commits into
base: master
Choose a base branch
from
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
6 changes: 3 additions & 3 deletions include/ros1_bridge/builtin_interfaces_factories.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -19,13 +19,13 @@
#include <std_msgs/Duration.h>
#include <std_msgs/Time.h>

#include <memory>
#include <string>

// include ROS 2 messages
#include <builtin_interfaces/msg/duration.hpp>
#include <builtin_interfaces/msg/time.hpp>

#include <memory>
#include <string>

#include "ros1_bridge/factory.hpp"

namespace ros1_bridge
Expand Down
14 changes: 9 additions & 5 deletions include/ros1_bridge/factory.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -294,7 +294,8 @@ class ServiceFactory : public ServiceFactoryInterface

bool forward_1_to_2(
rclcpp::ClientBase::SharedPtr cli, rclcpp::Logger logger,
const ROS1Request & request1, ROS1Response & response1)
const ROS1Request & request1, ROS1Response & response1,
int service_execution_timeout)
{
auto client = std::dynamic_pointer_cast<rclcpp::Client<ROS2_T>>(cli);
if (!client) {
Expand All @@ -311,28 +312,31 @@ class ServiceFactory : public ServiceFactoryInterface
}
RCLCPP_WARN(logger, "Waiting for ROS 2 service %s...", cli->get_service_name());
}
auto timeout = std::chrono::seconds(5);
auto timeout = std::chrono::seconds(service_execution_timeout);
auto future = client->async_send_request(request2);
auto status = future.wait_for(timeout);
if (status == std::future_status::ready) {
auto response2 = future.get();
translate_2_to_1(*response2, response1);
} else {
RCLCPP_ERROR(logger, "Failed to get response from ROS 2 service %s", cli->get_service_name());
RCLCPP_ERROR(
logger, "Failed to get response from ROS 2 service %s within %d seconds",
cli->get_service_name(), service_execution_timeout);
return false;
}
return true;
}

ServiceBridge1to2 service_bridge_1_to_2(
ros::NodeHandle & ros1_node, rclcpp::Node::SharedPtr ros2_node, const std::string & name)
ros::NodeHandle & ros1_node, rclcpp::Node::SharedPtr ros2_node, const std::string & name,
int service_execution_timeout)
{
ServiceBridge1to2 bridge;
bridge.client = ros2_node->create_client<ROS2_T>(name);
auto m = &ServiceFactory<ROS1_T, ROS2_T>::forward_1_to_2;
auto f = std::bind(
m, this, bridge.client, ros2_node->get_logger(), std::placeholders::_1,
std::placeholders::_2);
std::placeholders::_2, service_execution_timeout);
bridge.server = ros1_node.advertiseService<ROS1Request, ROS1Response>(name, f);
return bridge;
}
Expand Down
2 changes: 1 addition & 1 deletion include/ros1_bridge/factory_interface.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -123,7 +123,7 @@ class ServiceFactoryInterface
{
public:
virtual ServiceBridge1to2 service_bridge_1_to_2(
ros::NodeHandle &, rclcpp::Node::SharedPtr, const std::string &) = 0;
ros::NodeHandle &, rclcpp::Node::SharedPtr, const std::string &, int) = 0;

virtual ServiceBridge2to1 service_bridge_2_to_1(
ros::NodeHandle &, rclcpp::Node::SharedPtr, const std::string &) = 0;
Expand Down
3 changes: 2 additions & 1 deletion package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -4,11 +4,12 @@
<name>ros1_bridge</name>
<version>0.10.2</version>
<description>A simple bridge between ROS 1 and ROS 2</description>
<maintainer email="[email protected]">Jacob Perron</maintainer>
<maintainer email="[email protected]">Shane Loretz</maintainer>
<maintainer email="[email protected]">Geoffrey Biggs</maintainer>
<license>Apache License 2.0</license>

<author email="[email protected]">Dirk Thomas</author>
<author email="[email protected]">Jacob Perron</author>

<buildtool_depend>ament_cmake</buildtool_depend>
<buildtool_depend>ament_index_python</buildtool_depend>
Expand Down
9 changes: 9 additions & 0 deletions resource/interface_factories.cpp.em
Original file line number Diff line number Diff line change
Expand Up @@ -317,11 +317,20 @@ void ServiceFactory<
auto & @(field["ros2"]["name"])2 = req2.@(field["ros2"]["name"]);
@[ end if]@
@[ if field["basic"]]@
@[ if frm == "1"]@
@(field["ros2"]["name"])@(to) = @(field["ros1"]["name"])@(frm);
@[ else]@
@(field["ros1"]["name"])@(to) = @(field["ros2"]["name"])@(frm);
@[ end if]@
@[ else]@
@[ if frm == "1"]@
Factory<@(field["ros1"]["cpptype"]),@(field["ros2"]["cpptype"])>::convert_@(frm)_to_@(to)(@
@(field["ros1"]["name"])@(frm), @(field["ros2"]["name"])@(to));
@[ else]@
Factory<@(field["ros1"]["cpptype"]),@(field["ros2"]["cpptype"])>::convert_@(frm)_to_@(to)(@
@(field["ros2"]["name"])@(frm), @(field["ros1"]["name"])@(to));
@[ end if]@
@[ end if]@
@[ if field["array"]]@
}
@[ end if]@
Expand Down
4 changes: 2 additions & 2 deletions ros1_bridge/__init__.py
Original file line number Diff line number Diff line change
Expand Up @@ -607,10 +607,10 @@ def determine_common_services(
ros2_type = str(ros2_fields[direction][i].type)
ros1_name = ros1_field[1]
ros2_name = ros2_fields[direction][i].name
if ros1_type != ros2_type or ros1_name != ros2_name:
if ros1_type != ros2_type:
# if the message types have a custom mapping their names
# might not be equal, therefore check the message pairs
if (ros1_type, ros2_type) not in message_string_pairs:
if (ros1_type.rstrip("[]"), ros2_type.rstrip("[]")) not in message_string_pairs:
match = False
break
output[direction].append({
Expand Down
7 changes: 6 additions & 1 deletion src/dynamic_bridge.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -327,6 +327,10 @@ void update_bridge(
}
}

int service_execution_timeout{5};
ros1_node.getParamCached(
"ros1_bridge/dynamic_bridge/service_execution_timeout", service_execution_timeout);

// create bridges for ros2 services
for (auto & service : ros2_services) {
auto & name = service.first;
Expand All @@ -339,7 +343,8 @@ void update_bridge(
"ros2", details.at("package"), details.at("name"));
if (factory) {
try {
service_bridges_1_to_2[name] = factory->service_bridge_1_to_2(ros1_node, ros2_node, name);
service_bridges_1_to_2[name] = factory->service_bridge_1_to_2(
ros1_node, ros2_node, name, service_execution_timeout);
printf("Created 1 to 2 bridge for service %s\n", name.data());
} catch (std::runtime_error & e) {
fprintf(stderr, "Failed to created a bridge: %s\n", e.what());
Expand Down
7 changes: 6 additions & 1 deletion src/parameter_bridge.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -58,6 +58,8 @@ int main(int argc, char * argv[])
// type: the type of the service to bridge (e.g. 'pkgname/srv/SrvName')
const char * services_1_to_2_parameter_name = "services_1_to_2";
const char * services_2_to_1_parameter_name = "services_2_to_1";
const char * service_execution_timeout_parameter_name =
"ros1_bridge/parameter_bridge/service_execution_timeout";
if (argc > 1) {
topics_parameter_name = argv[1];
}
Expand Down Expand Up @@ -110,6 +112,9 @@ int main(int argc, char * argv[])
ros1_node.getParam(services_1_to_2_parameter_name, services_1_to_2) &&
services_1_to_2.getType() == XmlRpc::XmlRpcValue::TypeArray)
{
int service_execution_timeout{5};
ros1_node.getParamCached(
service_execution_timeout_parameter_name, service_execution_timeout);
for (size_t i = 0; i < static_cast<size_t>(services_1_to_2.size()); ++i) {
std::string service_name = static_cast<std::string>(services_1_to_2[i]["service"]);
std::string type_name = static_cast<std::string>(services_1_to_2[i]["type"]);
Expand Down Expand Up @@ -143,7 +148,7 @@ int main(int argc, char * argv[])
try {
service_bridges_1_to_2.push_back(
factory->service_bridge_1_to_2(
ros1_node, ros2_node, service_name));
ros1_node, ros2_node, service_name, service_execution_timeout));
printf("Created 1 to 2 bridge for service %s\n", service_name.c_str());
} catch (std::runtime_error & e) {
fprintf(
Expand Down