diff --git a/include/ros1_bridge/factory.hpp b/include/ros1_bridge/factory.hpp index 400ca455..a1a44bc4 100755 --- a/include/ros1_bridge/factory.hpp +++ b/include/ros1_bridge/factory.hpp @@ -59,9 +59,7 @@ class Factory : public FactoryInterface const std::string & topic_name, size_t queue_size) { - rmw_qos_profile_t custom_qos_profile = rmw_qos_profile_default; - custom_qos_profile.depth = queue_size; - return node->create_publisher(topic_name, custom_qos_profile); + return node->create_publisher(topic_name, rclcpp::QoS(rclcpp::KeepLast(queue_size))); } rclcpp::PublisherBase::SharedPtr @@ -70,7 +68,9 @@ class Factory : public FactoryInterface const std::string & topic_name, const rmw_qos_profile_t & qos_profile) { - return node->create_publisher(topic_name, qos_profile); + auto qos = rclcpp::QoS(rclcpp::KeepAll()); + qos.get_rmw_qos_profile() = qos_profile; + return node->create_publisher(topic_name, qos); } ros::Subscriber @@ -121,8 +121,10 @@ class Factory : public FactoryInterface callback = std::bind( &Factory::ros2_callback, std::placeholders::_1, std::placeholders::_2, 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; return node->create_subscription( - topic_name, callback, qos, nullptr, true); + topic_name, rclcpp_qos, callback, nullptr, true); } 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 dc088c1c..43e98704 100644 --- a/src/simple_bridge.cpp +++ b/src/simple_bridge.cpp @@ -82,7 +82,7 @@ int main(int argc, char * argv[]) rclcpp::init(argc, argv); auto ros2_node = rclcpp::Node::make_shared("ros_bridge"); ros2_pub = ros2_node->create_publisher( - "chatter", rmw_qos_profile_sensor_data); + "chatter", rclcpp::SensorDataQoS()); // ROS 1 subscriber ros::Subscriber ros1_sub = ros1_node.subscribe( @@ -90,7 +90,7 @@ int main(int argc, char * argv[]) // ROS 2 subscriber auto ros2_sub = ros2_node->create_subscription( - "chatter", ros2ChatterCallback, rmw_qos_profile_sensor_data, nullptr, true); + "chatter", rclcpp::SensorDataQoS(), ros2ChatterCallback, nullptr, true); // ROS 1 asynchronous spinner ros::AsyncSpinner async_spinner(1); diff --git a/src/simple_bridge_1_to_2.cpp b/src/simple_bridge_1_to_2.cpp index be334ecb..0eb97d91 100644 --- a/src/simple_bridge_1_to_2.cpp +++ b/src/simple_bridge_1_to_2.cpp @@ -49,7 +49,7 @@ int main(int argc, char * argv[]) // ROS 2 node and publisher rclcpp::init(argc, argv); auto node = rclcpp::Node::make_shared("talker"); - pub = node->create_publisher("chatter"); + pub = node->create_publisher("chatter", 10); // ROS 1 node and subscriber ros::init(argc, argv, "listener"); diff --git a/src/simple_bridge_2_to_1.cpp b/src/simple_bridge_2_to_1.cpp index 0be85268..42499789 100644 --- a/src/simple_bridge_2_to_1.cpp +++ b/src/simple_bridge_2_to_1.cpp @@ -53,7 +53,7 @@ int main(int argc, char * argv[]) rclcpp::init(argc, argv); auto node = rclcpp::Node::make_shared("listener"); auto sub = node->create_subscription( - "chatter", chatterCallback, rmw_qos_profile_sensor_data); + "chatter", rclcpp::SensorDataQoS(), chatterCallback); rclcpp::spin(node);