|
7 | 7 | #include <QApplication> |
8 | 8 | #include <QProgressDialog> |
9 | 9 | #include "rclcpp/generic_subscription.hpp" |
10 | | -#include "rosbag2_transport/qos.hpp" |
| 10 | + |
| 11 | +// function taken from rosbag2_transport |
| 12 | + |
| 13 | +rclcpp::QoS adapt_request_to_offers( |
| 14 | + const std::string & topic_name, const std::vector<rclcpp::TopicEndpointInfo> & endpoints) |
| 15 | +{ |
| 16 | + rclcpp::QoS request_qos(rmw_qos_profile_default.depth); |
| 17 | + |
| 18 | + if (endpoints.empty()) { |
| 19 | + return request_qos; |
| 20 | + } |
| 21 | + size_t num_endpoints = endpoints.size(); |
| 22 | + size_t reliability_reliable_endpoints_count = 0; |
| 23 | + size_t durability_transient_local_endpoints_count = 0; |
| 24 | + for (const auto & endpoint : endpoints) { |
| 25 | + const auto & profile = endpoint.qos_profile().get_rmw_qos_profile(); |
| 26 | + if (profile.reliability == RMW_QOS_POLICY_RELIABILITY_RELIABLE) { |
| 27 | + reliability_reliable_endpoints_count++; |
| 28 | + } |
| 29 | + if (profile.durability == RMW_QOS_POLICY_DURABILITY_TRANSIENT_LOCAL) { |
| 30 | + durability_transient_local_endpoints_count++; |
| 31 | + } |
| 32 | + } |
| 33 | + |
| 34 | + // Policy: reliability |
| 35 | + if (reliability_reliable_endpoints_count == num_endpoints) { |
| 36 | + request_qos.reliable(); |
| 37 | + } else { |
| 38 | + request_qos.best_effort(); |
| 39 | + } |
| 40 | + |
| 41 | + // Policy: durability |
| 42 | + // If all publishers offer transient_local, we can request it and receive latched messages |
| 43 | + if (durability_transient_local_endpoints_count == num_endpoints) { |
| 44 | + request_qos.transient_local(); |
| 45 | + } else { |
| 46 | + request_qos.durability_volatile(); |
| 47 | + } |
| 48 | + |
| 49 | + return request_qos; |
| 50 | +} |
11 | 51 |
|
12 | 52 | DataStreamROS2::DataStreamROS2() : |
13 | 53 | DataStreamer(), |
@@ -192,7 +232,7 @@ void DataStreamROS2::subscribeToTopic(const std::string& topic_name, const std:: |
192 | 232 | auto bound_callback = [=](std::shared_ptr<rclcpp::SerializedMessage> msg) { messageCallback(topic_name, msg); }; |
193 | 233 |
|
194 | 234 | auto publisher_info = _node->get_publishers_info_by_topic(topic_name); |
195 | | - auto detected_qos = rosbag2_transport::Rosbag2QoS::adapt_request_to_offers(topic_name, publisher_info); |
| 235 | + auto detected_qos = adapt_request_to_offers(topic_name, publisher_info); |
196 | 236 |
|
197 | 237 | // double subscription, latching or not |
198 | 238 | auto subscription = _node->create_generic_subscription(topic_name, |
|
0 commit comments