From 6a7a918ea617a9af5486bf37551aed273489bd65 Mon Sep 17 00:00:00 2001 From: Yadunund Date: Sat, 20 Jan 2024 12:42:09 +0800 Subject: [PATCH 1/2] Limit threads per zenoh session Signed-off-by: Yadunund --- .../config/DEFAULT_RMW_ZENOH_SESSION_CONFIG.json5 | 3 +++ zenoh_c_vendor/CMakeLists.txt | 15 +++++++++++++++ 2 files changed, 18 insertions(+) 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 43550e1d..0d8528a2 100644 --- a/rmw_zenoh_cpp/config/DEFAULT_RMW_ZENOH_SESSION_CONFIG.json5 +++ b/rmw_zenoh_cpp/config/DEFAULT_RMW_ZENOH_SESSION_CONFIG.json5 @@ -185,6 +185,9 @@ /// Higher values lead to a more aggressive batching but it will introduce additional latency. backoff: 100, }, + // Number of threads dedicated to transmission + // By default, the number of threads is calculated as follows: 1 + ((#cores - 1) / 4) + threads: 1, }, /// Configure the zenoh RX parameters of a link rx: { diff --git a/zenoh_c_vendor/CMakeLists.txt b/zenoh_c_vendor/CMakeLists.txt index 2240ba87..391f1552 100644 --- a/zenoh_c_vendor/CMakeLists.txt +++ b/zenoh_c_vendor/CMakeLists.txt @@ -10,9 +10,24 @@ endif() find_package(ament_cmake REQUIRED) find_package(ament_cmake_vendor_package REQUIRED) +# Disable default features and only enable tcp transport for zenoh. This reduces +# build time but more importantly allows us to limit the number of threads that +# the zenoh session can spin via the session config as well as the ASYNC_STD_THREAD_COUNT +# environment variable. Without this limit, applications with multiple zenoh sessions can +# encounter system resource errors when trying to create new threads. +# Once zenoh migrates to relying on tokio for its async runtime, we can consider +# removing these flags since with tokio, zenoh can better manage the threads it spins +# with the help of thread pools. +# Note: We separate the two args needed for cargo with "$" and not ";" as the +# latter is a list separater in cmake and hence the string will be split into two +# when expanded. +set(ZENOHC_CARGO_FLAGS "--no-default-features$--features=zenoh/transport_tcp") + ament_vendor(zenoh_c_vendor VCS_URL https://github.com/eclipse-zenoh/zenoh-c.git VCS_VERSION 0.10.1-rc + CMAKE_ARGS + "-DZENOHC_CARGO_FLAGS=${ZENOHC_CARGO_FLAGS}" ) # set(INSTALL_DIR "${CMAKE_CURRENT_BINARY_DIR}/${PROJECT_NAME}-prefix/install") From ec36e0f3304e50a48af81bb45b96d9eff4ae7a52 Mon Sep 17 00:00:00 2001 From: Yadunund Date: Mon, 22 Jan 2024 22:02:04 +0800 Subject: [PATCH 2/2] Limit thread count in router config and add note to configs Signed-off-by: Yadunund --- .../config/DEFAULT_RMW_ZENOH_ROUTER_CONFIG.json5 | 9 ++++++++- .../config/DEFAULT_RMW_ZENOH_SESSION_CONFIG.json5 | 7 +++++++ zenoh_c_vendor/CMakeLists.txt | 3 ++- 3 files changed, 17 insertions(+), 2 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 434de9fe..ac57e00e 100644 --- a/rmw_zenoh_cpp/config/DEFAULT_RMW_ZENOH_ROUTER_CONFIG.json5 +++ b/rmw_zenoh_cpp/config/DEFAULT_RMW_ZENOH_ROUTER_CONFIG.json5 @@ -186,7 +186,14 @@ backoff: 100, // Number of threads dedicated to transmission // By default, the number of threads is calculated as follows: 1 + ((#cores - 1) / 4) - // threads: 4, + // We limit the number of threads that the zenoh session can spin to 1. + // Without this limit, applications with multiple zenoh sessions can + // encounter system resource errors when trying to create new threads. + // Once zenoh migrates to relying on tokio for its async runtime, + // see https://github.com/eclipse-zenoh/zenoh/pull/566, we can consider + // removing these flags since with tokio, zenoh can better manage the threads it spins + // with the help of thread pools. + threads: 1, }, }, /// 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 0d8528a2..8a07b61e 100644 --- a/rmw_zenoh_cpp/config/DEFAULT_RMW_ZENOH_SESSION_CONFIG.json5 +++ b/rmw_zenoh_cpp/config/DEFAULT_RMW_ZENOH_SESSION_CONFIG.json5 @@ -187,6 +187,13 @@ }, // Number of threads dedicated to transmission // By default, the number of threads is calculated as follows: 1 + ((#cores - 1) / 4) + // We limit the number of threads that the zenoh session can spin to 1. + // Without this limit, applications with multiple zenoh sessions can + // encounter system resource errors when trying to create new threads. + // Once zenoh migrates to relying on tokio for its async runtime, + // see https://github.com/eclipse-zenoh/zenoh/pull/566, we can consider + // removing these flags since with tokio, zenoh can better manage the threads it spins + // with the help of thread pools. threads: 1, }, /// Configure the zenoh RX parameters of a link diff --git a/zenoh_c_vendor/CMakeLists.txt b/zenoh_c_vendor/CMakeLists.txt index 391f1552..2b3ebdf4 100644 --- a/zenoh_c_vendor/CMakeLists.txt +++ b/zenoh_c_vendor/CMakeLists.txt @@ -15,7 +15,8 @@ find_package(ament_cmake_vendor_package REQUIRED) # the zenoh session can spin via the session config as well as the ASYNC_STD_THREAD_COUNT # environment variable. Without this limit, applications with multiple zenoh sessions can # encounter system resource errors when trying to create new threads. -# Once zenoh migrates to relying on tokio for its async runtime, we can consider +# Once zenoh migrates to relying on tokio for its async runtime, +# see https://github.com/eclipse-zenoh/zenoh/pull/566, we can consider # removing these flags since with tokio, zenoh can better manage the threads it spins # with the help of thread pools. # Note: We separate the two args needed for cargo with "$" and not ";" as the