From c62d6549344482369cf3f9c6954e329724a8eba8 Mon Sep 17 00:00:00 2001 From: Chris Lalancette Date: Wed, 13 Nov 2024 19:27:51 +0000 Subject: [PATCH] Don't shutdown contained entities. It is tempting to think of the entities in the RMW graph as a hierarchy, where an rmw_context_t contains zero or more rmw_node_t, and rmw_node_t contains zero or more publishers, subscriptions, clients, and services. However, the reality is that the upper layers (particularly rclcpp and rclpy) don't exactly view the entities like that. More specifically, each entity is considered standalone, that happens to have linkage to other entities in the graph. For example, a publisher is considered to be a standalone entity that happens to be linked to a particular node. Because of this, it is not proper to shutdown all nodes within a context when the context is shutdown. The node should continue to live on until it is shutdown. And a similar argument goes for the node shutdown; it should not shutdown the publishers, subscriptions, clients, and services that are contained within it. This manifested itself as a exception that was being thrown in some of the tests in test_communication. Because it is using a loop with rclcpp::ok(), followed by a publisher->publish(), the test would sometimes throw an exception if Ctrl-C was hit between the rclcpp::ok() and the publish() call. And that's because even though the context has been shut down, the publisher is an independent entity that should continue to exist until the next rclcpp::ok(). The fix here is simple; don't shut "contained" entities down during a context or node shutdown. Signed-off-by: Chris Lalancette --- .../src/detail/rmw_context_impl_s.cpp | 13 ----- rmw_zenoh_cpp/src/detail/rmw_node_data.cpp | 50 ------------------- 2 files changed, 63 deletions(-) diff --git a/rmw_zenoh_cpp/src/detail/rmw_context_impl_s.cpp b/rmw_zenoh_cpp/src/detail/rmw_context_impl_s.cpp index 374af78e..2c47dd3b 100644 --- a/rmw_zenoh_cpp/src/detail/rmw_context_impl_s.cpp +++ b/rmw_zenoh_cpp/src/detail/rmw_context_impl_s.cpp @@ -233,19 +233,6 @@ class rmw_context_impl_s::Data final return ret; } - // Shutdown all the nodes in this context. - for (auto node_it = nodes_.begin(); node_it != nodes_.end(); ++node_it) { - ret = node_it->second->shutdown(); - if (ret != RMW_RET_OK) { - RMW_ZENOH_LOG_ERROR_NAMED( - "rmw_zenoh_cpp", - "Unable to shutdown node with id %zu. rmw_ret_t code: %zu.", - node_it->second->id(), - ret - ); - } - } - z_undeclare_subscriber(z_move(graph_subscriber_)); if (shm_manager_.has_value()) { z_drop(z_move(shm_manager_.value())); diff --git a/rmw_zenoh_cpp/src/detail/rmw_node_data.cpp b/rmw_zenoh_cpp/src/detail/rmw_node_data.cpp index bd3f3f6e..0fabfd95 100644 --- a/rmw_zenoh_cpp/src/detail/rmw_node_data.cpp +++ b/rmw_zenoh_cpp/src/detail/rmw_node_data.cpp @@ -402,56 +402,6 @@ rmw_ret_t NodeData::shutdown() return ret; } - // Shutdown all the entities within this node. - for (auto pub_it = pubs_.begin(); pub_it != pubs_.end(); ++pub_it) { - ret = pub_it->second->shutdown(); - if (ret != RMW_RET_OK) { - RMW_ZENOH_LOG_ERROR_NAMED( - "rmw_zenoh_cpp", - "Unable to shutdown publisher %s within id %zu. rmw_ret_t code: %zu.", - pub_it->second->topic_info().name_.c_str(), - id_, - ret - ); - } - } - for (auto sub_it = subs_.begin(); sub_it != subs_.end(); ++sub_it) { - ret = sub_it->second->shutdown(); - if (ret != RMW_RET_OK) { - RMW_ZENOH_LOG_ERROR_NAMED( - "rmw_zenoh_cpp", - "Unable to shutdown subscription %s within id %zu. rmw_ret_t code: %zu.", - sub_it->second->topic_info().name_.c_str(), - id_, - ret - ); - } - } - for (auto srv_it = services_.begin(); srv_it != services_.end(); ++srv_it) { - ret = srv_it->second->shutdown(); - if (ret != RMW_RET_OK) { - RMW_ZENOH_LOG_ERROR_NAMED( - "rmw_zenoh_cpp", - "Unable to shutdown service %s within id %zu. rmw_ret_t code: %zu.", - srv_it->second->topic_info().name_.c_str(), - id_, - ret - ); - } - } - for (auto cli_it = clients_.begin(); cli_it != clients_.end(); ++cli_it) { - ret = cli_it->second->shutdown(); - if (ret != RMW_RET_OK) { - RMW_ZENOH_LOG_ERROR_NAMED( - "rmw_zenoh_cpp", - "Unable to shutdown client %s within id %zu. rmw_ret_t code: %zu.", - cli_it->second->topic_info().name_.c_str(), - id_, - ret - ); - } - } - // Unregister this node from the ROS graph. zc_liveliness_undeclare_token(z_move(token_));