From 93feca13ebaa4d44c41593ad6e3beeb791f94611 Mon Sep 17 00:00:00 2001 From: Ananya Muddukrishna Date: Tue, 8 Dec 2020 13:27:10 +0100 Subject: [PATCH 1/6] Demonstrate unique network flows feature Signed-off-by: Ananya Muddukrishna --- .../topics/minimal_publisher/CMakeLists.txt | 4 + ...mber_function_with_unique_network_flow.cpp | 121 ++++++++++++++++++ .../topics/minimal_subscriber/CMakeLists.txt | 4 + ...mber_function_with_unique_network_flow.cpp | 110 ++++++++++++++++ 4 files changed, 239 insertions(+) create mode 100644 rclcpp/topics/minimal_publisher/member_function_with_unique_network_flow.cpp create mode 100644 rclcpp/topics/minimal_subscriber/member_function_with_unique_network_flow.cpp diff --git a/rclcpp/topics/minimal_publisher/CMakeLists.txt b/rclcpp/topics/minimal_publisher/CMakeLists.txt index caea7b49..3221ee81 100644 --- a/rclcpp/topics/minimal_publisher/CMakeLists.txt +++ b/rclcpp/topics/minimal_publisher/CMakeLists.txt @@ -20,12 +20,16 @@ ament_target_dependencies(publisher_lambda rclcpp std_msgs) add_executable(publisher_member_function member_function.cpp) ament_target_dependencies(publisher_member_function rclcpp std_msgs) +add_executable(publisher_member_function_with_unique_network_flow member_function_with_unique_network_flow.cpp) +ament_target_dependencies(publisher_member_function_with_unique_network_flow rclcpp std_msgs) + add_executable(publisher_not_composable not_composable.cpp) ament_target_dependencies(publisher_not_composable rclcpp std_msgs) install(TARGETS publisher_lambda publisher_member_function + publisher_member_function_with_unique_network_flow publisher_not_composable DESTINATION lib/${PROJECT_NAME} ) diff --git a/rclcpp/topics/minimal_publisher/member_function_with_unique_network_flow.cpp b/rclcpp/topics/minimal_publisher/member_function_with_unique_network_flow.cpp new file mode 100644 index 00000000..9eee65ab --- /dev/null +++ b/rclcpp/topics/minimal_publisher/member_function_with_unique_network_flow.cpp @@ -0,0 +1,121 @@ +// Copyright 2020 Ericsson AB +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include +#include +#include +#include +#include +#include + +#include "rclcpp/rclcpp.hpp" +#include "rclcpp/publisher_options.hpp" +#include "std_msgs/msg/string.hpp" + +using namespace std::chrono_literals; + +class MinimalPublisherWithUniqueNetworkFlow : public rclcpp::Node +{ +public: + MinimalPublisherWithUniqueNetworkFlow() + : Node("minimal_publisher_with_unique_network_flow"), count_1_(0), count_2_(0) + { + // Enable unique network flow via options + auto options_1 = rclcpp::PublisherOptions(); + options_1.unique_network_flow = true; + publisher_1_ = this->create_publisher("topic_1", 10, options_1); + timer_1_ = this->create_wall_timer( + 500ms, std::bind(&MinimalPublisherWithUniqueNetworkFlow::timer_1_callback, this)); + + // Unique network flow is disabled by default + auto options_2 = rclcpp::PublisherOptions(); + publisher_2_ = this->create_publisher("topic_2", 10); + timer_2_ = this->create_wall_timer( + 1000ms, std::bind(&MinimalPublisherWithUniqueNetworkFlow::timer_2_callback, this)); + + // Print network flows and check for uniqueness + auto network_flows_1 = publisher_1_->get_network_flow(); + auto network_flows_2 = publisher_2_->get_network_flow(); + print_network_flows(network_flows_1); + print_network_flows(network_flows_2); + if (!are_network_flows_unique(network_flows_1, network_flows_2)) { + RCLCPP_ERROR(this->get_logger(), "Network flows across publishers are not unique"); + } + } + +private: + void timer_1_callback() + { + auto message = std_msgs::msg::String(); + message.data = "Hello, world! " + std::to_string(count_1_++); + + RCLCPP_INFO( + this->get_logger(), "Publishing: '%s'", message.data.c_str()); + publisher_1_->publish(message); + } + void timer_2_callback() + { + auto message = std_msgs::msg::String(); + message.data = "Hej, världen! " + std::to_string(count_2_++); + + RCLCPP_INFO( + this->get_logger(), "Publishing: '%s'", message.data.c_str()); + publisher_2_->publish(message); + } + /// Compare network flows + /* + * Compare two network flows + * \return false if network flows are not unique true otherwise + */ + bool are_network_flows_unique( + const std::vector & network_flows_1, + const std::vector & network_flows_2) const + { + if (network_flows_1.size() > 0 && network_flows_2.size() > 0) { + for (auto network_flow_1 : network_flows_1) { + for (auto network_flow_2 : network_flows_2) { + if (network_flow_1 == network_flow_2) { + return false; + } + } + } + } + return true; + } + /// Print network flows + void print_network_flows(const std::vector & network_flows) const + { + std::ostringstream stream; + for (auto network_flow : network_flows) { + stream << network_flow << ", "; + } + RCLCPP_INFO( + this->get_logger(), "Publisher created with network flows: '%s'", + stream.str().c_str()); + } + rclcpp::TimerBase::SharedPtr timer_1_; + rclcpp::TimerBase::SharedPtr timer_2_; + rclcpp::Publisher::SharedPtr publisher_1_; + rclcpp::Publisher::SharedPtr publisher_2_; + size_t count_1_; + size_t count_2_; +}; + +int main(int argc, char * argv[]) +{ + rclcpp::init(argc, argv); + rclcpp::spin(std::make_shared()); + rclcpp::shutdown(); + return 0; +} diff --git a/rclcpp/topics/minimal_subscriber/CMakeLists.txt b/rclcpp/topics/minimal_subscriber/CMakeLists.txt index 96484555..b9ef6a89 100644 --- a/rclcpp/topics/minimal_subscriber/CMakeLists.txt +++ b/rclcpp/topics/minimal_subscriber/CMakeLists.txt @@ -23,6 +23,9 @@ ament_target_dependencies(subscriber_member_function rclcpp std_msgs) add_executable(subscriber_member_function_with_topic_statistics member_function_with_topic_statistics.cpp) ament_target_dependencies(subscriber_member_function_with_topic_statistics rclcpp std_msgs) +add_executable(subscriber_member_function_with_unique_network_flow member_function_with_unique_network_flow.cpp) +ament_target_dependencies(subscriber_member_function_with_unique_network_flow rclcpp std_msgs) + add_executable(subscriber_not_composable not_composable.cpp) ament_target_dependencies(subscriber_not_composable rclcpp std_msgs) @@ -30,6 +33,7 @@ install(TARGETS subscriber_lambda subscriber_member_function subscriber_member_function_with_topic_statistics + subscriber_member_function_with_unique_network_flow subscriber_not_composable DESTINATION lib/${PROJECT_NAME}) diff --git a/rclcpp/topics/minimal_subscriber/member_function_with_unique_network_flow.cpp b/rclcpp/topics/minimal_subscriber/member_function_with_unique_network_flow.cpp new file mode 100644 index 00000000..6adc3f2a --- /dev/null +++ b/rclcpp/topics/minimal_subscriber/member_function_with_unique_network_flow.cpp @@ -0,0 +1,110 @@ +// Copyright 2020 Ericsson AB +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + + +#include +#include +#include +#include +#include + +#include "rclcpp/rclcpp.hpp" +#include "rclcpp/subscription_options.hpp" +#include "std_msgs/msg/string.hpp" + +using std::placeholders::_1; + +class MinimalSubscriberWithUniqueNetworkFlow : public rclcpp::Node +{ +public: + MinimalSubscriberWithUniqueNetworkFlow() + : Node("minimal_subscriber_with_unique_network_flow") + { + // Enable unique network flow via options + auto options_1 = rclcpp::SubscriptionOptions(); + options_1.unique_network_flow = true; + + subscription_1_ = this->create_subscription( + "topic_1", 10, std::bind( + &MinimalSubscriberWithUniqueNetworkFlow::topic_1_callback, this, + _1), options_1); + + // Unique network flow is disabled by default + auto options_2 = rclcpp::SubscriptionOptions(); + subscription_2_ = this->create_subscription( + "topic_2", 10, std::bind( + &MinimalSubscriberWithUniqueNetworkFlow::topic_2_callback, this, + _1), options_2); + + // Print network flows and check for uniqueness + auto network_flows_1 = subscription_1_->get_network_flow(); + auto network_flows_2 = subscription_2_->get_network_flow(); + print_network_flows(network_flows_1); + print_network_flows(network_flows_2); + if (!are_network_flows_unique(network_flows_1, network_flows_2)) { + RCLCPP_ERROR(this->get_logger(), "Network flows across subscriptions are not unique"); + } + } + +private: + void topic_1_callback(const std_msgs::msg::String::SharedPtr msg) const + { + RCLCPP_INFO(this->get_logger(), "Topic 1 news: '%s'", msg->data.c_str()); + } + void topic_2_callback(const std_msgs::msg::String::SharedPtr msg) const + { + RCLCPP_INFO(this->get_logger(), "Topic 2 news: '%s'", msg->data.c_str()); + } + /// Compare network flows + /* + * Compare two network flows + * \return false if network flows are not unique true otherwise + */ + bool are_network_flows_unique( + const std::vector & network_flows_1, + const std::vector & network_flows_2) const + { + if (network_flows_1.size() > 0 && network_flows_2.size() > 0) { + for (auto network_flow_1 : network_flows_1) { + for (auto network_flow_2 : network_flows_2) { + if (network_flow_1 == network_flow_2) { + return false; + } + } + } + } + return true; + } + /// Print network flows + void print_network_flows(const std::vector & network_flows) const + { + std::ostringstream stream; + for (auto network_flow : network_flows) { + stream << network_flow << ", "; + } + RCLCPP_INFO( + this->get_logger(), "Subscription created with network flows: '%s'", + stream.str().c_str()); + } + rclcpp::Subscription::SharedPtr subscription_1_; + rclcpp::Subscription::SharedPtr subscription_2_; +}; + +int main(int argc, char * argv[]) +{ + rclcpp::init(argc, argv); + rclcpp::spin(std::make_shared()); + rclcpp::shutdown(); + return 0; +} From d7abc7d31aec73c4a0ff69378f0b259ea7fac654 Mon Sep 17 00:00:00 2001 From: Ananya Muddukrishna Date: Fri, 5 Feb 2021 17:43:49 +0100 Subject: [PATCH 2/6] Use new unique network flow option Signed-off-by: Ananya Muddukrishna --- .../member_function_with_unique_network_flow.cpp | 2 +- .../member_function_with_unique_network_flow.cpp | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/rclcpp/topics/minimal_publisher/member_function_with_unique_network_flow.cpp b/rclcpp/topics/minimal_publisher/member_function_with_unique_network_flow.cpp index 9eee65ab..b6a14d56 100644 --- a/rclcpp/topics/minimal_publisher/member_function_with_unique_network_flow.cpp +++ b/rclcpp/topics/minimal_publisher/member_function_with_unique_network_flow.cpp @@ -33,7 +33,7 @@ class MinimalPublisherWithUniqueNetworkFlow : public rclcpp::Node { // Enable unique network flow via options auto options_1 = rclcpp::PublisherOptions(); - options_1.unique_network_flow = true; + options_1.require_unique_network_flow = RMW_UNIQUE_NETWORK_FLOW_STRICTLY_REQUIRED; publisher_1_ = this->create_publisher("topic_1", 10, options_1); timer_1_ = this->create_wall_timer( 500ms, std::bind(&MinimalPublisherWithUniqueNetworkFlow::timer_1_callback, this)); diff --git a/rclcpp/topics/minimal_subscriber/member_function_with_unique_network_flow.cpp b/rclcpp/topics/minimal_subscriber/member_function_with_unique_network_flow.cpp index 6adc3f2a..bf81c044 100644 --- a/rclcpp/topics/minimal_subscriber/member_function_with_unique_network_flow.cpp +++ b/rclcpp/topics/minimal_subscriber/member_function_with_unique_network_flow.cpp @@ -33,7 +33,7 @@ class MinimalSubscriberWithUniqueNetworkFlow : public rclcpp::Node { // Enable unique network flow via options auto options_1 = rclcpp::SubscriptionOptions(); - options_1.unique_network_flow = true; + options_1.require_unique_network_flow = RMW_UNIQUE_NETWORK_FLOW_STRICTLY_REQUIRED; subscription_1_ = this->create_subscription( "topic_1", 10, std::bind( From a895fc9ff23e10aacf2b4320f591f792b6c2b75f Mon Sep 17 00:00:00 2001 From: Ananya Muddukrishna Date: Fri, 26 Feb 2021 19:03:53 +0100 Subject: [PATCH 3/6] Modify to match renamed API Signed-off-by: Ananya Muddukrishna --- ...mber_function_with_unique_network_flow.cpp | 75 ++++++++--------- ...mber_function_with_unique_network_flow.cpp | 84 ++++++++++--------- 2 files changed, 76 insertions(+), 83 deletions(-) diff --git a/rclcpp/topics/minimal_publisher/member_function_with_unique_network_flow.cpp b/rclcpp/topics/minimal_publisher/member_function_with_unique_network_flow.cpp index b6a14d56..e10ff08f 100644 --- a/rclcpp/topics/minimal_publisher/member_function_with_unique_network_flow.cpp +++ b/rclcpp/topics/minimal_publisher/member_function_with_unique_network_flow.cpp @@ -25,33 +25,35 @@ using namespace std::chrono_literals; -class MinimalPublisherWithUniqueNetworkFlow : public rclcpp::Node +class MinimalPublisherWithUniqueNetworkFlowEndpoints : public rclcpp::Node { public: - MinimalPublisherWithUniqueNetworkFlow() - : Node("minimal_publisher_with_unique_network_flow"), count_1_(0), count_2_(0) + MinimalPublisherWithUniqueNetworkFlowEndpoints() + : Node("minimal_publisher_with_unique_network_flow_endpoints"), count_1_(0), count_2_(0) { - // Enable unique network flow via options + // Create publisher with unique network flow endpoints + // Enable unique network flow endpoints via options auto options_1 = rclcpp::PublisherOptions(); - options_1.require_unique_network_flow = RMW_UNIQUE_NETWORK_FLOW_STRICTLY_REQUIRED; + options_1.require_unique_network_flow_endpoints = + RMW_UNIQUE_NETWORK_FLOW_ENDPOINTS_OPTIONALLY_REQUIRED; publisher_1_ = this->create_publisher("topic_1", 10, options_1); timer_1_ = this->create_wall_timer( - 500ms, std::bind(&MinimalPublisherWithUniqueNetworkFlow::timer_1_callback, this)); + 500ms, std::bind(&MinimalPublisherWithUniqueNetworkFlowEndpoints::timer_1_callback, this)); - // Unique network flow is disabled by default + // Create publisher without unique network flow endpoints + // Unique network flow endpoints are disabled in default options auto options_2 = rclcpp::PublisherOptions(); publisher_2_ = this->create_publisher("topic_2", 10); timer_2_ = this->create_wall_timer( - 1000ms, std::bind(&MinimalPublisherWithUniqueNetworkFlow::timer_2_callback, this)); + 1000ms, std::bind(&MinimalPublisherWithUniqueNetworkFlowEndpoints::timer_2_callback, this)); - // Print network flows and check for uniqueness - auto network_flows_1 = publisher_1_->get_network_flow(); - auto network_flows_2 = publisher_2_->get_network_flow(); - print_network_flows(network_flows_1); - print_network_flows(network_flows_2); - if (!are_network_flows_unique(network_flows_1, network_flows_2)) { - RCLCPP_ERROR(this->get_logger(), "Network flows across publishers are not unique"); - } + // Get network flow endpoints + auto network_flow_endpoints_1 = publisher_1_->get_network_flow_endpoints(); + auto network_flow_endpoints_2 = publisher_2_->get_network_flow_endpoints(); + + // Print network flow endpoints + print_network_flow_endpoints(network_flow_endpoints_1); + print_network_flow_endpoints(network_flow_endpoints_2); } private: @@ -73,35 +75,24 @@ class MinimalPublisherWithUniqueNetworkFlow : public rclcpp::Node this->get_logger(), "Publishing: '%s'", message.data.c_str()); publisher_2_->publish(message); } - /// Compare network flows - /* - * Compare two network flows - * \return false if network flows are not unique true otherwise - */ - bool are_network_flows_unique( - const std::vector & network_flows_1, - const std::vector & network_flows_2) const - { - if (network_flows_1.size() > 0 && network_flows_2.size() > 0) { - for (auto network_flow_1 : network_flows_1) { - for (auto network_flow_2 : network_flows_2) { - if (network_flow_1 == network_flow_2) { - return false; - } - } - } - } - return true; - } - /// Print network flows - void print_network_flows(const std::vector & network_flows) const + /// Print network flow endpoints in JSON-like format + void print_network_flow_endpoints( + const std::vector & network_flow_endpoints) const { std::ostringstream stream; - for (auto network_flow : network_flows) { - stream << network_flow << ", "; + stream << "{\"networkFlowEndpoints\": ["; + bool comma_skip = true; + for (auto network_flow_endpoint : network_flow_endpoints) { + if (comma_skip) { + comma_skip = false; + } else { + stream << ","; + } + stream << network_flow_endpoint; } + stream << "]}"; RCLCPP_INFO( - this->get_logger(), "Publisher created with network flows: '%s'", + this->get_logger(), "%s", stream.str().c_str()); } rclcpp::TimerBase::SharedPtr timer_1_; @@ -115,7 +106,7 @@ class MinimalPublisherWithUniqueNetworkFlow : public rclcpp::Node int main(int argc, char * argv[]) { rclcpp::init(argc, argv); - rclcpp::spin(std::make_shared()); + rclcpp::spin(std::make_shared()); rclcpp::shutdown(); return 0; } diff --git a/rclcpp/topics/minimal_subscriber/member_function_with_unique_network_flow.cpp b/rclcpp/topics/minimal_subscriber/member_function_with_unique_network_flow.cpp index bf81c044..f9f4544c 100644 --- a/rclcpp/topics/minimal_subscriber/member_function_with_unique_network_flow.cpp +++ b/rclcpp/topics/minimal_subscriber/member_function_with_unique_network_flow.cpp @@ -25,36 +25,49 @@ using std::placeholders::_1; -class MinimalSubscriberWithUniqueNetworkFlow : public rclcpp::Node +class MinimalSubscriberWithUniqueNetworkFlowEndpoints : public rclcpp::Node { public: - MinimalSubscriberWithUniqueNetworkFlow() - : Node("minimal_subscriber_with_unique_network_flow") + MinimalSubscriberWithUniqueNetworkFlowEndpoints() + : Node("minimal_subscriber_with_unique_network_flow_endpoints") { - // Enable unique network flow via options + // Create subscription with unique network flow endpoints + // Enable unique network flow endpoints via options auto options_1 = rclcpp::SubscriptionOptions(); - options_1.require_unique_network_flow = RMW_UNIQUE_NETWORK_FLOW_STRICTLY_REQUIRED; + options_1.require_unique_network_flow_endpoints = + RMW_UNIQUE_NETWORK_FLOW_ENDPOINTS_STRICTLY_REQUIRED; subscription_1_ = this->create_subscription( "topic_1", 10, std::bind( - &MinimalSubscriberWithUniqueNetworkFlow::topic_1_callback, this, + &MinimalSubscriberWithUniqueNetworkFlowEndpoints::topic_1_callback, this, _1), options_1); - // Unique network flow is disabled by default + // Create subscription without unique network flow endpoints + // Unique network flow endpoints are disabled by default auto options_2 = rclcpp::SubscriptionOptions(); subscription_2_ = this->create_subscription( "topic_2", 10, std::bind( - &MinimalSubscriberWithUniqueNetworkFlow::topic_2_callback, this, + &MinimalSubscriberWithUniqueNetworkFlowEndpoints::topic_2_callback, this, _1), options_2); - // Print network flows and check for uniqueness - auto network_flows_1 = subscription_1_->get_network_flow(); - auto network_flows_2 = subscription_2_->get_network_flow(); - print_network_flows(network_flows_1); - print_network_flows(network_flows_2); - if (!are_network_flows_unique(network_flows_1, network_flows_2)) { - RCLCPP_ERROR(this->get_logger(), "Network flows across subscriptions are not unique"); + // Get network flow endpoints + auto network_flow_endpoints_1 = subscription_1_->get_network_flow_endpoints(); + auto network_flow_endpoints_2 = subscription_2_->get_network_flow_endpoints(); + + // Check if network flow endpoints are unique + for (auto network_flow_endpoint_1 : network_flow_endpoints_1) { + for (auto network_flow_endpoint_2 : network_flow_endpoints_2) { + if (network_flow_endpoint_1 == network_flow_endpoint_2) { + RCLCPP_ERROR( + this->get_logger(), "Network flow endpoints across subscriptions are not unique"); + break; + } + } } + + // Print network flow endpoints + print_network_flow_endpoints(network_flow_endpoints_1); + print_network_flow_endpoints(network_flow_endpoints_2); } private: @@ -66,35 +79,24 @@ class MinimalSubscriberWithUniqueNetworkFlow : public rclcpp::Node { RCLCPP_INFO(this->get_logger(), "Topic 2 news: '%s'", msg->data.c_str()); } - /// Compare network flows - /* - * Compare two network flows - * \return false if network flows are not unique true otherwise - */ - bool are_network_flows_unique( - const std::vector & network_flows_1, - const std::vector & network_flows_2) const - { - if (network_flows_1.size() > 0 && network_flows_2.size() > 0) { - for (auto network_flow_1 : network_flows_1) { - for (auto network_flow_2 : network_flows_2) { - if (network_flow_1 == network_flow_2) { - return false; - } - } - } - } - return true; - } - /// Print network flows - void print_network_flows(const std::vector & network_flows) const + /// Print network flow endpoints in JSON-like format + void print_network_flow_endpoints( + const std::vector & network_flow_endpoints) const { std::ostringstream stream; - for (auto network_flow : network_flows) { - stream << network_flow << ", "; + stream << "{\"networkFlowEndpoints\": ["; + bool comma_skip = true; + for (auto network_flow_endpoint : network_flow_endpoints) { + if (comma_skip) { + comma_skip = false; + } else { + stream << ","; + } + stream << network_flow_endpoint; } + stream << "]}"; RCLCPP_INFO( - this->get_logger(), "Subscription created with network flows: '%s'", + this->get_logger(), "%s", stream.str().c_str()); } rclcpp::Subscription::SharedPtr subscription_1_; @@ -104,7 +106,7 @@ class MinimalSubscriberWithUniqueNetworkFlow : public rclcpp::Node int main(int argc, char * argv[]) { rclcpp::init(argc, argv); - rclcpp::spin(std::make_shared()); + rclcpp::spin(std::make_shared()); rclcpp::shutdown(); return 0; } From 3a4e8330eb7e4963e2dd627dc874592d0bae8e11 Mon Sep 17 00:00:00 2001 From: Ananya Muddukrishna Date: Fri, 26 Feb 2021 19:23:34 +0100 Subject: [PATCH 4/6] Rename files for consistency Signed-off-by: Ananya Muddukrishna --- ...cpp => member_function_with_unique_network_flow_endpoints.cpp} | 0 ...cpp => member_function_with_unique_network_flow_endpoints.cpp} | 0 2 files changed, 0 insertions(+), 0 deletions(-) rename rclcpp/topics/minimal_publisher/{member_function_with_unique_network_flow.cpp => member_function_with_unique_network_flow_endpoints.cpp} (100%) rename rclcpp/topics/minimal_subscriber/{member_function_with_unique_network_flow.cpp => member_function_with_unique_network_flow_endpoints.cpp} (100%) diff --git a/rclcpp/topics/minimal_publisher/member_function_with_unique_network_flow.cpp b/rclcpp/topics/minimal_publisher/member_function_with_unique_network_flow_endpoints.cpp similarity index 100% rename from rclcpp/topics/minimal_publisher/member_function_with_unique_network_flow.cpp rename to rclcpp/topics/minimal_publisher/member_function_with_unique_network_flow_endpoints.cpp diff --git a/rclcpp/topics/minimal_subscriber/member_function_with_unique_network_flow.cpp b/rclcpp/topics/minimal_subscriber/member_function_with_unique_network_flow_endpoints.cpp similarity index 100% rename from rclcpp/topics/minimal_subscriber/member_function_with_unique_network_flow.cpp rename to rclcpp/topics/minimal_subscriber/member_function_with_unique_network_flow_endpoints.cpp From 336ce1d8772a261c1285afcead632bd9bf0839ae Mon Sep 17 00:00:00 2001 From: Ananya Muddukrishna Date: Fri, 26 Feb 2021 19:24:35 +0100 Subject: [PATCH 5/6] Update build configuration Signed-off-by: Ananya Muddukrishna --- rclcpp/topics/minimal_publisher/CMakeLists.txt | 6 +++--- rclcpp/topics/minimal_subscriber/CMakeLists.txt | 6 +++--- 2 files changed, 6 insertions(+), 6 deletions(-) diff --git a/rclcpp/topics/minimal_publisher/CMakeLists.txt b/rclcpp/topics/minimal_publisher/CMakeLists.txt index 3221ee81..305b2f2e 100644 --- a/rclcpp/topics/minimal_publisher/CMakeLists.txt +++ b/rclcpp/topics/minimal_publisher/CMakeLists.txt @@ -20,8 +20,8 @@ ament_target_dependencies(publisher_lambda rclcpp std_msgs) add_executable(publisher_member_function member_function.cpp) ament_target_dependencies(publisher_member_function rclcpp std_msgs) -add_executable(publisher_member_function_with_unique_network_flow member_function_with_unique_network_flow.cpp) -ament_target_dependencies(publisher_member_function_with_unique_network_flow rclcpp std_msgs) +add_executable(publisher_member_function_with_unique_network_flow_endpoints member_function_with_unique_network_flow_endpoints.cpp) +ament_target_dependencies(publisher_member_function_with_unique_network_flow_endpoints rclcpp std_msgs) add_executable(publisher_not_composable not_composable.cpp) ament_target_dependencies(publisher_not_composable rclcpp std_msgs) @@ -29,7 +29,7 @@ ament_target_dependencies(publisher_not_composable rclcpp std_msgs) install(TARGETS publisher_lambda publisher_member_function - publisher_member_function_with_unique_network_flow + publisher_member_function_with_unique_network_flow_endpoints publisher_not_composable DESTINATION lib/${PROJECT_NAME} ) diff --git a/rclcpp/topics/minimal_subscriber/CMakeLists.txt b/rclcpp/topics/minimal_subscriber/CMakeLists.txt index b9ef6a89..4a771c3f 100644 --- a/rclcpp/topics/minimal_subscriber/CMakeLists.txt +++ b/rclcpp/topics/minimal_subscriber/CMakeLists.txt @@ -23,8 +23,8 @@ ament_target_dependencies(subscriber_member_function rclcpp std_msgs) add_executable(subscriber_member_function_with_topic_statistics member_function_with_topic_statistics.cpp) ament_target_dependencies(subscriber_member_function_with_topic_statistics rclcpp std_msgs) -add_executable(subscriber_member_function_with_unique_network_flow member_function_with_unique_network_flow.cpp) -ament_target_dependencies(subscriber_member_function_with_unique_network_flow rclcpp std_msgs) +add_executable(subscriber_member_function_with_unique_network_flow_endpoints member_function_with_unique_network_flow_endpoints.cpp) +ament_target_dependencies(subscriber_member_function_with_unique_network_flow_endpoints rclcpp std_msgs) add_executable(subscriber_not_composable not_composable.cpp) ament_target_dependencies(subscriber_not_composable rclcpp std_msgs) @@ -33,7 +33,7 @@ install(TARGETS subscriber_lambda subscriber_member_function subscriber_member_function_with_topic_statistics - subscriber_member_function_with_unique_network_flow + subscriber_member_function_with_unique_network_flow_endpoints subscriber_not_composable DESTINATION lib/${PROJECT_NAME}) From 2e2233c0dbc87f7df66e23df66ddc0a585857cc2 Mon Sep 17 00:00:00 2001 From: Ananya Muddukrishna Date: Fri, 26 Feb 2021 19:25:26 +0100 Subject: [PATCH 6/6] Catch exception on failure to create subscriber Signed-off-by: Ananya Muddukrishna --- ...ion_with_unique_network_flow_endpoints.cpp | 68 +++++++++++-------- 1 file changed, 38 insertions(+), 30 deletions(-) diff --git a/rclcpp/topics/minimal_subscriber/member_function_with_unique_network_flow_endpoints.cpp b/rclcpp/topics/minimal_subscriber/member_function_with_unique_network_flow_endpoints.cpp index f9f4544c..5a008014 100644 --- a/rclcpp/topics/minimal_subscriber/member_function_with_unique_network_flow_endpoints.cpp +++ b/rclcpp/topics/minimal_subscriber/member_function_with_unique_network_flow_endpoints.cpp @@ -31,43 +31,51 @@ class MinimalSubscriberWithUniqueNetworkFlowEndpoints : public rclcpp::Node MinimalSubscriberWithUniqueNetworkFlowEndpoints() : Node("minimal_subscriber_with_unique_network_flow_endpoints") { - // Create subscription with unique network flow endpoints - // Enable unique network flow endpoints via options - auto options_1 = rclcpp::SubscriptionOptions(); - options_1.require_unique_network_flow_endpoints = - RMW_UNIQUE_NETWORK_FLOW_ENDPOINTS_STRICTLY_REQUIRED; + try { + // Create subscription with unique network flow endpoints + // Enable unique network flow endpoints via options + // Since option is strict, expect exception + auto options_1 = rclcpp::SubscriptionOptions(); + options_1.require_unique_network_flow_endpoints = + RMW_UNIQUE_NETWORK_FLOW_ENDPOINTS_STRICTLY_REQUIRED; - subscription_1_ = this->create_subscription( - "topic_1", 10, std::bind( - &MinimalSubscriberWithUniqueNetworkFlowEndpoints::topic_1_callback, this, - _1), options_1); + subscription_1_ = this->create_subscription( + "topic_1", 10, std::bind( + &MinimalSubscriberWithUniqueNetworkFlowEndpoints::topic_1_callback, this, + _1), options_1); - // Create subscription without unique network flow endpoints - // Unique network flow endpoints are disabled by default - auto options_2 = rclcpp::SubscriptionOptions(); - subscription_2_ = this->create_subscription( - "topic_2", 10, std::bind( - &MinimalSubscriberWithUniqueNetworkFlowEndpoints::topic_2_callback, this, - _1), options_2); + // Create subscription without unique network flow endpoints + // Unique network flow endpoints are disabled by default + auto options_2 = rclcpp::SubscriptionOptions(); + subscription_2_ = this->create_subscription( + "topic_2", 10, std::bind( + &MinimalSubscriberWithUniqueNetworkFlowEndpoints::topic_2_callback, this, + _1), options_2); - // Get network flow endpoints - auto network_flow_endpoints_1 = subscription_1_->get_network_flow_endpoints(); - auto network_flow_endpoints_2 = subscription_2_->get_network_flow_endpoints(); + // Get network flow endpoints + auto network_flow_endpoints_1 = subscription_1_->get_network_flow_endpoints(); + auto network_flow_endpoints_2 = subscription_2_->get_network_flow_endpoints(); - // Check if network flow endpoints are unique - for (auto network_flow_endpoint_1 : network_flow_endpoints_1) { - for (auto network_flow_endpoint_2 : network_flow_endpoints_2) { - if (network_flow_endpoint_1 == network_flow_endpoint_2) { - RCLCPP_ERROR( - this->get_logger(), "Network flow endpoints across subscriptions are not unique"); - break; + // Check if network flow endpoints are unique + for (auto network_flow_endpoint_1 : network_flow_endpoints_1) { + for (auto network_flow_endpoint_2 : network_flow_endpoints_2) { + if (network_flow_endpoint_1 == network_flow_endpoint_2) { + RCLCPP_ERROR( + this->get_logger(), "Network flow endpoints across subscriptions are not unique"); + break; + } } } - } - // Print network flow endpoints - print_network_flow_endpoints(network_flow_endpoints_1); - print_network_flow_endpoints(network_flow_endpoints_2); + // Print network flow endpoints + print_network_flow_endpoints(network_flow_endpoints_1); + print_network_flow_endpoints(network_flow_endpoints_2); + } catch (const rclcpp::exceptions::RCLError & e) { + RCLCPP_ERROR( + this->get_logger(), + "Error: %s", + e.what()); + } } private: