diff --git a/rmw_zenoh_cpp/CMakeLists.txt b/rmw_zenoh_cpp/CMakeLists.txt index c8b36b39..732cd470 100644 --- a/rmw_zenoh_cpp/CMakeLists.txt +++ b/rmw_zenoh_cpp/CMakeLists.txt @@ -11,8 +11,6 @@ if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang") add_compile_options(-Wall -Wextra -Wpedantic) endif() -set(RMW_ZENOH_BUILD_WITH_SHARED_MEMORY TRUE CACHE BOOL "Compile Zenoh RMW with Shared Memory support") - # find dependencies find_package(ament_cmake REQUIRED) @@ -45,7 +43,6 @@ add_library(rmw_zenoh_cpp SHARED src/detail/rmw_subscription_data.cpp src/detail/service_type_support.cpp src/detail/simplified_xxhash3.cpp - src/detail/shm_context.cpp src/detail/type_support.cpp src/detail/type_support_common.cpp src/detail/zenoh_config.cpp @@ -84,13 +81,6 @@ target_compile_definitions(rmw_zenoh_cpp RMW_VERSION_PATCH=${rmw_VERSION_PATCH} ) -if(${RMW_ZENOH_BUILD_WITH_SHARED_MEMORY}) - target_compile_definitions(rmw_zenoh_cpp - PUBLIC - RMW_ZENOH_BUILD_WITH_SHARED_MEMORY - ) -endif() - ament_export_targets(export_rmw_zenoh_cpp) register_rmw_implementation( 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 b78dc031..ed12a361 100644 --- a/rmw_zenoh_cpp/config/DEFAULT_RMW_ZENOH_ROUTER_CONFIG.json5 +++ b/rmw_zenoh_cpp/config/DEFAULT_RMW_ZENOH_ROUTER_CONFIG.json5 @@ -461,7 +461,7 @@ /// subscriber side. By doing so, the probing procedure will succeed and shared memory will operate as expected. /// /// ROS setting: disabled by default until fully tested - enabled: true, + enabled: false, }, auth: { /// The configuration of authentication. 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 42716f24..daffd790 100644 --- a/rmw_zenoh_cpp/config/DEFAULT_RMW_ZENOH_SESSION_CONFIG.json5 +++ b/rmw_zenoh_cpp/config/DEFAULT_RMW_ZENOH_SESSION_CONFIG.json5 @@ -464,7 +464,7 @@ /// subscriber side. By doing so, the probing procedure will succeed and shared memory will operate as expected. /// /// ROS setting: disabled by default until fully tested - enabled: true, + enabled: false, }, auth: { /// The configuration of authentication. 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 2f5c9fbc..61dd9c8b 100644 --- a/rmw_zenoh_cpp/src/detail/rmw_context_impl_s.cpp +++ b/rmw_zenoh_cpp/src/detail/rmw_context_impl_s.cpp @@ -165,21 +165,21 @@ class rmw_context_impl_s::Data final : public std::enable_shared_from_this "rmw_zenoh_cpp", "[rmw_context_impl_s] z_call received an invalid reply.\n"); } } -#ifdef RMW_ZENOH_BUILD_WITH_SHARED_MEMORY - // Initialize the shm subsystem if shared_memory is enabled in the config - if (rmw_zenoh_cpp::zenoh_shm_enabled()) { - RMW_ZENOH_LOG_DEBUG_NAMED("rmw_zenoh_cpp", "SHM is enabled"); - - shm_ = std::make_optional( - rmw_zenoh_cpp::ShmContext( - rmw_zenoh_cpp::zenoh_shm_alloc_size(), - rmw_zenoh_cpp::zenoh_shm_message_size_threshold() - )); - } else { - RMW_ZENOH_LOG_DEBUG_NAMED("rmw_zenoh_cpp", "SHM is disabled"); + + // Initialize the shm manager if shared_memory is enabled in the config. + shm_provider_ = std::nullopt; +#ifndef _MSC_VER + if (shm_enabled == "true") { + auto layout = zenoh::MemoryLayout( + SHM_BUFFER_SIZE_MB * 1024 * 1024, + zenoh::AllocAlignment({5})); + zenoh::PosixShmProvider provider(layout, &result); + if (result != Z_OK) { + throw std::runtime_error("Unable to create shm provider."); + } + shm_provider_ = std::move(provider); } #endif - graph_guard_condition_ = std::make_unique(); graph_guard_condition_->implementation_identifier = rmw_zenoh_cpp::rmw_zenoh_identifier; graph_guard_condition_->data = &guard_condition_data_; @@ -262,13 +262,11 @@ class rmw_context_impl_s::Data final : public std::enable_shared_from_this return session_; } -#ifdef RMW_ZENOH_BUILD_WITH_SHARED_MEMORY - std::optional & shm() + std::optional & shm_provider() { std::lock_guard lock(mutex_); - return shm_; + return shm_provider_; } -#endif rmw_guard_condition_t * graph_guard_condition() { @@ -400,11 +398,9 @@ class rmw_context_impl_s::Data final : public std::enable_shared_from_this std::string enclave_; // An owned session. std::shared_ptr session_; -#ifdef RMW_ZENOH_BUILD_WITH_SHARED_MEMORY - // An optional SHM context that is initialized of SHM is enabled in the + // An optional SHM manager that is initialized of SHM is enabled in the // zenoh session config. - std::optional shm_; -#endif + std::optional shm_provider_; // Graph cache. std::shared_ptr graph_cache_; // ROS graph liveliness subscriber. @@ -460,13 +456,11 @@ const std::shared_ptr rmw_context_impl_s::session() const return data_->session(); } -#ifdef RMW_ZENOH_BUILD_WITH_SHARED_MEMORY ///============================================================================= -std::optional & rmw_context_impl_s::shm() +std::optional & rmw_context_impl_s::shm_provider() { - return data_->shm(); + return data_->shm_provider(); } -#endif ///============================================================================= rmw_guard_condition_t * rmw_context_impl_s::graph_guard_condition() diff --git a/rmw_zenoh_cpp/src/detail/rmw_context_impl_s.hpp b/rmw_zenoh_cpp/src/detail/rmw_context_impl_s.hpp index 3c3b9eb7..a2fdaf5e 100644 --- a/rmw_zenoh_cpp/src/detail/rmw_context_impl_s.hpp +++ b/rmw_zenoh_cpp/src/detail/rmw_context_impl_s.hpp @@ -50,13 +50,11 @@ struct rmw_context_impl_s final // Loan the Zenoh session. const std::shared_ptr session() const; -#ifdef RMW_ZENOH_BUILD_WITH_SHARED_MEMORY - // Get a reference to the shm subsystem. + // Get a reference to the shm_provider. // Note: This is not thread-safe. // TODO(Yadunund): Remove this API and instead include a publish() API // that handles the shm_provider once the context manages publishers. - std::optional & shm(); -#endif + std::optional & shm_provider(); // Get the graph guard condition. rmw_guard_condition_t * graph_guard_condition(); diff --git a/rmw_zenoh_cpp/src/detail/rmw_publisher_data.cpp b/rmw_zenoh_cpp/src/detail/rmw_publisher_data.cpp index 40dc747f..f960b879 100644 --- a/rmw_zenoh_cpp/src/detail/rmw_publisher_data.cpp +++ b/rmw_zenoh_cpp/src/detail/rmw_publisher_data.cpp @@ -201,11 +201,8 @@ PublisherData::PublisherData( ///============================================================================= rmw_ret_t PublisherData::publish( - const void * ros_message -#ifdef RMW_ZENOH_BUILD_WITH_SHARED_MEMORY - , const std::optional & shm -#endif -) + const void * ros_message, + std::optional & /*shm_provider*/) { std::lock_guard lock(mutex_); if (is_shutdown_) { @@ -221,59 +218,19 @@ rmw_ret_t PublisherData::publish( // To store serialized message byte array. char * msg_bytes = nullptr; -#ifdef RMW_ZENOH_BUILD_WITH_SHARED_MEMORY - std::optional shmbuf = std::nullopt; -#endif - rcutils_allocator_t * allocator = &rmw_node_->context->options.allocator; auto always_free_msg_bytes = rcpputils::make_scope_exit( - [&msg_bytes, allocator -#ifdef RMW_ZENOH_BUILD_WITH_SHARED_MEMORY - , &shmbuf -#endif - ]() { - if (msg_bytes -#ifdef RMW_ZENOH_BUILD_WITH_SHARED_MEMORY - && !shmbuf.has_value() -#endif - ) - { + [&msg_bytes, allocator]() { + if (msg_bytes) { allocator->deallocate(msg_bytes, allocator->state); } }); - -#ifdef RMW_ZENOH_BUILD_WITH_SHARED_MEMORY - // Get memory from SHM buffer if available. - if (shm.has_value() && max_data_length >= shm.value().msgsize_threshold) { - RMW_ZENOH_LOG_DEBUG_NAMED("rmw_zenoh_cpp", "SHM is enabled."); - - auto & provider = shm.value().shm_provider; - - // TODO(yellowhatter): SHM, use alignment based on msgsize_threshold - auto alloc_result = provider.alloc_gc_defrag_blocking( - max_data_length, - zenoh::AllocAlignment({0})); - - if (std::holds_alternative(alloc_result)) { - auto && buf = std::get(std::move(alloc_result)); - msg_bytes = reinterpret_cast(buf.data()); - shmbuf = std::make_optional(std::move(buf)); - } else { - // TODO(Yadunund): Should we revert to regular allocation and not return an error? - RMW_SET_ERROR_MSG("Failed to allocate a SHM buffer, even after GCing."); - return RMW_RET_ERROR; - } - } else { -#endif // Get memory from the allocator. msg_bytes = static_cast(allocator->allocate(max_data_length, allocator->state)); RMW_CHECK_FOR_NULL_WITH_MSG( msg_bytes, "bytes for message is null", return RMW_RET_BAD_ALLOC); -#ifdef RMW_ZENOH_BUILD_WITH_SHARED_MEMORY -} -#endif // Object that manages the raw buffer eprosima::fastcdr::FastBuffer fastbuffer(msg_bytes, max_data_length); @@ -300,14 +257,11 @@ rmw_ret_t PublisherData::publish( options.attachment = rmw_zenoh_cpp::AttachmentData( sequence_number_++, source_timestamp, entity_->copy_gid()).serialize_to_zbytes(); - auto payload = -#ifdef RMW_ZENOH_BUILD_WITH_SHARED_MEMORY - shmbuf.has_value() ? zenoh::Bytes(std::move(*shmbuf)) : -#endif - zenoh::Bytes( - std::vector( - reinterpret_cast(msg_bytes), - reinterpret_cast(msg_bytes) + data_length)); + // TODO(ahcorde): shmbuf + std::vector raw_data( + reinterpret_cast(msg_bytes), + reinterpret_cast(msg_bytes) + data_length); + zenoh::Bytes payload(std::move(raw_data)); TRACETOOLS_TRACEPOINT( rmw_publish, static_cast(rmw_publisher_), ros_message, source_timestamp); @@ -328,11 +282,8 @@ rmw_ret_t PublisherData::publish( ///============================================================================= rmw_ret_t PublisherData::publish_serialized_message( - const rmw_serialized_message_t * serialized_message -#ifdef RMW_ZENOH_BUILD_WITH_SHARED_MEMORY - , const std::optional & shm -#endif -) + const rmw_serialized_message_t * serialized_message, + std::optional & /*shm_provider*/) { eprosima::fastcdr::FastBuffer buffer( reinterpret_cast(serialized_message->buffer), serialized_message->buffer_length); @@ -354,48 +305,14 @@ rmw_ret_t PublisherData::publish_serialized_message( options.attachment = rmw_zenoh_cpp::AttachmentData( sequence_number_++, source_timestamp, entity_->copy_gid()).serialize_to_zbytes(); - -#ifdef RMW_ZENOH_BUILD_WITH_SHARED_MEMORY - // Get memory from SHM buffer if available. - if (shm.has_value() && data_length >= shm.value().msgsize_threshold) { - RMW_ZENOH_LOG_DEBUG_NAMED("rmw_zenoh_cpp", "SHM is enabled."); - - auto & provider = shm.value().shm_provider; - - // TODO(yellowhatter): SHM, use alignment based on msgsize_threshold - auto alloc_result = provider.alloc_gc_defrag_blocking(data_length, zenoh::AllocAlignment({0})); - - if (std::holds_alternative(alloc_result)) { - auto && buf = std::get(std::move(alloc_result)); - auto msg_bytes = reinterpret_cast(buf.data()); - memcpy(msg_bytes, serialized_message->buffer, data_length); - zenoh::Bytes payload(std::move(buf)); - - TRACETOOLS_TRACEPOINT( - rmw_publish, static_cast(rmw_publisher_), serialized_message, - source_timestamp); - - pub_.put(std::move(payload), std::move(options), &result); - } else { - // TODO(Yadunund): Should we revert to regular allocation and not return an error? - RMW_SET_ERROR_MSG("Failed to allocate a SHM buffer, even after GCing."); - return RMW_RET_ERROR; - } - } else { -#endif - std::vector raw_image( + std::vector raw_data( serialized_message->buffer, serialized_message->buffer + data_length); - zenoh::Bytes payload(raw_image); + zenoh::Bytes payload(std::move(raw_data)); TRACETOOLS_TRACEPOINT( rmw_publish, static_cast(rmw_publisher_), serialized_message, source_timestamp); - pub_.put(std::move(payload), std::move(options), &result); -#ifdef RMW_ZENOH_BUILD_WITH_SHARED_MEMORY -} -#endif - if (result != Z_OK) { if (result == Z_ESESSION_CLOSED) { RMW_ZENOH_LOG_WARN_NAMED( diff --git a/rmw_zenoh_cpp/src/detail/rmw_publisher_data.hpp b/rmw_zenoh_cpp/src/detail/rmw_publisher_data.hpp index c27b10e1..7cec5406 100644 --- a/rmw_zenoh_cpp/src/detail/rmw_publisher_data.hpp +++ b/rmw_zenoh_cpp/src/detail/rmw_publisher_data.hpp @@ -28,7 +28,6 @@ #include "event.hpp" #include "liveliness_utils.hpp" #include "message_type_support.hpp" -#include "shm_context.hpp" #include "type_support_common.hpp" #include "zenoh_utils.hpp" @@ -57,19 +56,13 @@ class PublisherData final // Publish a ROS message. rmw_ret_t publish( - const void * ros_message -#ifdef RMW_ZENOH_BUILD_WITH_SHARED_MEMORY - , const std::optional & shm -#endif - ); + const void * ros_message, + std::optional & shm_provider); // Publish a serialized ROS message. rmw_ret_t publish_serialized_message( - const rmw_serialized_message_t * serialized_message -#ifdef RMW_ZENOH_BUILD_WITH_SHARED_MEMORY - , const std::optional & shm -#endif - ); + const rmw_serialized_message_t * serialized_message, + std::optional & shm_provider); // Get a copy of the keyexpr_hash of this PublisherData's liveliness::Entity. std::size_t keyexpr_hash() const; diff --git a/rmw_zenoh_cpp/src/detail/rmw_subscription_data.hpp b/rmw_zenoh_cpp/src/detail/rmw_subscription_data.hpp index 344b9138..a3fab3f9 100644 --- a/rmw_zenoh_cpp/src/detail/rmw_subscription_data.hpp +++ b/rmw_zenoh_cpp/src/detail/rmw_subscription_data.hpp @@ -34,7 +34,6 @@ #include "liveliness_utils.hpp" #include "message_type_support.hpp" #include "attachment_helpers.hpp" -#include "shm_context.hpp" #include "type_support_common.hpp" #include "zenoh_utils.hpp" @@ -77,11 +76,8 @@ class SubscriptionData final : public std::enable_shared_from_this & shm -#endif - ); + const void * ros_message, + std::optional & shm_provider); // Get a copy of the keyexpr_hash of this SubscriptionData's liveliness::Entity. std::size_t keyexpr_hash() const; diff --git a/rmw_zenoh_cpp/src/detail/shm_context.cpp b/rmw_zenoh_cpp/src/detail/shm_context.cpp deleted file mode 100644 index e750fa81..00000000 --- a/rmw_zenoh_cpp/src/detail/shm_context.cpp +++ /dev/null @@ -1,33 +0,0 @@ -// Copyright 2024 Open Source Robotics Foundation, Inc. -// -// Licensed under the Apache License, Version 2.0 (the "License"); -// you may not use this file except in compliance with the License. -// You may obtain a copy of the License at -// -// http://www.apache.org/licenses/LICENSE-2.0 -// -// Unless required by applicable law or agreed to in writing, software -// distributed under the License is distributed on an "AS IS" BASIS, -// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -// See the License for the specific language governing permissions and -// limitations under the License. - -#ifdef RMW_ZENOH_BUILD_WITH_SHARED_MEMORY - -#include - -#include "shm_context.hpp" - -namespace rmw_zenoh_cpp -{ -///============================================================================= -ShmContext::ShmContext(size_t alloc_size, size_t msgsize_threshold) -: // Create Layout for provider's memory - // Provider's alignment is 1 (=2^0) bytes as we are going to make only 1-byte aligned allocations - // TODO(yellowhatter): use zenoh_shm_message_size_threshold as base for alignment - shm_provider(zenoh::PosixShmProvider(zenoh::MemoryLayout(alloc_size, zenoh::AllocAlignment {0}))), - msgsize_threshold(msgsize_threshold) -{} -} // namespace rmw_zenoh_cpp - -#endif diff --git a/rmw_zenoh_cpp/src/detail/shm_context.hpp b/rmw_zenoh_cpp/src/detail/shm_context.hpp deleted file mode 100644 index 112d7af0..00000000 --- a/rmw_zenoh_cpp/src/detail/shm_context.hpp +++ /dev/null @@ -1,36 +0,0 @@ -// Copyright 2024 Open Source Robotics Foundation, Inc. -// -// Licensed under the Apache License, Version 2.0 (the "License"); -// you may not use this file except in compliance with the License. -// You may obtain a copy of the License at -// -// http://www.apache.org/licenses/LICENSE-2.0 -// -// Unless required by applicable law or agreed to in writing, software -// distributed under the License is distributed on an "AS IS" BASIS, -// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -// See the License for the specific language governing permissions and -// limitations under the License. - -#ifndef DETAIL__SHM_CONTEXT_HPP_ -#define DETAIL__SHM_CONTEXT_HPP_ - -#ifdef RMW_ZENOH_BUILD_WITH_SHARED_MEMORY - -#include - -namespace rmw_zenoh_cpp -{ -///============================================================================= -struct ShmContext -{ - zenoh::PosixShmProvider shm_provider; - size_t msgsize_threshold; - - ShmContext(size_t alloc_size, size_t msgsize_threshold); -}; -} // namespace rmw_zenoh_cpp - -#endif - -#endif // DETAIL__SHM_CONTEXT_HPP_ diff --git a/rmw_zenoh_cpp/src/detail/zenoh_config.cpp b/rmw_zenoh_cpp/src/detail/zenoh_config.cpp index dd960529..fa100d0a 100644 --- a/rmw_zenoh_cpp/src/detail/zenoh_config.cpp +++ b/rmw_zenoh_cpp/src/detail/zenoh_config.cpp @@ -43,14 +43,6 @@ static const std::unordered_map _get_z_config( const char * envar_name, @@ -131,94 +123,4 @@ std::optional zenoh_router_check_attempts() // If unset, use the default. return default_value; } - -#ifdef RMW_ZENOH_BUILD_WITH_SHARED_MEMORY -///============================================================================= -bool zenoh_shm_enabled() -{ - const char * envar_value; - - if (NULL != rcutils_get_env(zenoh_shm_enabled_envar, &envar_value)) { - RMW_ZENOH_LOG_ERROR_NAMED( - "rmw_zenoh_cpp", "Envar %s cannot be read. Report this bug.", - zenoh_shm_enabled_envar); - return zenoh_shm_enabled_default; - } - - if (strlen(envar_value) == strlen("true") && - strncmp(envar_value, "true", strlen(envar_value)) == 0) - { - return true; - } - - if (strlen(envar_value) == strlen("false") && - strncmp(envar_value, "false", strlen(envar_value)) == 0) - { - return false; - } - - return zenoh_shm_enabled_default; -} -///============================================================================= -size_t zenoh_shm_alloc_size() -{ - const char * envar_value; - - if (NULL != rcutils_get_env(zenoh_shm_alloc_size_envar, &envar_value)) { - RMW_ZENOH_LOG_ERROR_NAMED( - "rmw_zenoh_cpp", "Envar %s cannot be read. Report this bug.", - zenoh_shm_alloc_size_envar); - return zenoh_shm_alloc_size_default; - } - - // If the environment variable contains a value, handle it accordingly. - if (envar_value[0] != '\0') { - const auto read_value = std::strtoull(envar_value, nullptr, 10); - if (read_value > 0) { - if (read_value > std::numeric_limits::max()) { - RMW_ZENOH_LOG_ERROR_NAMED( - "rmw_zenoh_cpp", "Envar %s: value is too large!", - zenoh_shm_alloc_size_envar); - } else { - return read_value; - } - } - } - - return zenoh_shm_alloc_size_default; -} -///============================================================================= -size_t zenoh_shm_message_size_threshold() -{ - const char * envar_value; - - if (NULL != rcutils_get_env(zenoh_shm_message_size_threshold_envar, &envar_value)) { - RMW_ZENOH_LOG_ERROR_NAMED( - "rmw_zenoh_cpp", "Envar %s cannot be read. Report this bug.", - zenoh_shm_message_size_threshold_envar); - return zenoh_shm_message_size_threshold_default; - } - - // If the environment variable contains a value, handle it accordingly. - if (envar_value[0] != '\0') { - const auto read_value = std::strtoull(envar_value, nullptr, 10); - if (read_value > 0) { - if (read_value > std::numeric_limits::max()) { - RMW_ZENOH_LOG_ERROR_NAMED( - "rmw_zenoh_cpp", "Envar %s: value is too large!", - zenoh_shm_message_size_threshold_envar); - } else if ((read_value & (read_value - 1)) != 0) { // power of 2 check - RMW_ZENOH_LOG_ERROR_NAMED( - "rmw_zenoh_cpp", "Envar %s: value must be power of 2!", - zenoh_shm_message_size_threshold_envar); - - } else { - return read_value; - } - } - } - - return zenoh_shm_message_size_threshold_default; -} -#endif } // namespace rmw_zenoh_cpp diff --git a/rmw_zenoh_cpp/src/detail/zenoh_config.hpp b/rmw_zenoh_cpp/src/detail/zenoh_config.hpp index 7ce7d5f4..1f1e194f 100644 --- a/rmw_zenoh_cpp/src/detail/zenoh_config.hpp +++ b/rmw_zenoh_cpp/src/detail/zenoh_config.hpp @@ -61,36 +61,6 @@ std::optional get_z_config(const ConfigurableEntity & entity); /// @return The number of times to try connecting to a zenoh router and /// std::nullopt if establishing a connection to a router is not required. std::optional zenoh_router_check_attempts(); - -#ifdef RMW_ZENOH_BUILD_WITH_SHARED_MEMORY -///============================================================================= -/// Get the enabled state of shared memory subsystem -/// based on the environment variable ZENOH_SHM_ENABLED. -/// @details The behavior is as follows: -/// - If not set or not "false", the default value of "true" is returned. -/// - Else "false" is returned. -/// @return The amount of shared memory to be pre-allocated for Zenoh SHM operation -bool zenoh_shm_enabled(); - -///============================================================================= -/// Get the amount of shared memory to be pre-allocated for Zenoh SHM operation -/// based on the environment variable ZENOH_SHM_ALLOC_SIZE. -/// @details The behavior is as follows: -/// - If not set or <= 0, the default value of 1MB is returned. -/// - Else value of environemnt variable is returned. -/// @return The amount of shared memory to be pre-allocated for Zenoh SHM operation -size_t zenoh_shm_alloc_size(); - -///============================================================================= -/// Message size threshold for implicit SHM optimization based on the environment -/// variable ZENOH_SHM_MESSAGE_SIZE_THRESHOLD. -/// Messages smaller than this threshold will not be forwarded through Zenoh SHM -/// @details The behavior is as follows: -/// - If not set or <= 0, the default value of 2KB is returned. -/// - Else value of environemnt variable is returned. -/// @return The amount of shared memory to be pre-allocated for Zenoh SHM operation -size_t zenoh_shm_message_size_threshold(); -#endif } // namespace rmw_zenoh_cpp #endif // DETAIL__ZENOH_CONFIG_HPP_ diff --git a/rmw_zenoh_cpp/src/rmw_zenoh.cpp b/rmw_zenoh_cpp/src/rmw_zenoh.cpp index f573b04f..e7342c13 100644 --- a/rmw_zenoh_cpp/src/rmw_zenoh.cpp +++ b/rmw_zenoh_cpp/src/rmw_zenoh.cpp @@ -614,11 +614,8 @@ rmw_publish( } return pub_data->publish( - ros_message -#ifdef RMW_ZENOH_BUILD_WITH_SHARED_MEMORY - , context_impl->shm() -#endif - ); + ros_message, + context_impl->shm_provider()); } //============================================================================== @@ -724,11 +721,8 @@ rmw_publish_serialized_message( RMW_CHECK_ARGUMENT_FOR_NULL(publisher_data, RMW_RET_INVALID_ARGUMENT); return publisher_data->publish_serialized_message( - serialized_message -#ifdef RMW_ZENOH_BUILD_WITH_SHARED_MEMORY - , context_impl->shm() -#endif - ); + serialized_message, + context_impl->shm_provider()); } //============================================================================== diff --git a/zenoh_cpp_vendor/CMakeLists.txt b/zenoh_cpp_vendor/CMakeLists.txt index f16d79d0..4d8e6536 100644 --- a/zenoh_cpp_vendor/CMakeLists.txt +++ b/zenoh_cpp_vendor/CMakeLists.txt @@ -15,9 +15,7 @@ find_package(ament_cmake_vendor_package REQUIRED) # 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_compression zenoh/transport_tcp zenoh/transport_tls") - -set(RMW_ZENOH_BUILD_WITH_SHARED_MEMORY TRUE CACHE BOOL "Compile Zenoh RMW with Shared Memory support") +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-c to benefit from : # - https://github.com/eclipse-zenoh/zenoh-c/pull/340 (fix build issue) @@ -31,7 +29,6 @@ ament_vendor(zenoh_c_vendor VCS_VERSION 2f389597264c200d9ddf72bbabbfea878abd5179 CMAKE_ARGS "-DZENOHC_CARGO_FLAGS=${ZENOHC_CARGO_FLAGS}" - "-DZENOHC_BUILD_WITH_SHARED_MEMORY:BOOL=${RMW_ZENOH_BUILD_WITH_SHARED_MEMORY}" "-DZENOHC_BUILD_WITH_UNSTABLE_API=TRUE" "-DZENOHC_CUSTOM_TARGET=${ZENOHC_CUSTOM_TARGET}" ) @@ -42,9 +39,8 @@ ament_vendor(zenoh_cpp_vendor VCS_URL https://github.com/eclipse-zenoh/zenoh-cpp VCS_VERSION c549fbdf54e866b9d8f29c883e66359fcac88ed4 CMAKE_ARGS - -DZENOHCXX_ZENOHC=ON - -DZENOHCXX_ZENOHPICO=OFF - ) + -DZENOHCXX_ZENOHC=OFF +) externalproject_add_stepdependencies(zenoh_cpp_vendor configure zenoh_c_vendor)