Skip to content
This repository has been archived by the owner on Jun 15, 2020. It is now read-only.

Add static bridge for strings #1

Merged
merged 6 commits into from
Aug 26, 2019
Merged
Show file tree
Hide file tree
Changes from 1 commit
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
42 changes: 42 additions & 0 deletions ros2_ign_bridge/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -11,5 +11,47 @@ if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang")
endif()

find_package(ament_cmake REQUIRED)
find_package(rclcpp REQUIRED)
find_package(std_msgs REQUIRED)

find_package(ignition-msgs4 QUIET REQUIRED)
set(IGN_MSGS_VER ${ignition-msgs4_VERSION_MAJOR})

find_package(ignition-transport7 QUIET REQUIRED)
set(IGN_TRANSPORT_VER ${ignition-transport7_VERSION_MAJOR})

include_directories(include)

set(common_sources
src/convert_builtin_interfaces.cpp
src/builtin_interfaces_factories.cpp
)

set(bridge_executables
static_bridge
)

foreach(bridge ${bridge_executables})
add_executable(${bridge}
src/${bridge}.cpp
${common_sources}
)
target_link_libraries(${bridge}
ignition-msgs${IGN_MSGS_VER}::core
ignition-transport${IGN_TRANSPORT_VER}::core
)
ament_target_dependencies(${bridge}
"rclcpp"
"std_msgs"
)
install(TARGETS ${bridge}
DESTINATION lib/${PROJECT_NAME}
)
endforeach()

if(BUILD_TESTING)
find_package(ament_lint_auto REQUIRED)
ament_lint_auto_find_test_dependencies()
endif()

ament_package()
107 changes: 107 additions & 0 deletions ros2_ign_bridge/include/ros2_ign_bridge/bridge.hpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,107 @@
// Copyright 2019 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.

#ifndef ROS2_IGN_BRIDGE__BRIDGE_HPP_
#define ROS2_IGN_BRIDGE__BRIDGE_HPP_

// include Ignition Transport
#include <ignition/transport/Node.hh>

#include <ros2_ign_bridge/builtin_interfaces_factories.hpp>

#include <memory>
#include <string>

namespace ros2_ign_bridge
{

struct BridgeRos2toIgnHandles
{
rclcpp::SubscriptionBase::SharedPtr ros2_subscriber;
ignition::transport::Node::Publisher ign_publisher;
};

struct BridgeIgntoRos2Handles
{
std::shared_ptr<ignition::transport::Node> ign_subscriber;
rclcpp::PublisherBase::SharedPtr ros2_publisher;
};

struct BridgeHandles
{
BridgeRos2toIgnHandles bridgeRos2toIgn;
BridgeIgntoRos2Handles bridgeIgntoRos2;
};

BridgeRos2toIgnHandles
create_bridge_from_ros2_to_ign(
rclcpp::Node::SharedPtr ros2_node,
std::shared_ptr<ignition::transport::Node> ign_node,
const std::string & ros2_type_name,
const std::string & ros2_topic_name,
const std::string & ign_type_name,
const std::string & ign_topic_name)
{
auto factory = get_factory(ros2_type_name, ign_type_name);
auto ign_pub = factory->create_ign_publisher(ign_node, ign_topic_name);

auto ros2_sub = factory->create_ros2_subscriber(ros2_node, ros2_topic_name, ign_pub);

BridgeRos2toIgnHandles handles;
handles.ros2_subscriber = ros2_sub;
handles.ign_publisher = ign_pub;
return handles;
}

BridgeIgntoRos2Handles
create_bridge_from_ign_to_ros2(
std::shared_ptr<ignition::transport::Node> ign_node,
rclcpp::Node::SharedPtr ros2_node,
const std::string & ign_type_name,
const std::string & ign_topic_name,
const std::string & ros2_type_name,
const std::string & ros2_topic_name)
{
auto factory = get_factory(ros2_type_name, ign_type_name);
auto ros2_pub = factory->create_ros2_publisher(ros2_node, ros2_topic_name);

factory->create_ign_subscriber(ign_node, ign_topic_name, ros2_pub);

BridgeIgntoRos2Handles handles;
handles.ign_subscriber = ign_node;
handles.ros2_publisher = ros2_pub;
return handles;
}

BridgeHandles
create_bidirectional_bridge(
rclcpp::Node::SharedPtr ros2_node,
std::shared_ptr<ignition::transport::Node> ign_node,
const std::string & ros2_type_name,
const std::string & ign_type_name,
const std::string & topic_name)
{
BridgeHandles handles;
handles.bridgeRos2toIgn = create_bridge_from_ros2_to_ign(
ros2_node, ign_node,
ros2_type_name, topic_name, ign_type_name, topic_name);
handles.bridgeIgntoRos2 = create_bridge_from_ign_to_ros2(
ign_node, ros2_node,
ign_type_name, topic_name, ros2_type_name, topic_name);
return handles;
}

} // namespace ros2_ign_bridge

#endif // ROS2_IGN_BRIDGE__BRIDGE_HPP_
Original file line number Diff line number Diff line change
@@ -0,0 +1,65 @@
// Copyright 2019 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.

#ifndef ROS2_IGN_BRIDGE__BUILTIN_INTERFACES_FACTORIES_HPP_
#define ROS2_IGN_BRIDGE__BUILTIN_INTERFACES_FACTORIES_HPP_

// include ROS 2 messages
#include <std_msgs/msg/string.hpp>

// include Ignition Transport messages
#include <ignition/msgs.hh>

#include <ros2_ign_bridge/factory.hpp>

#include <memory>
#include <string>

namespace ros2_ign_bridge
{

std::shared_ptr<FactoryInterface>
get_factory_builtin_interfaces(
const std::string & ros2_type_name,
const std::string & ign_type_name);

std::shared_ptr<FactoryInterface>
get_factory(
const std::string & ros2_type_name,
const std::string & ign_type_name);

// conversion functions for available interfaces

// std_msgs
template<>
void
Factory<
std_msgs::msg::String,
ignition::msgs::StringMsg
>::convert_ros2_to_ign(
const std_msgs::msg::String & ros2_msg,
ignition::msgs::StringMsg & ign_msg);

template<>
void
Factory<
std_msgs::msg::String,
ignition::msgs::StringMsg
>::convert_ign_to_ros2(
const ignition::msgs::StringMsg & ign_msg,
std_msgs::msg::String & ros2_msg);

} // namespace ros2_ign_bridge

#endif // ROS2_IGN_BRIDGE__BUILTIN_INTERFACES_FACTORIES_HPP_
Original file line number Diff line number Diff line change
@@ -0,0 +1,44 @@
// Copyright 2019 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.

#ifndef ROS2_IGN_BRIDGE__CONVERT_BUILTIN_INTERFACES_HPP_
#define ROS2_IGN_BRIDGE__CONVERT_BUILTIN_INTERFACES_HPP_

// include ROS 2 builtin messages
#include <std_msgs/msg/string.hpp>

// include Ignition builtin messages
#include <ignition/msgs.hh>

#include <ros2_ign_bridge/convert_decl.hpp>

namespace ros2_ign_bridge
{

// std_msgs
template<>
void
convert_ros2_to_ign(
const std_msgs::msg::String & ros2_msg,
ignition::msgs::StringMsg & ign_msg);

template<>
void
convert_ign_to_ros2(
const ignition::msgs::StringMsg & ign_msg,
std_msgs::msg::String & ros2_msg);

} // namespace ros2_ign_bridge

#endif // ROS2_IGN_BRIDGE__CONVERT_BUILTIN_INTERFACES_HPP_
35 changes: 35 additions & 0 deletions ros2_ign_bridge/include/ros2_ign_bridge/convert_decl.hpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,35 @@
// Copyright 2019 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.

#ifndef ROS2_IGN_BRIDGE__CONVERT_DECL_HPP_
#define ROS2_IGN_BRIDGE__CONVERT_DECL_HPP_

namespace ros2_ign_bridge
{

template<typename ROS2_T, typename IGN_T>
void
convert_ros2_to_ign(
const ROS2_T & ros2_msg,
IGN_T & ign_msg);

template<typename ROS2_T, typename IGN_T>
void
convert_ign_to_ros2(
const IGN_T & ign_msg,
ROS2_T & ros2_msg);

} // namespace ros2_ign_bridge

#endif // ROS2_IGN_BRIDGE__CONVERT_DECL_HPP_
Loading