From eccec54f2b5a79670cf8a78068f6acac193ccd50 Mon Sep 17 00:00:00 2001 From: yadunund Date: Sun, 2 Feb 2025 13:59:57 -0800 Subject: [PATCH 1/4] Inform users that peers will not discover and communicate with one another until the router is started (#440) * Inform users that peers will not discover and communicate with one another until the router is started Signed-off-by: Yadunund * Address feedback Signed-off-by: Yadunund --------- Signed-off-by: Yadunund --- rmw_zenoh_cpp/src/detail/rmw_context_impl_s.cpp | 9 +++++++++ 1 file changed, 9 insertions(+) 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 e6198f3a..3e3d0b72 100644 --- a/rmw_zenoh_cpp/src/detail/rmw_context_impl_s.cpp +++ b/rmw_zenoh_cpp/src/detail/rmw_context_impl_s.cpp @@ -111,6 +111,15 @@ class rmw_context_impl_s::Data final : public std::enable_shared_from_this "Have you started a router with `ros2 run rmw_zenoh_cpp rmw_zenohd`?"); } if (++connection_attempts >= configured_connection_attempts.value()) { + RMW_ZENOH_LOG_WARN_NAMED( + "rmw_zenoh_cpp", + "Unable to connect to a Zenoh router after %zu attempt(s). " + "Please ensure that a Zenoh router is running and can be reached. " + "You may increase the number of attempts to check for a router by " + "setting the ZENOH_ROUTER_CHECK_ATTEMPTS environment variable. " + "Proceeding with initialization but other peers will not discover " + "or receive data from peers in this session until a router is started.", + configured_connection_attempts.value()); break; } std::this_thread::sleep_for(sleep_time); From d322d6f4d86339a4dc041728ad98e11a6dd855e0 Mon Sep 17 00:00:00 2001 From: Julien Enoch Date: Tue, 4 Feb 2025 21:42:17 +0100 Subject: [PATCH 2/4] Bump Zenoh to commit id e4ea6f0 (1.2.0 + few commits) (#446) * Bump: zenoh-cpp=bd4d741 zenoh-c=15d56e1 zenoh=e17de41 * Config: add new gossip target setting (eclipse-zenoh/zenoh#1678) * Config: add new interests timeout setting (eclipse-zenoh/zenoh#1710) * Config: copy updates from eclipse-zenoh/zenoh#1712 * Config: copy updates from eclipse-zenoh/zenoh#1722 * Config: copy updates from eclipse-zenoh/zenoh#1749 * Config: copy updates from eclipse-zenoh/zenoh#1751 * fix: use the commit 15d56e1 to include the allocation feature * Bump zenoh-c=5fce7fb zenoh=e4ea6f0 (for eclipse-zenoh/zenoh#1754 fixing a routing issue in 1.2.0) * Update documentation for commits and undo style changes Signed-off-by: Yadunund --------- Signed-off-by: Yadunund Co-authored-by: yuanyuyuan Co-authored-by: Yadunund --- .../DEFAULT_RMW_ZENOH_ROUTER_CONFIG.json5 | 49 +++++++++++++------ .../DEFAULT_RMW_ZENOH_SESSION_CONFIG.json5 | 49 +++++++++++++------ zenoh_cpp_vendor/CMakeLists.txt | 17 +++---- 3 files changed, 77 insertions(+), 38 deletions(-) diff --git a/rmw_zenoh_cpp/config/DEFAULT_RMW_ZENOH_ROUTER_CONFIG.json5 b/rmw_zenoh_cpp/config/DEFAULT_RMW_ZENOH_ROUTER_CONFIG.json5 index f100eff6..22c1b2e3 100644 --- a/rmw_zenoh_cpp/config/DEFAULT_RMW_ZENOH_ROUTER_CONFIG.json5 +++ b/rmw_zenoh_cpp/config/DEFAULT_RMW_ZENOH_ROUTER_CONFIG.json5 @@ -135,11 +135,11 @@ /// Accepts a single value (e.g. autoconnect: ["router", "peer"]) /// or different values for router, peer and client (e.g. autoconnect: { router: [], peer: ["router", "peer"] }). /// Each value is a list of: "peer", "router" and/or "client". - autoconnect: { router: [], peer: ["router", "peer"] }, + autoconnect: { router: [], peer: ["router", "peer"], client: ["router"] }, /// Whether or not to listen for scout messages on UDP multicast and reply to them. listen: true, }, - /// The gossip scouting configuration. + /// The gossip scouting configuration. Note that instances in "client" mode do not participate in gossip. gossip: { /// Whether gossip scouting is enabled or not enabled: true, @@ -149,10 +149,17 @@ /// It mostly makes sense when using "linkstate" routing mode where all nodes in the subsystem don't have /// direct connectivity with each other. multihop: false, + /// Which type of Zenoh instances to send gossip messages to. + /// Accepts a single value (e.g. target: ["router", "peer"]) which applies whatever the configured "mode" is, + /// or different values for router or peer mode (e.g. target: { router: ["router", "peer"], peer: ["router"] }). + /// Each value is a list of "peer" and/or "router". + /// ROS setting: by default all peers rely on the router to discover each other. Thus configuring the peer to send gossip + /// messages only to the router is sufficient and avoids unecessary traffic between Nodes at launch time. + target: { router: ["router", "peer"], peer: ["router"]}, /// Which type of Zenoh instances to automatically establish sessions with upon discovery on gossip. /// Accepts a single value (e.g. autoconnect: ["router", "peer"]) - /// or different values for router, peer and client (e.g. autoconnect: { router: [], peer: ["router", "peer"] }). - /// Each value is a list of: "peer", "router" and/or "client". + /// or different values for router or peer mode (e.g. autoconnect: { router: [], peer: ["router", "peer"] }). + /// Each value is a list of: "peer" and/or "router". autoconnect: { router: [], peer: ["router", "peer"] }, }, }, @@ -191,6 +198,14 @@ /// The routing strategy to use in peers. ("peer_to_peer" or "linkstate"). mode: "peer_to_peer", }, + /// The interests-based routing configuration. + /// This configuration applies regardless of the mode (router, peer or client). + interests: { + /// The timeout to wait for incoming interests declarations in milliseconds. + /// The expiration of this timeout implies that the discovery protocol might be incomplete, + /// leading to potential loss of messages, queries or liveliness tokens. + timeout: 10000, + }, }, // /// Overwrite QoS options for Zenoh messages by key expression (ignores Zenoh API QoS config for overwritten values) @@ -343,11 +358,11 @@ open_timeout: 10000, /// Timeout in milliseconds when accepting a link accept_timeout: 10000, - /// Maximum number of zenoh session in pending state while accepting + /// Maximum number of links in pending state while performing the handshake for accepting it accept_pending: 100, - /// Maximum number of sessions that can be simultaneously alive + /// Maximum number of transports that can be simultaneously alive for a single zenoh sessions max_sessions: 1000, - /// Maximum number of incoming links that are admitted per session + /// Maximum number of incoming links that are admitted per transport max_links: 1, /// Enables the LowLatency transport /// This option does not make LowLatency transport mandatory, the actual implementation of transport @@ -429,14 +444,14 @@ /// then amount of memory being allocated for each queue is SIZE_XXX * LINK_MTU. /// If qos is false, then only the DATA priority will be allocated. size: { - control: 1, - real_time: 1, - interactive_high: 1, - interactive_low: 1, + control: 2, + real_time: 2, + interactive_high: 2, + interactive_low: 2, data_high: 2, - data: 4, - data_low: 4, - background: 4, + data: 2, + data_low: 2, + background: 2, }, /// Congestion occurs when the queue is empty (no available batch). congestion_control: { @@ -464,6 +479,12 @@ /// The maximum time limit (in ms) a message should be retained for batching when back-pressure happens. time_limit: 1, }, + allocation: { + /// Mode for memory allocation of batches in the priority queues. + /// - "init": batches are allocated at queue initialization time. + /// - "lazy": batches are allocated when needed up to the maximum number of batches configured in the size configuration parameter. + mode: "lazy", + }, }, }, /// Configure the zenoh RX parameters of a link diff --git a/rmw_zenoh_cpp/config/DEFAULT_RMW_ZENOH_SESSION_CONFIG.json5 b/rmw_zenoh_cpp/config/DEFAULT_RMW_ZENOH_SESSION_CONFIG.json5 index eea7c67d..ef38e538 100644 --- a/rmw_zenoh_cpp/config/DEFAULT_RMW_ZENOH_SESSION_CONFIG.json5 +++ b/rmw_zenoh_cpp/config/DEFAULT_RMW_ZENOH_SESSION_CONFIG.json5 @@ -140,11 +140,11 @@ /// Accepts a single value (e.g. autoconnect: ["router", "peer"]) /// or different values for router, peer and client (e.g. autoconnect: { router: [], peer: ["router", "peer"] }). /// Each value is a list of: "peer", "router" and/or "client". - autoconnect: { router: [], peer: ["router", "peer"] }, + autoconnect: { router: [], peer: ["router", "peer"], client: ["router"] }, /// Whether or not to listen for scout messages on UDP multicast and reply to them. listen: true, }, - /// The gossip scouting configuration. + /// The gossip scouting configuration. Note that instances in "client" mode do not participate in gossip. gossip: { /// Whether gossip scouting is enabled or not enabled: true, @@ -154,10 +154,17 @@ /// It mostly makes sense when using "linkstate" routing mode where all nodes in the subsystem don't have /// direct connectivity with each other. multihop: false, + /// Which type of Zenoh instances to send gossip messages to. + /// Accepts a single value (e.g. target: ["router", "peer"]) which applies whatever the configured "mode" is, + /// or different values for router or peer mode (e.g. target: { router: ["router", "peer"], peer: ["router"] }). + /// Each value is a list of "peer" and/or "router". + /// ROS setting: by default all peers rely on the router to discover each other. Thus configuring the peer to send gossip + /// messages only to the router is sufficient and avoids unecessary traffic between Nodes at launch time. + target: { router: ["router", "peer"], peer: ["router"]}, /// Which type of Zenoh instances to automatically establish sessions with upon discovery on gossip. /// Accepts a single value (e.g. autoconnect: ["router", "peer"]) - /// or different values for router, peer and client (e.g. autoconnect: { router: [], peer: ["router", "peer"] }). - /// Each value is a list of: "peer", "router" and/or "client". + /// or different values for router or peer mode (e.g. autoconnect: { router: [], peer: ["router", "peer"] }). + /// Each value is a list of: "peer" and/or "router". autoconnect: { router: [], peer: ["router", "peer"] }, }, }, @@ -194,6 +201,14 @@ /// The routing strategy to use in peers. ("peer_to_peer" or "linkstate"). mode: "peer_to_peer", }, + /// The interests-based routing configuration. + /// This configuration applies regardless of the mode (router, peer or client). + interests: { + /// The timeout to wait for incoming interests declarations in milliseconds. + /// The expiration of this timeout implies that the discovery protocol might be incomplete, + /// leading to potential loss of messages, queries or liveliness tokens. + timeout: 10000, + }, }, // /// Overwrite QoS options for Zenoh messages by key expression (ignores Zenoh API QoS config for overwritten values) @@ -346,11 +361,11 @@ open_timeout: 10000, /// Timeout in milliseconds when accepting a link accept_timeout: 10000, - /// Maximum number of zenoh session in pending state while accepting + /// Maximum number of links in pending state while performing the handshake for accepting it accept_pending: 100, - /// Maximum number of sessions that can be simultaneously alive + /// Maximum number of transports that can be simultaneously alive for a single zenoh sessions max_sessions: 1000, - /// Maximum number of incoming links that are admitted per session + /// Maximum number of incoming links that are admitted per transport max_links: 1, /// Enables the LowLatency transport /// This option does not make LowLatency transport mandatory, the actual implementation of transport @@ -432,14 +447,14 @@ /// then amount of memory being allocated for each queue is SIZE_XXX * LINK_MTU. /// If qos is false, then only the DATA priority will be allocated. size: { - control: 1, - real_time: 1, - interactive_high: 1, - interactive_low: 1, + control: 2, + real_time: 2, + interactive_high: 2, + interactive_low: 2, data_high: 2, - data: 4, - data_low: 4, - background: 4, + data: 2, + data_low: 2, + background: 2, }, /// Congestion occurs when the queue is empty (no available batch). congestion_control: { @@ -467,6 +482,12 @@ /// The maximum time limit (in ms) a message should be retained for batching when back-pressure happens. time_limit: 1, }, + allocation: { + /// Mode for memory allocation of batches in the priority queues. + /// - "init": batches are allocated at queue initialization time. + /// - "lazy": batches are allocated when needed up to the maximum number of batches configured in the size configuration parameter. + mode: "lazy", + }, }, }, /// Configure the zenoh RX parameters of a link diff --git a/zenoh_cpp_vendor/CMakeLists.txt b/zenoh_cpp_vendor/CMakeLists.txt index 75a5ee2f..ec04e52d 100644 --- a/zenoh_cpp_vendor/CMakeLists.txt +++ b/zenoh_cpp_vendor/CMakeLists.txt @@ -17,14 +17,14 @@ find_package(ament_cmake_vendor_package REQUIRED) # when expanded. set(ZENOHC_CARGO_FLAGS "--no-default-features$--features=shared-memory zenoh/transport_compression zenoh/transport_tcp zenoh/transport_tls") -# Set VCS_VERSION to include latest changes from zenoh/zenoh-c to benefit from : -# - https://github.com/eclipse-zenoh/zenoh/pull/1685 (Fix deadlock in advanced subscription undeclaration) -# - https://github.com/eclipse-zenoh/zenoh/pull/1696 (Fix SHM Garbage Collection (GC) policy) -# - https://github.com/eclipse-zenoh/zenoh/pull/1708 (Fix gossip with TLS endpoints) -# - https://github.com/eclipse-zenoh/zenoh/pull/1717 (Improve performance of a large number of peers) +# Set VCS_VERSION to include latest changes from zenoh/zenoh-c/zenoh-cpp to benefit from : +# - https://github.com/eclipse-zenoh/zenoh/pull/173 (Improve config to support priorities range in locators) +# - https://github.com/eclipse-zenoh/zenoh/pull/1736, https://github.com/eclipse-zenoh/zenoh/pull/1735, +# https://github.com/eclipse-zenoh/zenoh/pull/1744, https://github.com/eclipse-zenoh/zenoh/pull/1749, +# https://github.com/eclipse-zenoh/zenoh/pull/1751 (Improve performance of a large number of peers) ament_vendor(zenoh_c_vendor VCS_URL https://github.com/eclipse-zenoh/zenoh-c.git - VCS_VERSION 328736fe9bb9b654b1d9f47eecfc6d52f0d7d587 + VCS_VERSION 5fce7fb1d397e016ad02a50bde4262007d755424 CMAKE_ARGS "-DZENOHC_CARGO_FLAGS=${ZENOHC_CARGO_FLAGS}" "-DZENOHC_BUILD_WITH_UNSTABLE_API=TRUE" @@ -33,12 +33,9 @@ ament_vendor(zenoh_c_vendor ament_export_dependencies(zenohc) -# Set VCS_VERSION to include latest changes from zenoh-cpp to benefit from : -# - https://github.com/eclipse-zenoh/zenoh-cpp/pull/342 (Fix include what you use) -# - https://github.com/eclipse-zenoh/zenoh-cpp/pull/363 (Fix memory leak in string deserialization) ament_vendor(zenoh_cpp_vendor VCS_URL https://github.com/eclipse-zenoh/zenoh-cpp - VCS_VERSION bbfef04e843289aae70b5aa060a925e8ee5b1b6f + VCS_VERSION bd4d741c6c4fa6509d8d745e22c3c50b4306bd65 CMAKE_ARGS -DZENOHCXX_ZENOHC=OFF ) From 05ac638292f80c7750a9e57da60629bb6baaeb18 Mon Sep 17 00:00:00 2001 From: Yadunund Date: Tue, 4 Feb 2025 21:39:30 +0000 Subject: [PATCH 3/4] Update changelogs Signed-off-by: Yadunund --- rmw_zenoh_cpp/CHANGELOG.rst | 15 ++++++++++++++- zenoh_cpp_vendor/CHANGELOG.rst | 7 +++++++ 2 files changed, 21 insertions(+), 1 deletion(-) diff --git a/rmw_zenoh_cpp/CHANGELOG.rst b/rmw_zenoh_cpp/CHANGELOG.rst index 8c278abf..e6d780ad 100644 --- a/rmw_zenoh_cpp/CHANGELOG.rst +++ b/rmw_zenoh_cpp/CHANGELOG.rst @@ -2,7 +2,20 @@ Changelog for package rmw_zenoh_cpp ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +Forthcoming +----------- +* Bump Zenoh to commit id e4ea6f0 (1.2.0 + few commits) (`#446 `_) +* Inform users that peers will not discover and communicate with one another until the router is started (`#440 `_) +* Clear the error after rmw_serialized_message_resize() (`#435 `_) +* Fix `ZENOH_ROUTER_CHECK_ATTEMPTS` which was not respected (`#427 `_) +* fix: use the default destructor to drop the member `Payload` (`#419 `_) +* Remove `gid_hash\_` from `AttachmentData` (`#416 `_) +* Sync the config with the default config in Zenoh. (`#396 `_) +* fix: check the context validity before accessing the session (`#403 `_) +* Fix wan't typo (`#400 `_) +* Contributors: ChenYing Kuo (CY), Chris Lalancette, Julien Enoch, Mahmoud Mazouz, Tim Clephas, Yuyuan Yuan, Yadunund + 0.3.0 (2025-01-02) ------------------ * An alternative middleware for ROS 2 based on Zenoh. -* Contributors: Alejandro Hernández Cordero, Alex Day, Bernd Pfrommer, ChenYing Kuo (CY), Chris Lalancette, Christophe Bedard, CihatAltiparmak, Esteve Fernandez, Franco Cipollone, Geoffrey Biggs, Hans-Martin, James Mount, Julien Enoch, Morgan Quigley, Nate Koenig, Shivang Vijay, Yadunund, Yuyuan Yuan, methylDragon \ No newline at end of file +* Contributors: Alejandro Hernández Cordero, Alex Day, Bernd Pfrommer, ChenYing Kuo (CY), Chris Lalancette, Christophe Bedard, CihatAltiparmak, Esteve Fernandez, Franco Cipollone, Geoffrey Biggs, Hans-Martin, James Mount, Julien Enoch, Morgan Quigley, Nate Koenig, Shivang Vijay, Yadunund, Yuyuan Yuan, methylDragon diff --git a/zenoh_cpp_vendor/CHANGELOG.rst b/zenoh_cpp_vendor/CHANGELOG.rst index bda2657b..6d214a55 100644 --- a/zenoh_cpp_vendor/CHANGELOG.rst +++ b/zenoh_cpp_vendor/CHANGELOG.rst @@ -2,6 +2,13 @@ Changelog for package zenoh_cpp_vendor ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +Forthcoming +----------- +* Bump Zenoh to commit id e4ea6f0 (1.2.0 + few commits) (`#446 `_) +* Bump zenoh-c and zenoh-cpp to 1.1.1 (`#424 `_) +* Update Zenoh version (`#405 `_) +* Contributors: ChenYing Kuo (CY), Julien Enoch, Yuyuan Yuan, Yadunund + 0.3.0 (2025-01-02) ------------------ * Vendors zenoh-cpp for rmw_zenoh. From 2e43a482ce82a475f4b561f0722bdbe7becd18c3 Mon Sep 17 00:00:00 2001 From: Yadunund Date: Tue, 4 Feb 2025 21:39:44 +0000 Subject: [PATCH 4/4] 0.3.1 --- rmw_zenoh_cpp/CHANGELOG.rst | 4 ++-- rmw_zenoh_cpp/package.xml | 2 +- zenoh_cpp_vendor/CHANGELOG.rst | 4 ++-- zenoh_cpp_vendor/package.xml | 2 +- 4 files changed, 6 insertions(+), 6 deletions(-) diff --git a/rmw_zenoh_cpp/CHANGELOG.rst b/rmw_zenoh_cpp/CHANGELOG.rst index e6d780ad..05f8066d 100644 --- a/rmw_zenoh_cpp/CHANGELOG.rst +++ b/rmw_zenoh_cpp/CHANGELOG.rst @@ -2,8 +2,8 @@ Changelog for package rmw_zenoh_cpp ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ -Forthcoming ------------ +0.3.1 (2025-02-04) +------------------ * Bump Zenoh to commit id e4ea6f0 (1.2.0 + few commits) (`#446 `_) * Inform users that peers will not discover and communicate with one another until the router is started (`#440 `_) * Clear the error after rmw_serialized_message_resize() (`#435 `_) diff --git a/rmw_zenoh_cpp/package.xml b/rmw_zenoh_cpp/package.xml index e8b4288a..33305d52 100644 --- a/rmw_zenoh_cpp/package.xml +++ b/rmw_zenoh_cpp/package.xml @@ -2,7 +2,7 @@ rmw_zenoh_cpp - 0.3.0 + 0.3.1 A ROS 2 middleware implementation using zenoh-cpp Yadunund diff --git a/zenoh_cpp_vendor/CHANGELOG.rst b/zenoh_cpp_vendor/CHANGELOG.rst index 6d214a55..efe8f889 100644 --- a/zenoh_cpp_vendor/CHANGELOG.rst +++ b/zenoh_cpp_vendor/CHANGELOG.rst @@ -2,8 +2,8 @@ Changelog for package zenoh_cpp_vendor ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ -Forthcoming ------------ +0.3.1 (2025-02-04) +------------------ * Bump Zenoh to commit id e4ea6f0 (1.2.0 + few commits) (`#446 `_) * Bump zenoh-c and zenoh-cpp to 1.1.1 (`#424 `_) * Update Zenoh version (`#405 `_) diff --git a/zenoh_cpp_vendor/package.xml b/zenoh_cpp_vendor/package.xml index 7fa1ac67..f034dcd7 100644 --- a/zenoh_cpp_vendor/package.xml +++ b/zenoh_cpp_vendor/package.xml @@ -2,7 +2,7 @@ zenoh_cpp_vendor - 0.3.0 + 0.3.1 Vendor pkg to install zenoh-cpp Yadunund Apache License 2.0