Skip to content

Commit

Permalink
Allow external use of ros1_bridge library factories
Browse files Browse the repository at this point in the history
  • Loading branch information
paulbovbel committed Feb 6, 2019
1 parent b21099b commit 3873b76
Show file tree
Hide file tree
Showing 4 changed files with 98 additions and 47 deletions.
1 change: 1 addition & 0 deletions CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -135,6 +135,7 @@ custom_executable(simple_bridge "src/simple_bridge.cpp"
add_library(${PROJECT_NAME} SHARED
"src/builtin_interfaces_factories.cpp"
"src/convert_builtin_interfaces.cpp"
"src/bridge.cpp"
${generated_files})
ament_target_dependencies(${PROJECT_NAME}
${prefixed_ros1_message_packages}
Expand Down
47 changes: 6 additions & 41 deletions include/ros1_bridge/bridge.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -69,6 +69,9 @@ get_factory(
const std::string & ros1_type_name,
const std::string & ros2_type_name);

std::unique_ptr<ServiceFactoryInterface>
get_service_factory(const std::string &, const std::string &, const std::string &);

Bridge1to2Handles
create_bridge_from_1_to_2(
ros::NodeHandle ros1_node,
Expand All @@ -78,20 +81,7 @@ create_bridge_from_1_to_2(
size_t subscriber_queue_size,
const std::string & ros2_type_name,
const std::string & ros2_topic_name,
size_t publisher_queue_size)
{
auto factory = get_factory(ros1_type_name, ros2_type_name);
auto ros2_pub = factory->create_ros2_publisher(
ros2_node, ros2_topic_name, publisher_queue_size);

auto ros1_sub = factory->create_ros1_subscriber(
ros1_node, ros1_topic_name, subscriber_queue_size, ros2_pub);

Bridge1to2Handles handles;
handles.ros1_subscriber = ros1_sub;
handles.ros2_publisher = ros2_pub;
return handles;
}
size_t publisher_queue_size);

Bridge2to1Handles
create_bridge_from_2_to_1(
Expand All @@ -103,20 +93,7 @@ create_bridge_from_2_to_1(
const std::string & ros1_type_name,
const std::string & ros1_topic_name,
size_t publisher_queue_size,
rclcpp::PublisherBase::SharedPtr ros2_pub = nullptr)
{
auto factory = get_factory(ros1_type_name, ros2_type_name);
auto ros1_pub = factory->create_ros1_publisher(
ros1_node, ros1_topic_name, publisher_queue_size);

auto ros2_sub = factory->create_ros2_subscriber(
ros2_node, ros2_topic_name, subscriber_queue_size, ros1_pub, ros2_pub);

Bridge2to1Handles handles;
handles.ros2_subscriber = ros2_sub;
handles.ros1_publisher = ros1_pub;
return handles;
}
rclcpp::PublisherBase::SharedPtr ros2_pub = nullptr);

BridgeHandles
create_bidirectional_bridge(
Expand All @@ -125,19 +102,7 @@ create_bidirectional_bridge(
const std::string & ros1_type_name,
const std::string & ros2_type_name,
const std::string & topic_name,
size_t queue_size = 10)
{
printf("create bidirectional bridge for topic [%s]\n", topic_name.c_str());
BridgeHandles handles;
handles.bridge1to2 = create_bridge_from_1_to_2(
ros1_node, ros2_node,
ros1_type_name, topic_name, queue_size, ros2_type_name, topic_name, queue_size);
handles.bridge2to1 = create_bridge_from_2_to_1(
ros2_node, ros1_node,
ros2_type_name, topic_name, queue_size, ros1_type_name, topic_name, queue_size,
handles.bridge1to2.ros2_publisher);
return handles;
}
size_t queue_size = 10);

} // namespace ros1_bridge

Expand Down
91 changes: 91 additions & 0 deletions src/bridge.cpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,91 @@
// Copyright 2015 Open Source Robotics Foundation, Inc.
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
//
// http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.


#include "ros1_bridge/bridge.hpp"

namespace ros1_bridge
{

Bridge1to2Handles
create_bridge_from_1_to_2(
ros::NodeHandle ros1_node,
rclcpp::Node::SharedPtr ros2_node,
const std::string & ros1_type_name,
const std::string & ros1_topic_name,
size_t subscriber_queue_size,
const std::string & ros2_type_name,
const std::string & ros2_topic_name,
size_t publisher_queue_size)
{
auto factory = get_factory(ros1_type_name, ros2_type_name);
auto ros2_pub = factory->create_ros2_publisher(
ros2_node, ros2_topic_name, publisher_queue_size);

auto ros1_sub = factory->create_ros1_subscriber(
ros1_node, ros1_topic_name, subscriber_queue_size, ros2_pub);

Bridge1to2Handles handles;
handles.ros1_subscriber = ros1_sub;
handles.ros2_publisher = ros2_pub;
return handles;
}

Bridge2to1Handles
create_bridge_from_2_to_1(
rclcpp::Node::SharedPtr ros2_node,
ros::NodeHandle ros1_node,
const std::string & ros2_type_name,
const std::string & ros2_topic_name,
size_t subscriber_queue_size,
const std::string & ros1_type_name,
const std::string & ros1_topic_name,
size_t publisher_queue_size,
rclcpp::PublisherBase::SharedPtr ros2_pub)
{
auto factory = get_factory(ros1_type_name, ros2_type_name);
auto ros1_pub = factory->create_ros1_publisher(
ros1_node, ros1_topic_name, publisher_queue_size);

auto ros2_sub = factory->create_ros2_subscriber(
ros2_node, ros2_topic_name, subscriber_queue_size, ros1_pub, ros2_pub);

Bridge2to1Handles handles;
handles.ros2_subscriber = ros2_sub;
handles.ros1_publisher = ros1_pub;
return handles;
}

BridgeHandles
create_bidirectional_bridge(
ros::NodeHandle ros1_node,
rclcpp::Node::SharedPtr ros2_node,
const std::string & ros1_type_name,
const std::string & ros2_type_name,
const std::string & topic_name,
size_t queue_size)
{
printf("create bidirectional bridge for topic [%s]\n", topic_name.c_str());
BridgeHandles handles;
handles.bridge1to2 = create_bridge_from_1_to_2(
ros1_node, ros2_node,
ros1_type_name, topic_name, queue_size, ros2_type_name, topic_name, queue_size);
handles.bridge2to1 = create_bridge_from_2_to_1(
ros2_node, ros1_node,
ros2_type_name, topic_name, queue_size, ros1_type_name, topic_name, queue_size,
handles.bridge1to2.ros2_publisher);
return handles;
}

} // namespace ros1_bridge
6 changes: 0 additions & 6 deletions src/dynamic_bridge.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -41,12 +41,6 @@

std::mutex g_bridge_mutex;

namespace ros1_bridge
{
std::unique_ptr<ros1_bridge::ServiceFactoryInterface>
get_service_factory(const std::string &, const std::string &, const std::string &);
}

struct Bridge1to2HandlesAndMessageTypes
{
ros1_bridge::Bridge1to2Handles bridge_handles;
Expand Down

0 comments on commit 3873b76

Please sign in to comment.