diff --git a/rmw_zenoh_cpp/src/detail/liveliness_utils.cpp b/rmw_zenoh_cpp/src/detail/liveliness_utils.cpp index 1969c633..2d27e5c4 100644 --- a/rmw_zenoh_cpp/src/detail/liveliness_utils.cpp +++ b/rmw_zenoh_cpp/src/detail/liveliness_utils.cpp @@ -453,42 +453,6 @@ Entity::Entity( ///============================================================================= std::shared_ptr Entity::make( - z_id_t zid, - const std::string & nid, - const std::string & id, - EntityType type, - NodeInfo node_info, - std::optional topic_info) -{ - if (id.empty()) { - RCUTILS_SET_ERROR_MSG("Invalid id."); - return nullptr; - } - if (entity_to_str.find(type) == entity_to_str.end()) { - RCUTILS_SET_ERROR_MSG("Invalid entity type."); - return nullptr; - } - if (node_info.ns_.empty() || node_info.name_.empty()) { - RCUTILS_SET_ERROR_MSG("Invalid node_info for entity."); - return nullptr; - } - if (type != EntityType::Node && !topic_info.has_value()) { - RCUTILS_SET_ERROR_MSG("Invalid topic_info for entity."); - return nullptr; - } - - return std::make_shared( - Entity{ - zid_to_str(zid), - nid, - id, - std::move(type), - std::move(node_info), - std::move(topic_info)}); -} - -///============================================================================= -std::shared_ptr Entity::make_cpp( zenoh::Id zid, const std::string & nid, const std::string & id, diff --git a/rmw_zenoh_cpp/src/detail/liveliness_utils.hpp b/rmw_zenoh_cpp/src/detail/liveliness_utils.hpp index 1cd2e522..8f5603e3 100644 --- a/rmw_zenoh_cpp/src/detail/liveliness_utils.hpp +++ b/rmw_zenoh_cpp/src/detail/liveliness_utils.hpp @@ -128,14 +128,6 @@ class Entity /// @param topic_info An optional topic information for relevant entities. /// @return An entity if all inputs are valid. This way no invalid entities can be created. static EntityPtr make( - z_id_t zid, - const std::string & nid, - const std::string & id, - EntityType type, - NodeInfo node_info, - std::optional topic_info = std::nullopt); - - static EntityPtr make_cpp( zenoh::Id zid, const std::string & nid, const std::string & id, 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 9f539756..cecea380 100644 --- a/rmw_zenoh_cpp/src/detail/rmw_context_impl_s.cpp +++ b/rmw_zenoh_cpp/src/detail/rmw_context_impl_s.cpp @@ -84,7 +84,6 @@ void rmw_context_impl_s::graph_sub_data_handler(z_loaned_sample_t * sample, void rmw_context_impl_s::Data::Data( std::size_t domain_id, const std::string & enclave, - z_owned_session_t session, std::shared_ptr session_cpp, const std::string & liveliness_str, std::shared_ptr graph_cache @@ -94,7 +93,6 @@ rmw_context_impl_s::Data::Data( ) : enclave_(std::move(enclave)), domain_id_(std::move(domain_id)), - session_(std::move(session)), session_cpp_(session_cpp), liveliness_str_(std::move(liveliness_str)), graph_cache_(std::move(graph_cache)), @@ -187,7 +185,7 @@ rmw_ret_t rmw_context_impl_s::Data::subscribe_to_ros_graph() z_undeclare_subscriber(z_move(this->graph_subscriber_)); }); if (zc_liveliness_declare_subscriber( - z_loan(session_), + z_loan(session_cpp_->_0), &graph_subscriber_, z_loan(keyexpr), z_move(callback), &sub_options) != Z_OK) { @@ -366,7 +364,6 @@ rmw_context_impl_s::rmw_context_impl_s( data_ = std::make_shared( domain_id, std::move(enclave), - std::move(session->_0), std::move(session), std::move(liveliness_str), std::move(graph_cache) @@ -397,7 +394,7 @@ std::string rmw_context_impl_s::enclave() const const z_loaned_session_t * rmw_context_impl_s::session() const { std::lock_guard lock(data_->mutex_); - return z_loan(data_->session_); + return z_loan(data_->session_cpp_->_0); } const std::shared_ptr rmw_context_impl_s::session_cpp() const 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 ef5a79cf..e3f3240f 100644 --- a/rmw_zenoh_cpp/src/detail/rmw_context_impl_s.hpp +++ b/rmw_zenoh_cpp/src/detail/rmw_context_impl_s.hpp @@ -106,7 +106,6 @@ class rmw_context_impl_s final Data( std::size_t domain_id, const std::string & enclave, - z_owned_session_t session, std::shared_ptr session_cpp, const std::string & liveliness_str, std::shared_ptr graph_cache @@ -133,7 +132,7 @@ class rmw_context_impl_s final // The ROS domain id of this context. std::size_t domain_id_; // An owned session. - z_owned_session_t session_; + // z_owned_session_t session_; std::shared_ptr session_cpp_; // Liveliness keyexpr string to subscribe to for ROS graph changes. std::string liveliness_str_; diff --git a/rmw_zenoh_cpp/src/detail/rmw_node_data.cpp b/rmw_zenoh_cpp/src/detail/rmw_node_data.cpp index 11131231..3942daef 100644 --- a/rmw_zenoh_cpp/src/detail/rmw_node_data.cpp +++ b/rmw_zenoh_cpp/src/detail/rmw_node_data.cpp @@ -37,7 +37,7 @@ std::shared_ptr NodeData::make( const std::string & enclave) { // Create the entity. - auto entity = rmw_zenoh_cpp::liveliness::Entity::make_cpp( + auto entity = rmw_zenoh_cpp::liveliness::Entity::make( session->get_zid(), std::to_string(id), std::to_string(id), diff --git a/rmw_zenoh_cpp/src/detail/rmw_publisher_data.cpp b/rmw_zenoh_cpp/src/detail/rmw_publisher_data.cpp index c28233e7..815de019 100644 --- a/rmw_zenoh_cpp/src/detail/rmw_publisher_data.cpp +++ b/rmw_zenoh_cpp/src/detail/rmw_publisher_data.cpp @@ -78,7 +78,7 @@ std::shared_ptr PublisherData::make( }); std::size_t domain_id = node_info.domain_id_; - auto entity = liveliness::Entity::make_cpp( + auto entity = liveliness::Entity::make( session->get_zid(), std::to_string(node_id), std::to_string(publisher_id), diff --git a/rmw_zenoh_cpp/src/detail/rmw_service_data.cpp b/rmw_zenoh_cpp/src/detail/rmw_service_data.cpp index 66721511..c9ae1e26 100644 --- a/rmw_zenoh_cpp/src/detail/rmw_service_data.cpp +++ b/rmw_zenoh_cpp/src/detail/rmw_service_data.cpp @@ -121,7 +121,7 @@ std::shared_ptr ServiceData::make( }); std::size_t domain_id = node_info.domain_id_; - auto entity = liveliness::Entity::make_cpp( + auto entity = liveliness::Entity::make( session->get_zid(), std::to_string(node_id), std::to_string(service_id), diff --git a/rmw_zenoh_cpp/src/detail/rmw_subscription_data.cpp b/rmw_zenoh_cpp/src/detail/rmw_subscription_data.cpp index 9658a5c1..2450b0d3 100644 --- a/rmw_zenoh_cpp/src/detail/rmw_subscription_data.cpp +++ b/rmw_zenoh_cpp/src/detail/rmw_subscription_data.cpp @@ -132,7 +132,7 @@ std::shared_ptr SubscriptionData::make( // Everything above succeeded and is setup properly. Now declare a subscriber // with Zenoh; after this, callbacks may come in at any time. std::size_t domain_id = node_info.domain_id_; - auto entity = liveliness::Entity::make_cpp( + auto entity = liveliness::Entity::make( session->get_zid(), std::to_string(node_id), std::to_string(subscription_id), diff --git a/rmw_zenoh_cpp/src/rmw_zenoh.cpp b/rmw_zenoh_cpp/src/rmw_zenoh.cpp index 0d30ac8d..9f7d0daf 100644 --- a/rmw_zenoh_cpp/src/rmw_zenoh.cpp +++ b/rmw_zenoh_cpp/src/rmw_zenoh.cpp @@ -1568,7 +1568,7 @@ rmw_create_client( node_data, "NodeData not found.", return nullptr); - client_data->entity = rmw_zenoh_cpp::liveliness::Entity::make_cpp( + client_data->entity = rmw_zenoh_cpp::liveliness::Entity::make( session->get_zid(), std::to_string(node_data->id()), std::to_string(