|
| 1 | +// Copyright 2020 Ericsson AB |
| 2 | +// |
| 3 | +// Licensed under the Apache License, Version 2.0 (the "License"); |
| 4 | +// you may not use this file except in compliance with the License. |
| 5 | +// You may obtain a copy of the License at |
| 6 | +// |
| 7 | +// http://www.apache.org/licenses/LICENSE-2.0 |
| 8 | +// |
| 9 | +// Unless required by applicable law or agreed to in writing, software |
| 10 | +// distributed under the License is distributed on an "AS IS" BASIS, |
| 11 | +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. |
| 12 | +// See the License for the specific language governing permissions and |
| 13 | +// limitations under the License. |
| 14 | + |
| 15 | +#include <chrono> |
| 16 | +#include <functional> |
| 17 | +#include <memory> |
| 18 | +#include <sstream> |
| 19 | +#include <string> |
| 20 | +#include <vector> |
| 21 | + |
| 22 | +#include "rclcpp/rclcpp.hpp" |
| 23 | +#include "rclcpp/publisher_options.hpp" |
| 24 | +#include "std_msgs/msg/string.hpp" |
| 25 | + |
| 26 | +using namespace std::chrono_literals; |
| 27 | + |
| 28 | +class MinimalPublisherWithUniqueNetworkFlowEndpoints : public rclcpp::Node |
| 29 | +{ |
| 30 | +public: |
| 31 | + MinimalPublisherWithUniqueNetworkFlowEndpoints() |
| 32 | + : Node("minimal_publisher_with_unique_network_flow_endpoints"), count_1_(0), count_2_(0) |
| 33 | + { |
| 34 | + // Create publisher with unique network flow endpoints |
| 35 | + // Enable unique network flow endpoints via options |
| 36 | + auto options_1 = rclcpp::PublisherOptions(); |
| 37 | + options_1.require_unique_network_flow_endpoints = |
| 38 | + RMW_UNIQUE_NETWORK_FLOW_ENDPOINTS_OPTIONALLY_REQUIRED; |
| 39 | + publisher_1_ = this->create_publisher<std_msgs::msg::String>("topic_1", 10, options_1); |
| 40 | + timer_1_ = this->create_wall_timer( |
| 41 | + 500ms, std::bind(&MinimalPublisherWithUniqueNetworkFlowEndpoints::timer_1_callback, this)); |
| 42 | + |
| 43 | + // Create publisher without unique network flow endpoints |
| 44 | + // Unique network flow endpoints are disabled in default options |
| 45 | + auto options_2 = rclcpp::PublisherOptions(); |
| 46 | + publisher_2_ = this->create_publisher<std_msgs::msg::String>("topic_2", 10); |
| 47 | + timer_2_ = this->create_wall_timer( |
| 48 | + 1000ms, std::bind(&MinimalPublisherWithUniqueNetworkFlowEndpoints::timer_2_callback, this)); |
| 49 | + |
| 50 | + // Get network flow endpoints |
| 51 | + auto network_flow_endpoints_1 = publisher_1_->get_network_flow_endpoints(); |
| 52 | + auto network_flow_endpoints_2 = publisher_2_->get_network_flow_endpoints(); |
| 53 | + |
| 54 | + // Print network flow endpoints |
| 55 | + print_network_flow_endpoints(network_flow_endpoints_1); |
| 56 | + print_network_flow_endpoints(network_flow_endpoints_2); |
| 57 | + } |
| 58 | + |
| 59 | +private: |
| 60 | + void timer_1_callback() |
| 61 | + { |
| 62 | + auto message = std_msgs::msg::String(); |
| 63 | + message.data = "Hello, world! " + std::to_string(count_1_++); |
| 64 | + |
| 65 | + RCLCPP_INFO( |
| 66 | + this->get_logger(), "Publishing: '%s'", message.data.c_str()); |
| 67 | + publisher_1_->publish(message); |
| 68 | + } |
| 69 | + void timer_2_callback() |
| 70 | + { |
| 71 | + auto message = std_msgs::msg::String(); |
| 72 | + message.data = "Hej, världen! " + std::to_string(count_2_++); |
| 73 | + |
| 74 | + RCLCPP_INFO( |
| 75 | + this->get_logger(), "Publishing: '%s'", message.data.c_str()); |
| 76 | + publisher_2_->publish(message); |
| 77 | + } |
| 78 | + /// Print network flow endpoints in JSON-like format |
| 79 | + void print_network_flow_endpoints( |
| 80 | + const std::vector<rclcpp::NetworkFlowEndpoint> & network_flow_endpoints) const |
| 81 | + { |
| 82 | + std::ostringstream stream; |
| 83 | + stream << "{\"networkFlowEndpoints\": ["; |
| 84 | + bool comma_skip = true; |
| 85 | + for (auto network_flow_endpoint : network_flow_endpoints) { |
| 86 | + if (comma_skip) { |
| 87 | + comma_skip = false; |
| 88 | + } else { |
| 89 | + stream << ","; |
| 90 | + } |
| 91 | + stream << network_flow_endpoint; |
| 92 | + } |
| 93 | + stream << "]}"; |
| 94 | + RCLCPP_INFO( |
| 95 | + this->get_logger(), "%s", |
| 96 | + stream.str().c_str()); |
| 97 | + } |
| 98 | + rclcpp::TimerBase::SharedPtr timer_1_; |
| 99 | + rclcpp::TimerBase::SharedPtr timer_2_; |
| 100 | + rclcpp::Publisher<std_msgs::msg::String>::SharedPtr publisher_1_; |
| 101 | + rclcpp::Publisher<std_msgs::msg::String>::SharedPtr publisher_2_; |
| 102 | + size_t count_1_; |
| 103 | + size_t count_2_; |
| 104 | +}; |
| 105 | + |
| 106 | +int main(int argc, char * argv[]) |
| 107 | +{ |
| 108 | + rclcpp::init(argc, argv); |
| 109 | + rclcpp::spin(std::make_shared<MinimalPublisherWithUniqueNetworkFlowEndpoints>()); |
| 110 | + rclcpp::shutdown(); |
| 111 | + return 0; |
| 112 | +} |
0 commit comments