@@ -42,18 +42,23 @@ class MinimalPublisherWithUniqueNetworkFlowEndpoints : public rclcpp::Node
42
42
43
43
// Create publisher without unique network flow endpoints
44
44
// Unique network flow endpoints are disabled in default options
45
- auto options_2 = rclcpp::PublisherOptions ();
46
45
publisher_2_ = this ->create_publisher <std_msgs::msg::String>(" topic_2" , 10 );
47
46
timer_2_ = this ->create_wall_timer (
48
47
1000ms, std::bind (&MinimalPublisherWithUniqueNetworkFlowEndpoints::timer_2_callback, this ));
49
48
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 ();
49
+ // Catch an exception if implementation does not support get_network_flow_endpoints.
50
+ try {
51
+ // Get network flow endpoints
52
+ auto network_flow_endpoints_1 = publisher_1_->get_network_flow_endpoints ();
53
+ auto network_flow_endpoints_2 = publisher_2_->get_network_flow_endpoints ();
53
54
54
- // Print network flow endpoints
55
- print_network_flow_endpoints (network_flow_endpoints_1);
56
- print_network_flow_endpoints (network_flow_endpoints_2);
55
+ // Print network flow endpoints
56
+ print_network_flow_endpoints (network_flow_endpoints_1);
57
+ print_network_flow_endpoints (network_flow_endpoints_2);
58
+ } catch (const rclcpp::exceptions::RCLError & e) {
59
+ RCLCPP_INFO (
60
+ this ->get_logger (), " %s" , e.what ());
61
+ }
57
62
}
58
63
59
64
private:
0 commit comments