Skip to content

Commit

Permalink
Merge pull request #1 from hsrn24/support-tf-static-2to1-dynamic-bridge
Browse files Browse the repository at this point in the history
Add qos rules for tf_static topic
  • Loading branch information
pawelirh authored Oct 24, 2023
2 parents 689a932 + caef6ee commit 6f51fb5
Show file tree
Hide file tree
Showing 3 changed files with 16 additions and 3 deletions.
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
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

0 comments on commit 6f51fb5

Please sign in to comment.