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

Support tf_static 2to1 #424

Open
wants to merge 2 commits into
base: foxy
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
4 changes: 2 additions & 2 deletions CHANGELOG.rst
Original file line number Diff line number Diff line change
Expand Up @@ -2,8 +2,8 @@
Changelog for package ros1_bridge
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^

Forthcoming
-----------
0.9.7 (2023-05-27)
------------------
* remove xmlrpcpp from package.xml (`#406 <https://github.com/ros2/ros1_bridge/issues/406>`_)
* Parametrization of `parameter_bridge` quality of service [Port of the commits (ec44770) and (86b4245) to foxy branch] (`#401 <https://github.com/ros2/ros1_bridge/issues/401>`_)
* Contributors: Dharini Dutia, Lucyanno Frota
Expand Down
1 change: 1 addition & 0 deletions include/ros1_bridge/bridge.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -116,6 +116,7 @@ create_bridge_from_2_to_1(
const std::string & ros1_type_name,
const std::string & ros1_topic_name,
size_t publisher_queue_size,
bool publisher_latch,
rclcpp::PublisherBase::SharedPtr ros2_pub = nullptr);

BridgeHandles
Expand Down
2 changes: 1 addition & 1 deletion package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,7 @@
<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
<package format="3">
<name>ros1_bridge</name>
<version>0.9.6</version>
<version>0.9.7</version>
<description>A simple bridge between ROS 1 and ROS 2</description>
<maintainer email="[email protected]">Dirk Thomas</maintainer>
<license>Apache License 2.0</license>
Expand Down
5 changes: 4 additions & 1 deletion src/bridge.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -79,6 +79,7 @@ create_bridge_from_2_to_1(
rclcpp::PublisherBase::SharedPtr ros2_pub)
{
auto subscriber_qos = rclcpp::SensorDataQoS(rclcpp::KeepLast(subscriber_queue_size));
auto publisher_latch = false;
return create_bridge_from_2_to_1(
ros2_node,
ros1_node,
Expand All @@ -88,6 +89,7 @@ create_bridge_from_2_to_1(
ros1_type_name,
ros1_topic_name,
publisher_queue_size,
publisher_latch,
ros2_pub);
}

Expand All @@ -101,11 +103,12 @@ create_bridge_from_2_to_1(
const std::string & ros1_type_name,
const std::string & ros1_topic_name,
size_t publisher_queue_size,
bool publisher_latch,
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);
ros1_node, ros1_topic_name, publisher_queue_size, publisher_latch);

auto ros2_sub = factory->create_ros2_subscriber(
ros2_node, ros2_topic_name, subscriber_qos, ros1_pub, ros2_pub);
Expand Down
13 changes: 11 additions & 2 deletions src/dynamic_bridge.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -254,11 +254,20 @@ void update_bridge(
bridge.ros1_type_name = ros1_type_name;
bridge.ros2_type_name = ros2_type_name;

auto ros2_subscriber_qos = rclcpp::QoS(rclcpp::KeepLast(10));
auto ros_publisher_latch = false;
if (topic_name == "/tf_static") {
ros2_subscriber_qos.keep_all();
ros2_subscriber_qos.transient_local();
ros2_subscriber_qos.reliable();
ros_publisher_latch = true;
}

try {
bridge.bridge_handles = ros1_bridge::create_bridge_from_2_to_1(
ros2_node, ros1_node,
bridge.ros2_type_name, topic_name, 10,
bridge.ros1_type_name, topic_name, 10);
bridge.ros2_type_name, topic_name, ros2_subscriber_qos,
bridge.ros1_type_name, topic_name, 10, ros_publisher_latch);
} catch (std::runtime_error & e) {
fprintf(
stderr,
Expand Down