From 3d771c87d4adaf15c3304286e69f15a8e98258c3 Mon Sep 17 00:00:00 2001 From: Chris Lalancette Date: Tue, 19 Nov 2024 07:44:34 -0500 Subject: [PATCH] Don't block in rmw_init checking for the router. (#308) * Don't block in rmw_init checking for the router. It is much cleaner to just have rmw_init return without looping, so we switch to only checking for the router without waiting. However, if we don't find a router, warn the user. It still works to start a publisher and subscription, then start the router; they'll connect at that point. Signed-off-by: Chris Lalancette --- .../src/detail/rmw_context_impl_s.cpp | 25 +++++++++---------- rmw_zenoh_cpp/src/detail/zenoh_config.cpp | 8 +++--- .../src/detail/zenoh_router_check.cpp | 11 +++----- 3 files changed, 19 insertions(+), 25 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..0215a490 100644 --- a/rmw_zenoh_cpp/src/detail/rmw_context_impl_s.cpp +++ b/rmw_zenoh_cpp/src/detail/rmw_context_impl_s.cpp @@ -94,25 +94,24 @@ class rmw_context_impl_s::Data final z_close(z_move(session_)); }); - // TODO(Yadunund) Move this check into a separate thread. // Verify if the zenoh router is running if configured. const std::optional configured_connection_attempts = rmw_zenoh_cpp::zenoh_router_check_attempts(); if (configured_connection_attempts.has_value()) { - ret = RMW_RET_ERROR; uint64_t connection_attempts = 0; - // Retry until the connection is successful. - while (ret != RMW_RET_OK && connection_attempts < configured_connection_attempts.value()) { - if ((ret = rmw_zenoh_cpp::zenoh_router_check(z_loan(session_))) != RMW_RET_OK) { - ++connection_attempts; + constexpr std::chrono::milliseconds sleep_time(1000); + constexpr int64_t ticks_between_print(std::chrono::milliseconds(1000) / sleep_time); + while ((ret = rmw_zenoh_cpp::zenoh_router_check(z_loan(session_))) != RMW_RET_OK) { + if ((connection_attempts % ticks_between_print) == 0) { + RMW_ZENOH_LOG_WARN_NAMED( + "rmw_zenoh_cpp", + "Unable to connect to a Zenoh router. " + "Have you started a router with `ros2 run rmw_zenoh_cpp rmw_zenohd`?"); } - std::this_thread::sleep_for(std::chrono::milliseconds(100)); - } - if (ret != RMW_RET_OK) { - throw std::runtime_error( - "Unable to connect to a Zenoh router after " + - std::to_string(configured_connection_attempts.value()) + - " retries."); + if (++connection_attempts >= configured_connection_attempts.value()) { + break; + } + std::this_thread::sleep_for(sleep_time); } } diff --git a/rmw_zenoh_cpp/src/detail/zenoh_config.cpp b/rmw_zenoh_cpp/src/detail/zenoh_config.cpp index 5cb29172..6d296a62 100644 --- a/rmw_zenoh_cpp/src/detail/zenoh_config.cpp +++ b/rmw_zenoh_cpp/src/detail/zenoh_config.cpp @@ -100,8 +100,8 @@ rmw_ret_t get_z_config(const ConfigurableEntity & entity, z_owned_config_t * con std::optional zenoh_router_check_attempts() { const char * envar_value; - // The default value is to check indefinitely. - uint64_t default_value = std::numeric_limits::max(); + // The default is to check only once. + uint64_t default_value = 1; if (NULL != rcutils_get_env(router_check_attempts_envar, &envar_value)) { // NULL is returned if everything is ok. @@ -120,10 +120,10 @@ std::optional zenoh_router_check_attempts() return std::nullopt; } // If the value is 0, check indefinitely. - return default_value; + return std::numeric_limits::max(); } - // If unset, check indefinitely. + // If unset, use the default. return default_value; } } // namespace rmw_zenoh_cpp diff --git a/rmw_zenoh_cpp/src/detail/zenoh_router_check.cpp b/rmw_zenoh_cpp/src/detail/zenoh_router_check.cpp index ead5ca5a..7d7afaa9 100644 --- a/rmw_zenoh_cpp/src/detail/zenoh_router_check.cpp +++ b/rmw_zenoh_cpp/src/detail/zenoh_router_check.cpp @@ -42,23 +42,18 @@ rmw_ret_t zenoh_router_check(z_session_t session) (*(static_cast(ctx)))++; }; - rmw_ret_t ret = RMW_RET_OK; z_owned_closure_zid_t router_callback = z_closure(callback, nullptr /* drop */, &context); if (z_info_routers_zid(session, z_move(router_callback))) { RMW_ZENOH_LOG_ERROR_NAMED( "rmw_zenoh_cpp", "Failed to evaluate if Zenoh routers are connected to the session."); - ret = RMW_RET_ERROR; + return RMW_RET_ERROR; } else { if (context == 0) { - RMW_ZENOH_LOG_ERROR_NAMED( - "rmw_zenoh_cpp", - "Unable to connect to a Zenoh router. " - "Have you started a router with `ros2 run rmw_zenoh_cpp rmw_zenohd`?"); - ret = RMW_RET_ERROR; + return RMW_RET_ERROR; } } - return ret; + return RMW_RET_OK; } } // namespace rmw_zenoh_cpp