From 50a3ba2a0dae05a89d2be5e969df76ebcea73baf Mon Sep 17 00:00:00 2001 From: Alejandro Hernandez Cordero Date: Wed, 28 Aug 2024 13:52:41 +0200 Subject: [PATCH 1/7] Added Windows support Signed-off-by: Alejandro Hernandez Cordero --- README.md | 5 ++++ .../src/detail/zenoh_router_check.cpp | 7 +++++- rmw_zenoh_cpp/src/rmw_init.cpp | 9 +++++-- rmw_zenoh_cpp/src/rmw_zenoh.cpp | 24 ++++++++++++++----- rmw_zenoh_cpp/src/zenohd/main.cpp | 3 ++- zenoh_c_vendor/CMakeLists.txt | 4 ++-- 6 files changed, 40 insertions(+), 12 deletions(-) diff --git a/README.md b/README.md index 9a4097eb..ba6fafe5 100644 --- a/README.md +++ b/README.md @@ -12,6 +12,11 @@ For information about the Design please visit [design](docs/design.md) page. ## Requirements - [ROS 2](https://docs.ros.org): Rolling/Jazzy/Iron +### Windows + +```bash +choco install -y rust mingw +``` ## Setup diff --git a/rmw_zenoh_cpp/src/detail/zenoh_router_check.cpp b/rmw_zenoh_cpp/src/detail/zenoh_router_check.cpp index ead5ca5a..361b6f13 100644 --- a/rmw_zenoh_cpp/src/detail/zenoh_router_check.cpp +++ b/rmw_zenoh_cpp/src/detail/zenoh_router_check.cpp @@ -43,7 +43,12 @@ rmw_ret_t zenoh_router_check(z_session_t session) }; rmw_ret_t ret = RMW_RET_OK; - z_owned_closure_zid_t router_callback = z_closure(callback, nullptr /* drop */, &context); + // z_owned_closure_zid_t router_callback = z_closure(callback, nullptr /* drop */, &context); + z_owned_closure_zid_t router_callback; + router_callback.context = (void*)&context; + router_callback.call = callback; + router_callback.drop = nullptr; + if (z_info_routers_zid(session, z_move(router_callback))) { RMW_ZENOH_LOG_ERROR_NAMED( "rmw_zenoh_cpp", diff --git a/rmw_zenoh_cpp/src/rmw_init.cpp b/rmw_zenoh_cpp/src/rmw_init.cpp index 99c6f3ad..23af9da3 100644 --- a/rmw_zenoh_cpp/src/rmw_init.cpp +++ b/rmw_zenoh_cpp/src/rmw_init.cpp @@ -171,7 +171,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) != 0) { RMW_SET_ERROR_MSG("Error configuring Zenoh logging."); return RMW_RET_ERROR; } @@ -359,7 +359,12 @@ rmw_init(const rmw_init_options_t * options, rmw_context_t * context) // z_move(callback), // &sub_options); auto sub_options = zc_liveliness_subscriber_options_null(); - z_owned_closure_sample_t callback = z_closure(graph_sub_data_handler, nullptr, context->impl); + // z_owned_closure_sample_t callback = z_closure(graph_sub_data_handler, nullptr, context->impl); + z_owned_closure_sample_t callback; + callback.context = (void*)context->impl; + callback.call = graph_sub_data_handler; + callback.drop = nullptr; + context->impl->graph_subscriber = zc_liveliness_declare_subscriber( z_loan(context->impl->session), z_keyexpr(liveliness_str.c_str()), diff --git a/rmw_zenoh_cpp/src/rmw_zenoh.cpp b/rmw_zenoh_cpp/src/rmw_zenoh.cpp index 3de285a5..2b60a57b 100644 --- a/rmw_zenoh_cpp/src/rmw_zenoh.cpp +++ b/rmw_zenoh_cpp/src/rmw_zenoh.cpp @@ -1447,7 +1447,11 @@ rmw_create_subscription( // Everything above succeeded and is setup properly. Now declare a subscriber // with Zenoh; after this, callbacks may come in at any time. - z_owned_closure_sample_t callback = z_closure(rmw_zenoh_cpp::sub_data_handler, nullptr, sub_data); + // z_owned_closure_sample_t callback = z_closure(rmw_zenoh_cpp::sub_data_handler, nullptr, sub_data); + z_owned_closure_sample_t callback; + callback.context = (void*)sub_data; + callback.call = rmw_zenoh_cpp::sub_data_handler; + callback.drop = nullptr; z_owned_keyexpr_t keyexpr = ros_topic_name_to_zenoh_key( node->context->actual_domain_id, topic_name, @@ -2494,8 +2498,12 @@ rmw_send_request( // and any number. opts.consolidation = z_query_consolidation_latest(); opts.value.payload = z_bytes_t{data_length, reinterpret_cast(request_bytes)}; - z_owned_closure_reply_t zn_closure_reply = - z_closure(rmw_zenoh_cpp::client_data_handler, rmw_zenoh_cpp::client_data_drop, client_data); + // z_owned_closure_reply_t zn_closure_reply = + // z_closure(rmw_zenoh_cpp::client_data_handler, rmw_zenoh_cpp::client_data_drop, client_data); + z_owned_closure_reply_t zn_closure_reply; + zn_closure_reply.context = (void*)client_data; + zn_closure_reply.call = rmw_zenoh_cpp::client_data_handler; + zn_closure_reply.drop = rmw_zenoh_cpp::client_data_drop; z_get( z_loan(context_impl->session), z_loan(client_data->keyexpr), "", @@ -2865,9 +2873,13 @@ rmw_create_service( return nullptr; } - z_owned_closure_query_t callback = z_closure( - rmw_zenoh_cpp::service_data_handler, nullptr, - service_data); + // z_owned_closure_query_t callback = z_closure( + // rmw_zenoh_cpp::service_data_handler, nullptr, + // service_data); + z_owned_closure_query_t callback; + callback.context = (void*)service_data; + callback.call = rmw_zenoh_cpp::service_data_handler; + callback.drop = nullptr; // Configure the queryable to process complete queries. z_queryable_options_t qable_options = z_queryable_options_default(); qable_options.complete = true; diff --git a/rmw_zenoh_cpp/src/zenohd/main.cpp b/rmw_zenoh_cpp/src/zenohd/main.cpp index 8ae25809..d41574d5 100644 --- a/rmw_zenoh_cpp/src/zenohd/main.cpp +++ b/rmw_zenoh_cpp/src/zenohd/main.cpp @@ -30,6 +30,7 @@ #include "../detail/zenoh_config.hpp" #include "../detail/liveliness_utils.hpp" +#include "rcutils/env.h" #include "rmw/error_handling.h" #include "rcpputils/scope_exit.hpp" @@ -63,7 +64,7 @@ int main(int argc, char ** 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) != 0) { RMW_SET_ERROR_MSG("Error configuring Zenoh logging."); return 1; } diff --git a/zenoh_c_vendor/CMakeLists.txt b/zenoh_c_vendor/CMakeLists.txt index 7903e1e8..224957d3 100644 --- a/zenoh_c_vendor/CMakeLists.txt +++ b/zenoh_c_vendor/CMakeLists.txt @@ -25,9 +25,9 @@ set(ZENOHC_CARGO_FLAGS "--no-default-features$--features=zenoh/shared # - https://github.com/eclipse-zenoh/zenoh/pull/1150 (fix deadlock issue https://github.com/ros2/rmw_zenoh/issues/182) ament_vendor(zenoh_c_vendor VCS_URL https://github.com/eclipse-zenoh/zenoh-c.git - VCS_VERSION 548ee8dde0f53a58c06e68a2949949b31140c36c + VCS_VERSION 134dbfa06ca212def5fb51dd8e816734dfd8dff6 CMAKE_ARGS "-DZENOHC_CARGO_FLAGS=${ZENOHC_CARGO_FLAGS}" ) - + ament_package() From 16325a48de1b7a17e1edc04b5a3006aeda20f6c6 Mon Sep 17 00:00:00 2001 From: Alejandro Hernandez Cordero Date: Wed, 28 Aug 2024 13:53:47 +0200 Subject: [PATCH 2/7] make linters happy Signed-off-by: Alejandro Hernandez Cordero --- zenoh_c_vendor/CMakeLists.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/zenoh_c_vendor/CMakeLists.txt b/zenoh_c_vendor/CMakeLists.txt index 224957d3..52cd4f4d 100644 --- a/zenoh_c_vendor/CMakeLists.txt +++ b/zenoh_c_vendor/CMakeLists.txt @@ -29,5 +29,5 @@ ament_vendor(zenoh_c_vendor CMAKE_ARGS "-DZENOHC_CARGO_FLAGS=${ZENOHC_CARGO_FLAGS}" ) - + ament_package() From 78a36c2c10e7ee9bd748bd4fcba2a5610872eddb Mon Sep 17 00:00:00 2001 From: Alejandro Hernandez Cordero Date: Wed, 28 Aug 2024 14:01:13 +0200 Subject: [PATCH 3/7] make linters happy Signed-off-by: Alejandro Hernandez Cordero --- rmw_zenoh_cpp/src/detail/zenoh_router_check.cpp | 2 +- rmw_zenoh_cpp/src/rmw_init.cpp | 4 ++-- rmw_zenoh_cpp/src/rmw_zenoh.cpp | 6 +++--- 3 files changed, 6 insertions(+), 6 deletions(-) diff --git a/rmw_zenoh_cpp/src/detail/zenoh_router_check.cpp b/rmw_zenoh_cpp/src/detail/zenoh_router_check.cpp index 361b6f13..d0d5f58b 100644 --- a/rmw_zenoh_cpp/src/detail/zenoh_router_check.cpp +++ b/rmw_zenoh_cpp/src/detail/zenoh_router_check.cpp @@ -45,7 +45,7 @@ rmw_ret_t zenoh_router_check(z_session_t session) rmw_ret_t ret = RMW_RET_OK; // z_owned_closure_zid_t router_callback = z_closure(callback, nullptr /* drop */, &context); z_owned_closure_zid_t router_callback; - router_callback.context = (void*)&context; + router_callback.context = (void *)&context; router_callback.call = callback; router_callback.drop = nullptr; diff --git a/rmw_zenoh_cpp/src/rmw_init.cpp b/rmw_zenoh_cpp/src/rmw_init.cpp index 23af9da3..6195d2d5 100644 --- a/rmw_zenoh_cpp/src/rmw_init.cpp +++ b/rmw_zenoh_cpp/src/rmw_init.cpp @@ -359,9 +359,9 @@ rmw_init(const rmw_init_options_t * options, rmw_context_t * context) // z_move(callback), // &sub_options); auto sub_options = zc_liveliness_subscriber_options_null(); - // z_owned_closure_sample_t callback = z_closure(graph_sub_data_handler, nullptr, context->impl); + // z_owned_closure_sample_t callback = z_closure(graph_sub_data_handler, nullptr, context->impl); z_owned_closure_sample_t callback; - callback.context = (void*)context->impl; + callback.context = (void *)context->impl; callback.call = graph_sub_data_handler; callback.drop = nullptr; diff --git a/rmw_zenoh_cpp/src/rmw_zenoh.cpp b/rmw_zenoh_cpp/src/rmw_zenoh.cpp index 2b60a57b..99391867 100644 --- a/rmw_zenoh_cpp/src/rmw_zenoh.cpp +++ b/rmw_zenoh_cpp/src/rmw_zenoh.cpp @@ -1449,7 +1449,7 @@ rmw_create_subscription( // with Zenoh; after this, callbacks may come in at any time. // z_owned_closure_sample_t callback = z_closure(rmw_zenoh_cpp::sub_data_handler, nullptr, sub_data); z_owned_closure_sample_t callback; - callback.context = (void*)sub_data; + callback.context = (void *)sub_data; callback.call = rmw_zenoh_cpp::sub_data_handler; callback.drop = nullptr; z_owned_keyexpr_t keyexpr = ros_topic_name_to_zenoh_key( @@ -2501,7 +2501,7 @@ rmw_send_request( // z_owned_closure_reply_t zn_closure_reply = // z_closure(rmw_zenoh_cpp::client_data_handler, rmw_zenoh_cpp::client_data_drop, client_data); z_owned_closure_reply_t zn_closure_reply; - zn_closure_reply.context = (void*)client_data; + zn_closure_reply.context = (void *)client_data; zn_closure_reply.call = rmw_zenoh_cpp::client_data_handler; zn_closure_reply.drop = rmw_zenoh_cpp::client_data_drop; z_get( @@ -2877,7 +2877,7 @@ rmw_create_service( // rmw_zenoh_cpp::service_data_handler, nullptr, // service_data); z_owned_closure_query_t callback; - callback.context = (void*)service_data; + callback.context = (void *)service_data; callback.call = rmw_zenoh_cpp::service_data_handler; callback.drop = nullptr; // Configure the queryable to process complete queries. From 31b712eaa1c6772f2ec4ccb1dba5a7e8783197a9 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Alejandro=20Hern=C3=A1ndez=20Cordero?= Date: Fri, 30 Aug 2024 11:27:35 +0200 Subject: [PATCH 4/7] make linters happy MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Signed-off-by: Alejandro Hernández Cordero --- rmw_zenoh_cpp/src/detail/zenoh_router_check.cpp | 2 +- rmw_zenoh_cpp/src/rmw_init.cpp | 2 +- rmw_zenoh_cpp/src/rmw_zenoh.cpp | 11 ++++++----- 3 files changed, 8 insertions(+), 7 deletions(-) diff --git a/rmw_zenoh_cpp/src/detail/zenoh_router_check.cpp b/rmw_zenoh_cpp/src/detail/zenoh_router_check.cpp index d0d5f58b..c5587455 100644 --- a/rmw_zenoh_cpp/src/detail/zenoh_router_check.cpp +++ b/rmw_zenoh_cpp/src/detail/zenoh_router_check.cpp @@ -45,7 +45,7 @@ rmw_ret_t zenoh_router_check(z_session_t session) rmw_ret_t ret = RMW_RET_OK; // z_owned_closure_zid_t router_callback = z_closure(callback, nullptr /* drop */, &context); z_owned_closure_zid_t router_callback; - router_callback.context = (void *)&context; + router_callback.context = static_cast(&context); router_callback.call = callback; router_callback.drop = nullptr; diff --git a/rmw_zenoh_cpp/src/rmw_init.cpp b/rmw_zenoh_cpp/src/rmw_init.cpp index 6195d2d5..c4226efa 100644 --- a/rmw_zenoh_cpp/src/rmw_init.cpp +++ b/rmw_zenoh_cpp/src/rmw_init.cpp @@ -361,7 +361,7 @@ rmw_init(const rmw_init_options_t * options, rmw_context_t * context) auto sub_options = zc_liveliness_subscriber_options_null(); // z_owned_closure_sample_t callback = z_closure(graph_sub_data_handler, nullptr, context->impl); z_owned_closure_sample_t callback; - callback.context = (void *)context->impl; + callback.context = static_cast(context->impl); callback.call = graph_sub_data_handler; callback.drop = nullptr; diff --git a/rmw_zenoh_cpp/src/rmw_zenoh.cpp b/rmw_zenoh_cpp/src/rmw_zenoh.cpp index 99391867..4161877a 100644 --- a/rmw_zenoh_cpp/src/rmw_zenoh.cpp +++ b/rmw_zenoh_cpp/src/rmw_zenoh.cpp @@ -1445,11 +1445,12 @@ rmw_create_subscription( allocator->deallocate(type_hash_c_str, allocator->state); }); - // Everything above succeeded and is setup properly. Now declare a subscriber + // Everything above succeeded and is setup properly. Now declare a subscriber // with Zenoh; after this, callbacks may come in at any time. - // z_owned_closure_sample_t callback = z_closure(rmw_zenoh_cpp::sub_data_handler, nullptr, sub_data); + // z_owned_closure_sample_t callback = z_closure( + // rmw_zenoh_cpp::sub_data_handler, nullptr, sub_data); z_owned_closure_sample_t callback; - callback.context = (void *)sub_data; + callback.context = static_cast(sub_data); callback.call = rmw_zenoh_cpp::sub_data_handler; callback.drop = nullptr; z_owned_keyexpr_t keyexpr = ros_topic_name_to_zenoh_key( @@ -2501,7 +2502,7 @@ rmw_send_request( // z_owned_closure_reply_t zn_closure_reply = // z_closure(rmw_zenoh_cpp::client_data_handler, rmw_zenoh_cpp::client_data_drop, client_data); z_owned_closure_reply_t zn_closure_reply; - zn_closure_reply.context = (void *)client_data; + zn_closure_reply.context = static_cast(client_data); zn_closure_reply.call = rmw_zenoh_cpp::client_data_handler; zn_closure_reply.drop = rmw_zenoh_cpp::client_data_drop; z_get( @@ -2877,7 +2878,7 @@ rmw_create_service( // rmw_zenoh_cpp::service_data_handler, nullptr, // service_data); z_owned_closure_query_t callback; - callback.context = (void *)service_data; + callback.context = static_cast(service_data); callback.call = rmw_zenoh_cpp::service_data_handler; callback.drop = nullptr; // Configure the queryable to process complete queries. From ebc41f27213bb6270077c8f97fb636d23bdb4a8f Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Alejandro=20Hern=C3=A1ndez=20Cordero?= Date: Wed, 4 Sep 2024 13:53:31 +0200 Subject: [PATCH 5/7] Added feedback MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Signed-off-by: Alejandro Hernández Cordero --- .../src/detail/zenoh_router_check.cpp | 2 ++ rmw_zenoh_cpp/src/rmw_init.cpp | 19 ++++++++++++++++-- rmw_zenoh_cpp/src/rmw_zenoh.cpp | 10 +++++----- rmw_zenoh_cpp/src/zenohd/main.cpp | 20 ++++++++++++++++--- 4 files changed, 41 insertions(+), 10 deletions(-) diff --git a/rmw_zenoh_cpp/src/detail/zenoh_router_check.cpp b/rmw_zenoh_cpp/src/detail/zenoh_router_check.cpp index c5587455..616218dd 100644 --- a/rmw_zenoh_cpp/src/detail/zenoh_router_check.cpp +++ b/rmw_zenoh_cpp/src/detail/zenoh_router_check.cpp @@ -43,6 +43,8 @@ rmw_ret_t zenoh_router_check(z_session_t session) }; rmw_ret_t ret = RMW_RET_OK; + + // TODO(ahcorde): This sintax is not support on Windows yet // z_owned_closure_zid_t router_callback = z_closure(callback, nullptr /* drop */, &context); z_owned_closure_zid_t router_callback; router_callback.context = static_cast(&context); diff --git a/rmw_zenoh_cpp/src/rmw_init.cpp b/rmw_zenoh_cpp/src/rmw_init.cpp index c4226efa..c32a4613 100644 --- a/rmw_zenoh_cpp/src/rmw_init.cpp +++ b/rmw_zenoh_cpp/src/rmw_init.cpp @@ -171,10 +171,24 @@ 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 (rcutils_set_env_overwrite(ZENOH_LOG_ENV_VAR_STR, ZENOH_LOG_WARN_LEVEL_STR, 0) != 0) { - RMW_SET_ERROR_MSG("Error configuring Zenoh logging."); + + const char * value; + const char * error_message = rcutils_get_env(ZENOH_LOG_ENV_VAR_STR, &value); + if (error_message != NULL) { + RMW_SET_ERROR_MSG_WITH_FORMAT_STRING( + "Error configuring Zenoh logging. Unable to get %s environment variable: %s", + ZENOH_LOG_ENV_VAR_STR, + error_message); return RMW_RET_ERROR; } + if (value == nullptr) { + if (!rcutils_set_env(ZENOH_LOG_ENV_VAR_STR, ZENOH_LOG_WARN_LEVEL_STR)) { + RMW_SET_ERROR_MSG_WITH_FORMAT_STRING( + "Error configuring Zenoh logging. Unable to set %s environment variable.", + ZENOH_LOG_ENV_VAR_STR); + return RMW_RET_ERROR; + } + } // Initialize the zenoh configuration. z_owned_config_t config; @@ -359,6 +373,7 @@ rmw_init(const rmw_init_options_t * options, rmw_context_t * context) // z_move(callback), // &sub_options); auto sub_options = zc_liveliness_subscriber_options_null(); + // TODO(ahcorde): This sintax is not support on Windows yet // z_owned_closure_sample_t callback = z_closure(graph_sub_data_handler, nullptr, context->impl); z_owned_closure_sample_t callback; callback.context = static_cast(context->impl); diff --git a/rmw_zenoh_cpp/src/rmw_zenoh.cpp b/rmw_zenoh_cpp/src/rmw_zenoh.cpp index 484d2176..b2cbb9ec 100644 --- a/rmw_zenoh_cpp/src/rmw_zenoh.cpp +++ b/rmw_zenoh_cpp/src/rmw_zenoh.cpp @@ -1439,17 +1439,14 @@ rmw_create_subscription( rmw_subscription->topic_name); return nullptr; } + + // TODO(ahcorde): This sintax is not support on Windows yet // z_owned_closure_sample_t callback = // z_closure(rmw_zenoh_cpp::sub_data_handler, nullptr, sub_data); z_owned_closure_sample_t callback; callback.context = static_cast(sub_data); callback.call = rmw_zenoh_cpp::sub_data_handler; callback.drop = nullptr; - z_owned_keyexpr_t keyexpr = ros_topic_name_to_zenoh_key( - node->context->actual_domain_id, - topic_name, - sub_data->type_support->get_name(), - type_hash_c_str); z_owned_keyexpr_t keyexpr = z_keyexpr_new(sub_data->entity->topic_info()->topic_keyexpr_.c_str()); auto always_free_ros_keyexpr = rcpputils::make_scope_exit( @@ -2510,6 +2507,8 @@ rmw_send_request( // and any number. opts.consolidation = z_query_consolidation_latest(); opts.value.payload = z_bytes_t{data_length, reinterpret_cast(request_bytes)}; + + // TODO(ahcorde): This sintax is not support on Windows yet // z_owned_closure_reply_t zn_closure_reply = // z_closure(rmw_zenoh_cpp::client_data_handler, rmw_zenoh_cpp::client_data_drop, client_data); z_owned_closure_reply_t zn_closure_reply; @@ -2903,6 +2902,7 @@ rmw_create_service( return nullptr; } + // TODO(ahcorde): This sintax is not support on Windows yet // z_owned_closure_query_t callback = z_closure( // rmw_zenoh_cpp::service_data_handler, nullptr, // service_data); diff --git a/rmw_zenoh_cpp/src/zenohd/main.cpp b/rmw_zenoh_cpp/src/zenohd/main.cpp index d41574d5..c5812a96 100644 --- a/rmw_zenoh_cpp/src/zenohd/main.cpp +++ b/rmw_zenoh_cpp/src/zenohd/main.cpp @@ -64,9 +64,23 @@ int main(int argc, char ** 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 (rcutils_set_env_overwrite(ZENOH_LOG_ENV_VAR_STR, ZENOH_LOG_INFO_LEVEL_STR, 0) != 0) { - RMW_SET_ERROR_MSG("Error configuring Zenoh logging."); - return 1; + + const char * value; + const char * error_message = rcutils_get_env(ZENOH_LOG_ENV_VAR_STR, &value); + if (error_message != NULL) { + RMW_SET_ERROR_MSG_WITH_FORMAT_STRING( + "Error configuring Zenoh logging. Unable to get %s environment variable: %s", + ZENOH_LOG_ENV_VAR_STR, + error_message); + return RMW_RET_ERROR; + } + if (value == nullptr) { + if (!rcutils_set_env(ZENOH_LOG_ENV_VAR_STR, ZENOH_LOG_INFO_LEVEL_STR)) { + RMW_SET_ERROR_MSG_WITH_FORMAT_STRING( + "Error configuring Zenoh logging. Unable to set %s environment variable.", + ZENOH_LOG_ENV_VAR_STR); + return RMW_RET_ERROR; + } } // Initialize the zenoh configuration for the router. From d89b1f4b9992f86fdc2609cc15c62606bd64fb6d Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Alejandro=20Hern=C3=A1ndez=20Cordero?= Date: Fri, 6 Sep 2024 13:33:19 +0200 Subject: [PATCH 6/7] Added feedback MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Signed-off-by: Alejandro Hernández Cordero --- rmw_zenoh_cpp/src/detail/rmw_data_types.hpp | 11 ++++++ .../src/detail/zenoh_router_check.cpp | 34 ++++++++--------- rmw_zenoh_cpp/src/rmw_init.cpp | 10 ++--- rmw_zenoh_cpp/src/rmw_zenoh.cpp | 37 ++++++++----------- 4 files changed, 47 insertions(+), 45 deletions(-) diff --git a/rmw_zenoh_cpp/src/detail/rmw_data_types.hpp b/rmw_zenoh_cpp/src/detail/rmw_data_types.hpp index 60e4bd01..281af2c1 100644 --- a/rmw_zenoh_cpp/src/detail/rmw_data_types.hpp +++ b/rmw_zenoh_cpp/src/detail/rmw_data_types.hpp @@ -374,6 +374,17 @@ class rmw_client_data_t final bool is_shutdown_{false}; size_t num_in_flight_{0}; }; + +///============================================================================= +template +T make_z_closure(void * context, void (*call)(H *, void *), void (*drop)(void *)) +{ + T closure; + closure.context = context; + closure.call = call; + closure.drop = drop; + return closure; +} } // namespace rmw_zenoh_cpp #endif // DETAIL__RMW_DATA_TYPES_HPP_ diff --git a/rmw_zenoh_cpp/src/detail/zenoh_router_check.cpp b/rmw_zenoh_cpp/src/detail/zenoh_router_check.cpp index 616218dd..8f675098 100644 --- a/rmw_zenoh_cpp/src/detail/zenoh_router_check.cpp +++ b/rmw_zenoh_cpp/src/detail/zenoh_router_check.cpp @@ -22,34 +22,34 @@ #include "logging_macros.hpp" #include "liveliness_utils.hpp" +#include "rmw_data_types.hpp" namespace rmw_zenoh_cpp { +// Define callback +void callback_id(const struct z_id_t * id, void * ctx) +{ + const std::string id_str = liveliness::zid_to_str(*id); + RMW_ZENOH_LOG_INFO_NAMED( + "rmw_zenoh_cpp", + "Successfully connected to a Zenoh router with id %s.", id_str.c_str()); + // Note: Callback is guaranteed to never be called + // concurrently according to z_info_routers_zid docstring + (*(static_cast(ctx)))++; +} ///============================================================================= rmw_ret_t zenoh_router_check(z_session_t session) { // Initialize context for callback int context = 0; - // Define callback - auto callback = [](const struct z_id_t * id, void * ctx) { - const std::string id_str = liveliness::zid_to_str(*id); - RMW_ZENOH_LOG_INFO_NAMED( - "rmw_zenoh_cpp", - "Successfully connected to a Zenoh router with id %s.", id_str.c_str()); - // Note: Callback is guaranteed to never be called - // concurrently according to z_info_routers_zid docstring - (*(static_cast(ctx)))++; - }; - rmw_ret_t ret = RMW_RET_OK; - // TODO(ahcorde): This sintax is not support on Windows yet - // z_owned_closure_zid_t router_callback = z_closure(callback, nullptr /* drop */, &context); - z_owned_closure_zid_t router_callback; - router_callback.context = static_cast(&context); - router_callback.call = callback; - router_callback.drop = nullptr; + z_owned_closure_zid_t router_callback = + rmw_zenoh_cpp::make_z_closure( + static_cast(&context), + &callback_id, + nullptr); if (z_info_routers_zid(session, z_move(router_callback))) { RMW_ZENOH_LOG_ERROR_NAMED( diff --git a/rmw_zenoh_cpp/src/rmw_init.cpp b/rmw_zenoh_cpp/src/rmw_init.cpp index c32a4613..83a8e493 100644 --- a/rmw_zenoh_cpp/src/rmw_init.cpp +++ b/rmw_zenoh_cpp/src/rmw_init.cpp @@ -373,12 +373,10 @@ rmw_init(const rmw_init_options_t * options, rmw_context_t * context) // z_move(callback), // &sub_options); auto sub_options = zc_liveliness_subscriber_options_null(); - // TODO(ahcorde): This sintax is not support on Windows yet - // z_owned_closure_sample_t callback = z_closure(graph_sub_data_handler, nullptr, context->impl); - z_owned_closure_sample_t callback; - callback.context = static_cast(context->impl); - callback.call = graph_sub_data_handler; - callback.drop = nullptr; + z_owned_closure_sample_t callback = + rmw_zenoh_cpp::make_z_closure( + static_cast(context->impl), graph_sub_data_handler, nullptr + ); context->impl->graph_subscriber = zc_liveliness_declare_subscriber( z_loan(context->impl->session), diff --git a/rmw_zenoh_cpp/src/rmw_zenoh.cpp b/rmw_zenoh_cpp/src/rmw_zenoh.cpp index b2cbb9ec..51158d4e 100644 --- a/rmw_zenoh_cpp/src/rmw_zenoh.cpp +++ b/rmw_zenoh_cpp/src/rmw_zenoh.cpp @@ -1440,13 +1440,11 @@ rmw_create_subscription( return nullptr; } - // TODO(ahcorde): This sintax is not support on Windows yet - // z_owned_closure_sample_t callback = - // z_closure(rmw_zenoh_cpp::sub_data_handler, nullptr, sub_data); - z_owned_closure_sample_t callback; - callback.context = static_cast(sub_data); - callback.call = rmw_zenoh_cpp::sub_data_handler; - callback.drop = nullptr; + z_owned_closure_sample_t callback = + make_z_closure( + static_cast(sub_data), + rmw_zenoh_cpp::sub_data_handler, + nullptr); z_owned_keyexpr_t keyexpr = z_keyexpr_new(sub_data->entity->topic_info()->topic_keyexpr_.c_str()); auto always_free_ros_keyexpr = rcpputils::make_scope_exit( @@ -2508,13 +2506,11 @@ rmw_send_request( opts.consolidation = z_query_consolidation_latest(); opts.value.payload = z_bytes_t{data_length, reinterpret_cast(request_bytes)}; - // TODO(ahcorde): This sintax is not support on Windows yet - // z_owned_closure_reply_t zn_closure_reply = - // z_closure(rmw_zenoh_cpp::client_data_handler, rmw_zenoh_cpp::client_data_drop, client_data); - z_owned_closure_reply_t zn_closure_reply; - zn_closure_reply.context = static_cast(client_data); - zn_closure_reply.call = rmw_zenoh_cpp::client_data_handler; - zn_closure_reply.drop = rmw_zenoh_cpp::client_data_drop; + z_owned_closure_reply_t zn_closure_reply = + rmw_zenoh_cpp::make_z_closure( + static_cast(client_data), + &rmw_zenoh_cpp::client_data_handler, + rmw_zenoh_cpp::client_data_drop); z_get( z_loan(context_impl->session), z_loan(client_data->keyexpr), "", @@ -2902,14 +2898,11 @@ rmw_create_service( return nullptr; } - // TODO(ahcorde): This sintax is not support on Windows yet - // z_owned_closure_query_t callback = z_closure( - // rmw_zenoh_cpp::service_data_handler, nullptr, - // service_data); - z_owned_closure_query_t callback; - callback.context = static_cast(service_data); - callback.call = rmw_zenoh_cpp::service_data_handler; - callback.drop = nullptr; + z_owned_closure_query_t callback = + rmw_zenoh_cpp::make_z_closure( + static_cast(service_data), + &rmw_zenoh_cpp::service_data_handler, + nullptr); // Configure the queryable to process complete queries. z_queryable_options_t qable_options = z_queryable_options_default(); qable_options.complete = true; From ce1d2fb4543a983033527657b3a06e172575dbf4 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Alejandro=20Hern=C3=A1ndez=20Cordero?= Date: Fri, 6 Sep 2024 13:46:48 +0200 Subject: [PATCH 7/7] Fix compilation MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Signed-off-by: Alejandro Hernández Cordero --- rmw_zenoh_cpp/src/rmw_zenoh.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/rmw_zenoh_cpp/src/rmw_zenoh.cpp b/rmw_zenoh_cpp/src/rmw_zenoh.cpp index 51158d4e..d31d7665 100644 --- a/rmw_zenoh_cpp/src/rmw_zenoh.cpp +++ b/rmw_zenoh_cpp/src/rmw_zenoh.cpp @@ -1441,7 +1441,7 @@ rmw_create_subscription( } z_owned_closure_sample_t callback = - make_z_closure( + rmw_zenoh_cpp::make_z_closure( static_cast(sub_data), rmw_zenoh_cpp::sub_data_handler, nullptr);