From 589993ae88800f5de2264be4825c5d82db242f18 Mon Sep 17 00:00:00 2001 From: Julien Enoch Date: Fri, 17 Jan 2025 17:28:27 +0100 Subject: [PATCH] Fix `ZENOH_ROUTER_CHECK_ATTEMPTS` which was not respected (#427) * Fix check of connection to a router * README: update ZENOH_ROUTER_CHECK_ATTEMPTS following default value change in #308 (cherry picked from commit 6f910bf06f1edf10990a3cef9a62d6075a8d7a3f) --- README.md | 12 ++++++++---- rmw_zenoh_cpp/src/detail/rmw_context_impl_s.cpp | 4 ++-- 2 files changed, 10 insertions(+), 6 deletions(-) diff --git a/README.md b/README.md index f9d883b1..fa6cdc3e 100644 --- a/README.md +++ b/README.md @@ -83,11 +83,15 @@ The `ZENOH_ROUTER_CHECK_ATTEMPTS` environment variable can be used to configure The behavior is explained in the table below. -| ZENOH_ROUTER_CHECK_ATTEMPTS | Session behavior | -|:---------------------------:|:----------------------------------------------------------------------------------------------------------------:| -| unset or 0 | Indefinitely waits for connection to a Zenoh router. | -| < 0 | Skips Zenoh router check. | +| ZENOH_ROUTER_CHECK_ATTEMPTS | Session behavior | +|:---------------------------:|:------------------------------------------------------------------------------------------------------------------:| +| 0 | Indefinitely waits for connection to a Zenoh router. | +| < 0 | Skips Zenoh router check. | | > 0 | Attempts to connect to a Zenoh router in `ZENOH_ROUTER_CHECK_ATTEMPTS` attempts with 1 second wait between checks. | +| unset | Equivalent to `1`: the check is made only once. | + +If after the configured number of attempts the Node is still not connected to a `Zenoh router`, the initialisation goes on anyway. +If a `Zenoh router` is started after initialization phase, the Node will automatically connect to it, and autoconnect to other Nodes if gossip scouting is enabled (true with default configuratiuon). ### Session and Router configs `rmw_zenoh` relies on separate configurations files to configure the `Zenoh router` and `Zenoh session` respectively. 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 61dd9c8b..e6198f3a 100644 --- a/rmw_zenoh_cpp/src/detail/rmw_context_impl_s.cpp +++ b/rmw_zenoh_cpp/src/detail/rmw_context_impl_s.cpp @@ -100,8 +100,8 @@ class rmw_context_impl_s::Data final : public std::enable_shared_from_this constexpr int64_t ticks_between_print(std::chrono::milliseconds(1000) / sleep_time); do { zenoh::ZResult result; - this->session_->get_routers_z_id(&result); - if (result == Z_OK) { + const auto zids = this->session_->get_routers_z_id(&result); + if (result == Z_OK && !zids.empty()) { break; } if ((connection_attempts % ticks_between_print) == 0) {