diff --git a/rmw_zenoh_cpp/src/detail/graph_cache.cpp b/rmw_zenoh_cpp/src/detail/graph_cache.cpp index b622e06d..c602699e 100644 --- a/rmw_zenoh_cpp/src/detail/graph_cache.cpp +++ b/rmw_zenoh_cpp/src/detail/graph_cache.cpp @@ -13,6 +13,7 @@ // limitations under the License. #include +#include #include #include #include @@ -233,7 +234,7 @@ void GraphCache::handle_matched_events_for_put( update_event_counters( topic_info.name_, ZENOH_EVENT_PUBLICATION_MATCHED, - match_count_for_entity); + static_cast(match_count_for_entity)); if (is_entity_local(*entity) && match_count_for_entity > 0) { local_entities_with_events[entity].insert(ZENOH_EVENT_PUBLICATION_MATCHED); } @@ -260,7 +261,7 @@ void GraphCache::handle_matched_events_for_put( update_event_counters( topic_info.name_, ZENOH_EVENT_SUBSCRIPTION_MATCHED, - match_count_for_entity); + static_cast(match_count_for_entity)); if (is_entity_local(*entity) && match_count_for_entity > 0) { local_entities_with_events[entity].insert(ZENOH_EVENT_SUBSCRIPTION_MATCHED); } 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 9458eb45..6b56f06a 100644 --- a/rmw_zenoh_cpp/src/detail/rmw_context_impl_s.cpp +++ b/rmw_zenoh_cpp/src/detail/rmw_context_impl_s.cpp @@ -78,12 +78,12 @@ class rmw_context_impl_s::Data final } // Check if shm is enabled. - z_owned_string_t shm_enabled; - zc_config_get_from_str(z_loan(config), Z_CONFIG_SHARED_MEMORY_KEY, &shm_enabled); - auto always_free_shm_enabled = rcpputils::make_scope_exit( - [&shm_enabled]() { - z_drop(z_move(shm_enabled)); - }); + // z_owned_string_t shm_enabled; + // zc_config_get_from_str(z_loan(config), Z_CONFIG_SHARED_MEMORY_KEY, &shm_enabled); + // auto always_free_shm_enabled = rcpputils::make_scope_exit( + // [&shm_enabled]() { + // z_drop(z_move(shm_enabled)); + // }); // Initialize the zenoh session. if (z_open(&session_, z_move(config), NULL) != Z_OK) { @@ -166,29 +166,29 @@ class rmw_context_impl_s::Data final // Initialize the shm manager if shared_memory is enabled in the config. shm_provider_ = std::nullopt; - if (strncmp( - z_string_data(z_loan(shm_enabled)), - "true", - z_string_len(z_loan(shm_enabled))) == 0) - { - // TODO(yuyuan): determine the default alignment of SHM - z_alloc_alignment_t alignment = {5}; - z_owned_memory_layout_t layout; - z_memory_layout_new(&layout, SHM_BUFFER_SIZE_MB * 1024 * 1024, alignment); - - z_owned_shm_provider_t provider; - if (z_posix_shm_provider_new(&provider, z_loan(layout)) != Z_OK) { - RMW_ZENOH_LOG_ERROR_NAMED("rmw_zenoh_cpp", "Unable to create an SHM provider."); - throw std::runtime_error("Unable to create an SHM provider."); - } - shm_provider_ = provider; - } - auto free_shm_provider = rcpputils::make_scope_exit( - [this]() { - if (shm_provider_.has_value()) { - z_drop(z_move(shm_provider_.value())); - } - }); + // if (strncmp( + // z_string_data(z_loan(shm_enabled)), + // "true", + // z_string_len(z_loan(shm_enabled))) == 0) + // { + // // TODO(yuyuan): determine the default alignment of SHM + // z_alloc_alignment_t alignment = {5}; + // z_owned_memory_layout_t layout; + // z_memory_layout_new(&layout, SHM_BUFFER_SIZE_MB * 1024 * 1024, alignment); + + // z_owned_shm_provider_t provider; + // if (z_posix_shm_provider_new(&provider, z_loan(layout)) != Z_OK) { + // RMW_ZENOH_LOG_ERROR_NAMED("rmw_zenoh_cpp", "Unable to create an SHM provider."); + // throw std::runtime_error("Unable to create an SHM provider."); + // } + // shm_provider_ = provider; + // } + // auto free_shm_provider = rcpputils::make_scope_exit( + // [this]() { + // if (shm_provider_.has_value()) { + // z_drop(z_move(shm_provider_.value())); + // } + // }); graph_guard_condition_ = std::make_unique(); graph_guard_condition_->implementation_identifier = rmw_zenoh_cpp::rmw_zenoh_identifier; @@ -216,7 +216,7 @@ class rmw_context_impl_s::Data final }); close_session.cancel(); - free_shm_provider.cancel(); + // free_shm_provider.cancel(); undeclare_z_sub.cancel(); } 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 1e46d6af..813d7723 100644 --- a/rmw_zenoh_cpp/src/detail/rmw_context_impl_s.hpp +++ b/rmw_zenoh_cpp/src/detail/rmw_context_impl_s.hpp @@ -28,6 +28,10 @@ #include "rmw/ret_types.h" #include "rmw/types.h" +#ifdef _MSC_VER +#pragma warning(push) +#pragma warning(disable: 4099) +#endif ///============================================================================= class rmw_context_impl_s final { @@ -95,6 +99,8 @@ class rmw_context_impl_s final private: std::shared_ptr data_{nullptr}; }; - +#ifdef _MSC_VER +#pragma warning(pop) +#endif #endif // DETAIL__RMW_CONTEXT_IMPL_S_HPP_ diff --git a/rmw_zenoh_cpp/src/detail/zenoh_config.cpp b/rmw_zenoh_cpp/src/detail/zenoh_config.cpp index f295befc..72c3c2b9 100644 --- a/rmw_zenoh_cpp/src/detail/zenoh_config.cpp +++ b/rmw_zenoh_cpp/src/detail/zenoh_config.cpp @@ -105,7 +105,7 @@ std::optional zenoh_router_check_attempts() } // If the environment variable contains a value, handle it accordingly. if (envar_value[0] != '\0') { - const auto read_value = std::strtol(envar_value, nullptr, 10); + const auto read_value = std::strtoll(envar_value, nullptr, 10); if (read_value > 0) { return read_value; } else if (read_value < 0) { diff --git a/rmw_zenoh_cpp/src/rmw_event.cpp b/rmw_zenoh_cpp/src/rmw_event.cpp index 63de9bcb..68117032 100644 --- a/rmw_zenoh_cpp/src/rmw_event.cpp +++ b/rmw_zenoh_cpp/src/rmw_event.cpp @@ -220,16 +220,16 @@ rmw_take_event( case rmw_zenoh_cpp::ZENOH_EVENT_REQUESTED_QOS_INCOMPATIBLE: { auto ei = static_cast(event_info); RMW_CHECK_ARGUMENT_FOR_NULL(ei, RMW_RET_INVALID_ARGUMENT); - ei->total_count = st->total_count; - ei->total_count_change = st->total_count_change; + ei->total_count = static_cast(st->total_count); + ei->total_count_change = static_cast(st->total_count_change); *taken = true; return RMW_RET_OK; } case rmw_zenoh_cpp::ZENOH_EVENT_MESSAGE_LOST: { auto ei = static_cast(event_info); RMW_CHECK_ARGUMENT_FOR_NULL(ei, RMW_RET_INVALID_ARGUMENT); - ei->total_count = st->total_count; - ei->total_count_change = st->total_count_change; + ei->total_count = static_cast(st->total_count); + ei->total_count_change = static_cast(st->total_count_change); *taken = true; return RMW_RET_OK; } @@ -247,8 +247,8 @@ rmw_take_event( case rmw_zenoh_cpp::ZENOH_EVENT_OFFERED_QOS_INCOMPATIBLE: { auto ei = static_cast(event_info); RMW_CHECK_ARGUMENT_FOR_NULL(ei, RMW_RET_INVALID_ARGUMENT); - ei->total_count = st->total_count; - ei->total_count_change = st->total_count_change; + ei->total_count = static_cast(st->total_count); + ei->total_count_change = static_cast(st->total_count_change); *taken = true; return RMW_RET_OK; } diff --git a/rmw_zenoh_cpp/src/rmw_init.cpp b/rmw_zenoh_cpp/src/rmw_init.cpp index e76d6062..ac754aaa 100644 --- a/rmw_zenoh_cpp/src/rmw_init.cpp +++ b/rmw_zenoh_cpp/src/rmw_init.cpp @@ -86,10 +86,7 @@ rmw_init(const rmw_init_options_t * options, rmw_context_t * context) } }); - // If not already defined, set the logging environment variable for Zenoh sessions - // to warning level by default. - // TODO(Yadunund): Switch to rcutils_get_env once it supports not overwriting values. - if (setenv(ZENOH_LOG_ENV_VAR_STR, ZENOH_LOG_WARN_LEVEL_STR, 0) != 0) { + if (!rcutils_set_env_overwrite(ZENOH_LOG_ENV_VAR_STR, ZENOH_LOG_WARN_LEVEL_STR, 0)) { RMW_SET_ERROR_MSG("Error configuring Zenoh logging."); return RMW_RET_ERROR; } diff --git a/rmw_zenoh_cpp/src/zenohd/main.cpp b/rmw_zenoh_cpp/src/zenohd/main.cpp index ce73fc14..58a1b39f 100644 --- a/rmw_zenoh_cpp/src/zenohd/main.cpp +++ b/rmw_zenoh_cpp/src/zenohd/main.cpp @@ -33,6 +33,7 @@ #include "rmw/error_handling.h" #include "rcpputils/scope_exit.hpp" +#include "rcutils/env.h" static bool running = true; static std::mutex run_mutex; @@ -60,10 +61,7 @@ int main(int argc, char ** argv) (void)argc; (void)argv; - // If not already defined, set the logging environment variable for Zenoh router - // to info level by default. - // TODO(Yadunund): Switch to rcutils_get_env once it supports not overwriting values. - if (setenv(ZENOH_LOG_ENV_VAR_STR, ZENOH_LOG_INFO_LEVEL_STR, 0) != 0) { + if (!rcutils_set_env_overwrite(ZENOH_LOG_ENV_VAR_STR, ZENOH_LOG_INFO_LEVEL_STR, 0)) { RMW_SET_ERROR_MSG("Error configuring Zenoh logging."); return 1; }