diff --git a/include/ros1_bridge/factory.hpp b/include/ros1_bridge/factory.hpp index a1a44bc4..d58a38f9 100755 --- a/include/ros1_bridge/factory.hpp +++ b/include/ros1_bridge/factory.hpp @@ -123,8 +123,10 @@ class Factory : public FactoryInterface ros1_pub, ros1_type_name_, ros2_type_name_, node->get_logger(), ros2_pub); auto rclcpp_qos = rclcpp::QoS(rclcpp::QoSInitialization::from_rmw(qos)); rclcpp_qos.get_rmw_qos_profile() = qos; + rclcpp::SubscriptionOptions options; + options.ignore_local_publications = true; return node->create_subscription( - topic_name, rclcpp_qos, callback, nullptr, true); + topic_name, rclcpp_qos, callback, options); } void convert_1_to_2(const void * ros1_msg, void * ros2_msg) override diff --git a/src/simple_bridge.cpp b/src/simple_bridge.cpp index 43e98704..c0de28a2 100644 --- a/src/simple_bridge.cpp +++ b/src/simple_bridge.cpp @@ -89,8 +89,10 @@ int main(int argc, char * argv[]) "chatter", 10, ros1ChatterCallback); // ROS 2 subscriber + rclcpp::SubscriptionOptions options; + options.ignore_local_publications = true; auto ros2_sub = ros2_node->create_subscription( - "chatter", rclcpp::SensorDataQoS(), ros2ChatterCallback, nullptr, true); + "chatter", rclcpp::SensorDataQoS(), ros2ChatterCallback, options); // ROS 1 asynchronous spinner ros::AsyncSpinner async_spinner(1);