diff --git a/rmw_zenoh_cpp/src/detail/rmw_client_data.cpp b/rmw_zenoh_cpp/src/detail/rmw_client_data.cpp index cf0fcb4e..ae7396ba 100644 --- a/rmw_zenoh_cpp/src/detail/rmw_client_data.cpp +++ b/rmw_zenoh_cpp/src/detail/rmw_client_data.cpp @@ -15,36 +15,29 @@ #include "rmw_client_data.hpp" #include +#include #include -#include #include #include #include #include -#include -#include #include -#include "attachment_helpers.hpp" #include "cdr.hpp" #include "liveliness_utils.hpp" #include "logging_macros.hpp" -#include "message_type_support.hpp" #include "qos.hpp" #include "rmw_context_impl_s.hpp" #include "rcpputils/scope_exit.hpp" - #include "rmw/error_handling.h" -#include "rmw/get_topic_endpoint_info.h" -#include "rmw/impl/cpp/macros.hpp" namespace { ///============================================================================= -void client_data_handler(z_owned_reply_t * reply, void * data) +void client_data_handler(z_loaned_reply_t * reply, void * data) { auto client_data = static_cast(data); if (client_data == nullptr) { @@ -59,21 +52,20 @@ void client_data_handler(z_owned_reply_t * reply, void * data) return; } - if (!z_reply_check(reply)) { - RMW_ZENOH_LOG_ERROR_NAMED( - "rmw_zenoh_cpp", - "z_reply_check returned False" - ); - return; - } if (!z_reply_is_ok(reply)) { - z_value_t err = z_reply_err(reply); + const z_loaned_reply_err_t * err = z_reply_err(reply); + const z_loaned_bytes_t * err_payload = z_reply_err_payload(err); + + z_owned_string_t err_str; + z_bytes_to_string(err_payload, &err_str); + RMW_ZENOH_LOG_ERROR_NAMED( "rmw_zenoh_cpp", "z_reply_is_ok returned False for keyexpr %s. Reason: %.*s", client_data->topic_info().topic_keyexpr_.c_str(), - (int)err.payload.len, - err.payload.start); + static_cast(z_string_len(z_loan(err_str))), + z_string_data(z_loan(err_str))); + z_drop(z_move(err_str)); return; } @@ -81,11 +73,10 @@ void client_data_handler(z_owned_reply_t * reply, void * data) std::chrono::nanoseconds::rep received_timestamp = std::chrono::system_clock::now().time_since_epoch().count(); + z_owned_reply_t owned_reply; + z_reply_clone(&owned_reply, reply); client_data->add_new_reply( - std::make_unique(reply, received_timestamp)); - - // Since we took ownership of the reply, null it out here - *reply = z_reply_null(); + std::make_unique(owned_reply, received_timestamp)); } ///============================================================================= @@ -109,7 +100,7 @@ namespace rmw_zenoh_cpp { ///============================================================================= std::shared_ptr ClientData::make( - z_session_t session, + const z_loaned_session_t * session, const rmw_node_t * const node, const rmw_client_t * client, liveliness::NodeInfo node_info, @@ -235,29 +226,32 @@ ClientData::ClientData( } ///============================================================================= -bool ClientData::init(z_session_t session) +bool ClientData::init(const z_loaned_session_t * session) { - this->keyexpr_ = - z_keyexpr_new(this->entity_->topic_info().value().topic_keyexpr_.c_str()); + std::string topic_keyexpr = this->entity_->topic_info().value().topic_keyexpr_; auto free_ros_keyexpr = rcpputils::make_scope_exit( [this]() { z_drop(z_move(this->keyexpr_)); }); - if (!z_check(z_loan(this->keyexpr_))) { + if (z_keyexpr_from_str(&this->keyexpr_, topic_keyexpr.c_str()) != Z_OK) { RMW_SET_ERROR_MSG("unable to create zenoh keyexpr."); return false; } - this->token_ = zc_liveliness_declare_token( - session, - z_keyexpr(this->entity_->liveliness_keyexpr().c_str()), - NULL - ); + std::string liveliness_keyexpr = this->entity_->liveliness_keyexpr(); + z_view_keyexpr_t liveliness_ke; + z_view_keyexpr_from_str(&liveliness_ke, liveliness_keyexpr.c_str()); auto free_token = rcpputils::make_scope_exit( [this]() { z_drop(z_move(this->token_)); }); - if (!z_check(this->token_)) { + if(zc_liveliness_declare_token( + session, + &this->token_, + z_loan(liveliness_ke), + NULL + ) != Z_OK) + { RMW_ZENOH_LOG_ERROR_NAMED( "rmw_zenoh_cpp", "Unable to create liveliness token for the client."); @@ -277,13 +271,6 @@ liveliness::TopicInfo ClientData::topic_info() const return entity_->topic_info().value(); } -///============================================================================= -bool ClientData::liveliness_is_valid() const -{ - std::lock_guard lock(mutex_); - return zc_liveliness_token_check(&token_); -} - ///============================================================================= void ClientData::copy_gid(uint8_t out_gid[RMW_GID_STORAGE_SIZE]) const { @@ -301,14 +288,15 @@ void ClientData::add_new_reply(std::unique_ptr reply) reply_queue_.size() >= adapted_qos_profile.depth) { // Log warning if message is discarded due to hitting the queue depth - z_owned_str_t keystr = z_keyexpr_to_string(z_loan(keyexpr_)); + z_view_string_t keystr; + z_keyexpr_as_view_string(z_loan(keyexpr_), &keystr); RMW_ZENOH_LOG_ERROR_NAMED( "rmw_zenoh_cpp", "Query queue depth of %ld reached, discarding oldest Query " - "for client for %s", + "for client for %.*s", adapted_qos_profile.depth, - z_loan(keystr)); - z_drop(z_move(keystr)); + static_cast(z_string_len(z_loan(keystr))), + z_string_data(z_loan(keystr))); reply_queue_.pop_front(); } reply_queue_.emplace_back(std::move(reply)); @@ -338,16 +326,18 @@ rmw_ret_t ClientData::take_response( std::unique_ptr latest_reply = std::move(reply_queue_.front()); reply_queue_.pop_front(); - std::optional sample = latest_reply->get_sample(); - if (!sample) { + if (!latest_reply->get_sample().has_value()) { RMW_SET_ERROR_MSG("invalid reply sample"); return RMW_RET_ERROR; } + const z_loaned_sample_t * sample = latest_reply->get_sample().value(); // Object that manages the raw buffer + z_owned_slice_t payload; + z_bytes_to_slice(z_sample_payload(sample), &payload); eprosima::fastcdr::FastBuffer fastbuffer( - reinterpret_cast(const_cast(sample->payload.start)), - sample->payload.len); + reinterpret_cast(const_cast(z_slice_data(z_loan(payload)))), + z_slice_len(z_loan(payload))); // Object that serializes the data rmw_zenoh_cpp::Cdr deser(fastbuffer); @@ -361,28 +351,21 @@ rmw_ret_t ClientData::take_response( } // Fill in the request_header - request_header->request_id.sequence_number = - rmw_zenoh_cpp::get_int64_from_attachment(&sample->attachment, "sequence_number"); + rmw_zenoh_cpp::attachement_data_t attachment(z_sample_attachment(sample)); + request_header->request_id.sequence_number = attachment.sequence_number; if (request_header->request_id.sequence_number < 0) { RMW_SET_ERROR_MSG("Failed to get sequence_number from client call attachment"); return RMW_RET_ERROR; } - request_header->source_timestamp = - rmw_zenoh_cpp::get_int64_from_attachment(&sample->attachment, "source_timestamp"); + request_header->source_timestamp = attachment.source_timestamp; if (request_header->source_timestamp < 0) { RMW_SET_ERROR_MSG("Failed to get source_timestamp from client call attachment"); return RMW_RET_ERROR; } - if (!rmw_zenoh_cpp::get_gid_from_attachment( - &sample->attachment, - request_header->request_id.writer_guid)) - { - RMW_SET_ERROR_MSG("Could not get client gid from attachment"); - return RMW_RET_ERROR; - } - + memcpy(request_header->request_id.writer_guid, attachment.source_gid, RMW_GID_STORAGE_SIZE); request_header->received_timestamp = latest_reply->get_received_timestamp(); + z_drop(z_move(payload)); *taken = true; return RMW_RET_OK; @@ -436,28 +419,16 @@ rmw_ret_t ClientData::send_request( *sequence_id = sequence_number_++; // Send request - z_get_options_t opts = z_get_options_default(); - z_owned_bytes_map_t map = create_map_and_set_sequence_num( - *sequence_id, - [this](z_owned_bytes_map_t * map, const char * key) - { - uint8_t local_gid[RMW_GID_STORAGE_SIZE]; - entity_->copy_gid(local_gid); - z_bytes_t gid_bytes; - gid_bytes.len = RMW_GID_STORAGE_SIZE; - gid_bytes.start = local_gid; - z_bytes_map_insert_by_copy(map, z_bytes_new(key), gid_bytes); - }); - if (!z_check(map)) { - // create_map_and_set_sequence_num already set the error - return RMW_RET_ERROR; - } - auto always_free_attachment_map = rcpputils::make_scope_exit( - [&map]() { - z_bytes_map_drop(z_move(map)); - }); + z_get_options_t opts; + z_get_options_default(&opts); + z_owned_bytes_t attachment; + uint8_t local_gid[RMW_GID_STORAGE_SIZE]; + entity_->copy_gid(local_gid); + rmw_zenoh_cpp::create_map_and_set_sequence_num( + &attachment, *sequence_id, + local_gid); + opts.attachment = z_move(attachment); - opts.attachment = z_bytes_map_as_attachment(&map); opts.target = Z_QUERY_TARGET_ALL_COMPLETE; // The default timeout for a z_get query is 10 seconds and if a response is not received within // this window, the queryable will return an invalid reply. However, it is common for actions, @@ -468,15 +439,20 @@ rmw_ret_t ClientData::send_request( // which optimizes bandwidth. The default is "None", which imples replies may come in any order // and any number. opts.consolidation = z_query_consolidation_latest(); - opts.value.payload = z_bytes_t{data_length, reinterpret_cast(request_bytes)}; + + z_owned_bytes_t payload; + z_bytes_copy_from_buf( + &payload, reinterpret_cast(request_bytes), data_length); + opts.payload = z_move(payload); + // TODO(Yadunund): Once we switch to zenoh-cpp with lambda closures, // capture shared_from_this() instead of this. - z_owned_closure_reply_t zn_closure_reply = - z_closure(client_data_handler, client_data_drop, this); + z_owned_closure_reply_t callback; + z_closure(&callback, client_data_handler, client_data_drop, this); z_get( context_impl->session(), z_loan(keyexpr_), "", - z_move(zn_closure_reply), + z_move(callback), &opts); return RMW_RET_OK; @@ -534,12 +510,9 @@ void ClientData::_shutdown() } // Unregister this node from the ROS graph. - if (zc_liveliness_token_check(&token_)) { - zc_liveliness_undeclare_token(z_move(token_)); - } - if (z_check(z_loan(keyexpr_))) { - z_drop(z_move(keyexpr_)); - } + zc_liveliness_undeclare_token(z_move(token_)); + + z_drop(z_move(keyexpr_)); is_shutdown_ = true; } diff --git a/rmw_zenoh_cpp/src/detail/rmw_client_data.hpp b/rmw_zenoh_cpp/src/detail/rmw_client_data.hpp index eda4bf9c..d6650677 100644 --- a/rmw_zenoh_cpp/src/detail/rmw_client_data.hpp +++ b/rmw_zenoh_cpp/src/detail/rmw_client_data.hpp @@ -22,20 +22,13 @@ #include #include #include -#include #include -#include #include "event.hpp" #include "liveliness_utils.hpp" -#include "message_type_support.hpp" #include "service_type_support.hpp" -#include "type_support_common.hpp" #include "zenoh_utils.hpp" -#include "rcutils/allocator.h" - -#include "rmw/rmw.h" #include "rmw/ret_types.h" namespace rmw_zenoh_cpp @@ -47,7 +40,7 @@ class ClientData final : public std::enable_shared_from_this public: // Make a shared_ptr of ClientData. static std::shared_ptr make( - z_session_t session, + const z_loaned_session_t * session, const rmw_node_t * const node, const rmw_client_t * client, liveliness::NodeInfo node_info, @@ -60,9 +53,6 @@ class ClientData final : public std::enable_shared_from_this // Get a copy of the TopicInfo of this ClientData. liveliness::TopicInfo topic_info() const; - // Returns true if liveliness token is still valid. - bool liveliness_is_valid() const; - // Copy the GID of this ClientData into an rmw_gid_t. void copy_gid(uint8_t out_gid[RMW_GID_STORAGE_SIZE]) const; @@ -119,7 +109,7 @@ class ClientData final : public std::enable_shared_from_this std::shared_ptr response_type_support); // Initialize the Zenoh objects for this entity. - bool init(z_session_t session); + bool init(const z_loaned_session_t * session); // Shutdown this client (the mutex is expected to be held by the caller). void _shutdown(); 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 1a7e096c..7414b554 100644 --- a/rmw_zenoh_cpp/src/detail/rmw_context_impl_s.cpp +++ b/rmw_zenoh_cpp/src/detail/rmw_context_impl_s.cpp @@ -13,8 +13,8 @@ // limitations under the License. #include "rmw_context_impl_s.hpp" +#include -#include #include #include #include @@ -58,7 +58,7 @@ static std::mutex data_to_data_shared_ptr_map_mutex; static std::unordered_map> data_to_data_shared_ptr_map; -static void graph_sub_data_handler(const z_sample_t * sample, void * data); +static void graph_sub_data_handler(z_loaned_sample_t * sample, void * data); // Bundle all class members into a data struct which can be passed as a // weak ptr to various threads for thread-safe access without capturing @@ -88,20 +88,21 @@ class rmw_context_impl_s::Data final } // Check if shm is enabled. - z_owned_str_t shm_enabled = zc_config_get(z_loan(config), "transport/shared_memory/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. - session_ = z_open(z_move(config)); - if (!z_session_check(&session_)) { + if (z_open(&session_, z_move(config), NULL) != Z_OK) { + RMW_SET_ERROR_MSG("Error setting up zenoh session"); throw std::runtime_error("Error setting up zenoh session."); } auto close_session = rcpputils::make_scope_exit( [this]() { - z_close(z_move(session_)); + z_close(z_loan_mut(session_), NULL); }); // TODO(Yadunund) Move this check into a separate thread. @@ -147,60 +148,58 @@ class rmw_context_impl_s::Data final // the code will be simpler, and if we're just going to spin over the non-blocking // reads until we obtain responses, we'll just be hogging CPU time by convincing // the OS that we're doing actual work when it could instead park the thread. - z_owned_reply_channel_t channel = zc_reply_fifo_new(0); + z_owned_fifo_handler_reply_t handler; + z_owned_closure_reply_t closure; + z_fifo_channel_reply_new(&closure, &handler, SIZE_MAX - 1); + + + z_view_keyexpr_t keyexpr; + z_view_keyexpr_from_str(&keyexpr, liveliness_str.c_str()); zc_liveliness_get( - z_loan(session_), z_keyexpr(liveliness_str.c_str()), - z_move(channel.send), NULL); - z_owned_reply_t reply = z_reply_null(); - for (bool call_success = z_call(channel.recv, &reply); !call_success || z_check(reply); - call_success = z_call(channel.recv, &reply)) - { - if (!call_success) { - continue; - } - if (z_reply_is_ok(&reply)) { - z_sample_t sample = z_reply_ok(&reply); - z_owned_str_t keystr = z_keyexpr_to_string(sample.keyexpr); + z_loan(session_), z_loan(keyexpr), + z_move(closure), NULL); + + z_owned_reply_t reply; + while (z_recv(z_loan(handler), &reply) == Z_OK) { + if (z_reply_is_ok(z_loan(reply))) { + const z_loaned_sample_t * sample = z_reply_ok(z_loan(reply)); + z_view_string_t keystr; + z_keyexpr_as_view_string(z_sample_keyexpr(sample), &keystr); + std::string str(z_string_data(z_loan(keystr)), z_string_len(z_loan(keystr))); // Ignore tokens from the same session to avoid race conditions from this // query and the liveliness subscription. - graph_cache_->parse_put(z_loan(keystr), true); - z_drop(z_move(keystr)); + graph_cache_->parse_put(str, true); } else { RMW_ZENOH_LOG_DEBUG_NAMED( "rmw_zenoh_cpp", "[rmw_context_impl_s] z_call received an invalid reply.\n"); } + z_drop(z_move(reply)); } - z_drop(z_move(reply)); - z_drop(z_move(channel)); + z_drop(z_move(handler)); // Initialize the shm manager if shared_memory is enabled in the config. - shm_manager_ = std::nullopt; - if (shm_enabled._cstr != nullptr && - strcmp(shm_enabled._cstr, "true") == 0) + shm_provider_ = std::nullopt; + if (strncmp( + z_string_data(z_loan(shm_enabled)), + "true", + z_string_len(z_loan(shm_enabled))) == 0) { - char idstr[sizeof(zid.id) * 2 + 1]; // 2 bytes for each byte of the id, plus the trailing \0 - static constexpr size_t max_size_of_each = 3; // 2 for each byte, plus the trailing \0 - for (size_t i = 0; i < sizeof(zid.id); ++i) { - snprintf(idstr + 2 * i, max_size_of_each, "%02x", zid.id[i]); - } - idstr[sizeof(zid.id) * 2] = '\0'; - // TODO(yadunund): Can we get the size of the shm from the config even though it's not - // a standard parameter? - shm_manager_ = - zc_shm_manager_new( - z_loan(session_), - idstr, - SHM_BUFFER_SIZE_MB * 1024 * 1024); - if (!shm_manager_.has_value() || - !zc_shm_manager_check(&shm_manager_.value())) - { - throw std::runtime_error("Unable to create shm manager."); + // 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 a SHM provider."); + throw std::runtime_error("Unable to create shm provider."); } + shm_provider_ = provider; } - auto free_shm_manager = rcpputils::make_scope_exit( + auto free_shm_provider = rcpputils::make_scope_exit( [this]() { - if (shm_manager_.has_value()) { - z_drop(z_move(shm_manager_.value())); + if (shm_provider_.has_value()) { + z_drop(z_move(shm_provider_.value())); } }); @@ -210,26 +209,27 @@ class rmw_context_impl_s::Data final // Setup the liveliness subscriber to receives updates from the ROS graph // and update the graph cache. - auto sub_options = zc_liveliness_subscriber_options_null(); - z_owned_closure_sample_t callback = z_closure( - graph_sub_data_handler, nullptr, this); - graph_subscriber_ = zc_liveliness_declare_subscriber( - z_loan(session_), - z_keyexpr(liveliness_str.c_str()), - z_move(callback), - &sub_options); - zc_liveliness_subscriber_options_drop(z_move(sub_options)); + zc_liveliness_subscriber_options_t sub_options; + zc_liveliness_subscriber_options_default(&sub_options); + z_owned_closure_sample_t callback; + z_closure(&callback, graph_sub_data_handler, nullptr, this); + z_view_keyexpr_t liveliness_ke; + z_view_keyexpr_from_str(&liveliness_ke, liveliness_str.c_str()); auto undeclare_z_sub = rcpputils::make_scope_exit( [this]() { z_undeclare_subscriber(z_move(this->graph_subscriber_)); }); - if (!z_check(graph_subscriber_)) { + if (zc_liveliness_declare_subscriber( + z_loan(session_), + &graph_subscriber_, z_loan(liveliness_ke), + z_move(callback), &sub_options) != Z_OK) + { RMW_SET_ERROR_MSG("unable to create zenoh subscription"); throw std::runtime_error("Unable to subscribe to ROS graph updates."); } close_session.cancel(); - free_shm_manager.cancel(); + free_shm_provider.cancel(); undeclare_z_sub.cancel(); } @@ -257,8 +257,8 @@ class rmw_context_impl_s::Data final } z_undeclare_subscriber(z_move(graph_subscriber_)); - if (shm_manager_.has_value()) { - z_drop(z_move(shm_manager_.value())); + if (shm_provider_.has_value()) { + z_drop(z_move(shm_provider_.value())); } is_shutdown_ = true; @@ -267,7 +267,7 @@ class rmw_context_impl_s::Data final } // Close the zenoh session - if (z_close(z_move(session_)) < 0) { + if (z_close(z_loan_mut(session_), NULL) != Z_OK) { RMW_SET_ERROR_MSG("Error while closing zenoh session"); return RMW_RET_ERROR; } @@ -280,16 +280,16 @@ class rmw_context_impl_s::Data final return enclave_; } - z_session_t session() const + const z_loaned_session_t * session() const { std::lock_guard lock(mutex_); return z_loan(session_); } - std::optional & shm_manager() + std::optional & shm_provider() { std::lock_guard lock(mutex_); - return shm_manager_; + return shm_provider_; } rmw_guard_condition_t * graph_guard_condition() @@ -313,7 +313,7 @@ class rmw_context_impl_s::Data final bool session_is_valid() const { std::lock_guard lock(mutex_); - return z_check(session_); + return !z_session_is_closed(z_loan(session_)); } std::shared_ptr graph_cache() @@ -334,7 +334,7 @@ class rmw_context_impl_s::Data final } // Check that the Zenoh session is still valid. - if (!z_check(session_)) { + if (!session_is_valid()) { RMW_ZENOH_LOG_ERROR_NAMED( "rmw_zenoh_cpp", "Unable to create NodeData as Zenoh session is invalid."); @@ -424,7 +424,7 @@ class rmw_context_impl_s::Data final z_owned_session_t session_; // An optional SHM manager that is initialized of SHM is enabled in the // zenoh session config. - std::optional shm_manager_; + std::optional shm_provider_; // Graph cache. std::shared_ptr graph_cache_; // ROS graph liveliness subscriber. @@ -443,7 +443,7 @@ class rmw_context_impl_s::Data final }; ///============================================================================= -static void graph_sub_data_handler(const z_sample_t * sample, void * data) +static void graph_sub_data_handler(z_loaned_sample_t * sample, void * data) { z_view_string_t keystr; z_keyexpr_as_view_string(z_sample_keyexpr(sample), &keystr); @@ -469,7 +469,8 @@ static void graph_sub_data_handler(const z_sample_t * sample, void * data) } // Update the graph cache. - data_shared_ptr->update_graph_cache(sample->kind, keystr._cstr); + std::string str(z_string_data(z_loan(keystr)), z_string_len(z_loan(keystr))); + data_shared_ptr->update_graph_cache(z_sample_kind(sample), str); } ///============================================================================= @@ -489,17 +490,6 @@ rmw_context_impl_s::~rmw_context_impl_s() this->shutdown(); } -///============================================================================= -rmw_context_impl_s::~rmw_context_impl_s() -{ - // Don't touch Zenoh Session if the ROS process is exiting, - // it will cause panic. - if (!is_exiting) { - std::lock_guard lock(data_->mutex_); - z_drop(z_move(data_->session_)); - } -} - ///============================================================================= std::string rmw_context_impl_s::enclave() const { @@ -515,7 +505,7 @@ const z_loaned_session_t * rmw_context_impl_s::session() const ///============================================================================= std::optional & rmw_context_impl_s::shm_provider() { - return data_->shm_manager(); + return data_->shm_provider(); } ///============================================================================= diff --git a/rmw_zenoh_cpp/src/detail/rmw_node_data.cpp b/rmw_zenoh_cpp/src/detail/rmw_node_data.cpp index 24458529..2f7187b6 100644 --- a/rmw_zenoh_cpp/src/detail/rmw_node_data.cpp +++ b/rmw_zenoh_cpp/src/detail/rmw_node_data.cpp @@ -322,7 +322,7 @@ void NodeData::delete_service_data(const rmw_service_t * const service) ///============================================================================= bool NodeData::create_client_data( const rmw_client_t * const client, - z_session_t session, + const z_loaned_session_t * session, std::size_t id, const std::string & service_name, const rosidl_service_type_support_t * type_supports, diff --git a/rmw_zenoh_cpp/src/detail/rmw_node_data.hpp b/rmw_zenoh_cpp/src/detail/rmw_node_data.hpp index 52217965..0ad3bb6e 100644 --- a/rmw_zenoh_cpp/src/detail/rmw_node_data.hpp +++ b/rmw_zenoh_cpp/src/detail/rmw_node_data.hpp @@ -99,7 +99,7 @@ class NodeData final // Create a new ClientData for a given rmw_client_t. bool create_client_data( const rmw_client_t * const client, - z_session_t session, + const z_loaned_session_t * session, std::size_t id, const std::string & service_name, const rosidl_service_type_support_t * type_support, diff --git a/rmw_zenoh_cpp/src/detail/rmw_service_data.hpp b/rmw_zenoh_cpp/src/detail/rmw_service_data.hpp index cddaff88..a8f9d925 100644 --- a/rmw_zenoh_cpp/src/detail/rmw_service_data.hpp +++ b/rmw_zenoh_cpp/src/detail/rmw_service_data.hpp @@ -22,21 +22,14 @@ #include #include #include -#include #include #include #include "event.hpp" #include "liveliness_utils.hpp" -#include "message_type_support.hpp" #include "service_type_support.hpp" -#include "type_support_common.hpp" #include "zenoh_utils.hpp" -#include "rmw_data_types.hpp" -#include "rcutils/allocator.h" - -#include "rmw/rmw.h" #include "rmw/ret_types.h" namespace rmw_zenoh_cpp 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 8dcf8566..00000000 --- a/rmw_zenoh_cpp/src/detail/shm_context.cpp +++ /dev/null @@ -1,26 +0,0 @@ -// Copyright 2023 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. - -#include "shm_context.hpp" - -namespace rmw_zenoh_cpp -{ -///============================================================================= -#ifdef RMW_ZENOH_BUILD_WITH_SHARED_MEMORY -ShmContext::~ShmContext() -{ - z_drop(z_move(shm_provider)); -} -#endif -} // namespace rmw_zenoh_cpp diff --git a/rmw_zenoh_cpp/src/rmw_init_options.cpp b/rmw_zenoh_cpp/src/rmw_init_options.cpp index 783c5a6a..b5242035 100644 --- a/rmw_zenoh_cpp/src/rmw_init_options.cpp +++ b/rmw_zenoh_cpp/src/rmw_init_options.cpp @@ -16,13 +16,11 @@ #include #include "detail/identifier.hpp" -#include "detail/rmw_init_options_impl.hpp" #include "rcpputils/scope_exit.hpp" #include "rcutils/allocator.h" #include "rcutils/strdup.h" -#include "rcutils/types.h" #include "rmw/impl/cpp/macros.hpp" #include "rmw/init_options.h" diff --git a/rmw_zenoh_cpp/src/rmw_zenoh.cpp b/rmw_zenoh_cpp/src/rmw_zenoh.cpp index 55471207..d1d2fb63 100644 --- a/rmw_zenoh_cpp/src/rmw_zenoh.cpp +++ b/rmw_zenoh_cpp/src/rmw_zenoh.cpp @@ -19,24 +19,19 @@ #include #include #include -#include #include -#include #include #include -#include "detail/attachment_helpers.hpp" #include "detail/cdr.hpp" #include "detail/guard_condition.hpp" #include "detail/identifier.hpp" +#include "detail/logging.hpp" #include "detail/liveliness_utils.hpp" -#include "detail/logging_macros.hpp" #include "detail/message_type_support.hpp" -#include "detail/qos.hpp" #include "detail/rmw_context_impl_s.hpp" #include "detail/serialization_format.hpp" #include "detail/type_support_common.hpp" -#include "detail/zenoh_utils.hpp" #include "rcpputils/scope_exit.hpp" #include "rcutils/strdup.h" @@ -46,6 +41,7 @@ #include "rmw/impl/cpp/macros.hpp" #include "rmw/ret_types.h" #include "rmw/rmw.h" +#include "rmw/types.h" #include "rmw/validate_namespace.h" #include "rmw/validate_node_name.h" diff --git a/zenoh_c_vendor/CMakeLists.txt b/zenoh_c_vendor/CMakeLists.txt index ded765de..086ea5db 100644 --- a/zenoh_c_vendor/CMakeLists.txt +++ b/zenoh_c_vendor/CMakeLists.txt @@ -26,7 +26,7 @@ set(ZENOHC_CARGO_FLAGS "--no-default-features$--features=shared-memor # - https://github.com/eclipse-zenoh/zenoh-c/pull/620 (fix ze_querying_subscriber_get API to query newly discovered publishers) ament_vendor(zenoh_c_vendor VCS_URL https://github.com/eclipse-zenoh/zenoh-c.git - VCS_VERSION a57fda736d2f8866c06509f34b5bc73e372c6aaf + VCS_VERSION 4b759d4e4d35a97d7b20b5c4003b8b764a10f679 CMAKE_ARGS "-DZENOHC_CARGO_FLAGS=${ZENOHC_CARGO_FLAGS}" "-DZENOHC_BUILD_WITH_UNSTABLE_API=TRUE"