Skip to content

Commit

Permalink
add try&catch statement to unique network flow publisher example. (#313)
Browse files Browse the repository at this point in the history
* add try&catch statement to unique network flow publisher example.

Signed-off-by: Tomoya Fujita <[email protected]>
  • Loading branch information
fujitatomoya authored May 18, 2021
1 parent fa0c0e3 commit b83b185
Showing 1 changed file with 12 additions and 7 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -42,18 +42,23 @@ class MinimalPublisherWithUniqueNetworkFlowEndpoints : public rclcpp::Node

// 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<std_msgs::msg::String>("topic_2", 10);
timer_2_ = this->create_wall_timer(
1000ms, std::bind(&MinimalPublisherWithUniqueNetworkFlowEndpoints::timer_2_callback, this));

// 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();
// Catch an exception if implementation does not support get_network_flow_endpoints.
try {
// 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);
// 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_INFO(
this->get_logger(), "%s", e.what());
}
}

private:
Expand Down

0 comments on commit b83b185

Please sign in to comment.