Skip to content

Commit 8bca9d7

Browse files
authored
refactor: wrap the zenoh session with a shared pointer (#333)
* refactor: wrap the zenoh session with a shared pointer * fixup! refactor: wrap the zenoh session with a shared pointer * chore: remove the automatically added headers * fix: apply the suggested change * fix: hold the session at the right place
1 parent 7fcd074 commit 8bca9d7

14 files changed

+120
-55
lines changed

rmw_zenoh_cpp/src/detail/rmw_client_data.cpp

+10-5
Original file line numberDiff line numberDiff line change
@@ -105,7 +105,7 @@ namespace rmw_zenoh_cpp
105105
{
106106
///=============================================================================
107107
std::shared_ptr<ClientData> ClientData::make(
108-
const z_loaned_session_t * session,
108+
std::shared_ptr<ZenohSession> session,
109109
const rmw_node_t * const node,
110110
const rmw_client_t * client,
111111
liveliness::NodeInfo node_info,
@@ -167,7 +167,7 @@ std::shared_ptr<ClientData> ClientData::make(
167167

168168
std::size_t domain_id = node_info.domain_id_;
169169
auto entity = liveliness::Entity::make(
170-
z_info_zid(session),
170+
z_info_zid(session->loan()),
171171
std::to_string(node_id),
172172
std::to_string(service_id),
173173
liveliness::EntityType::Client,
@@ -192,6 +192,7 @@ std::shared_ptr<ClientData> ClientData::make(
192192
node,
193193
client,
194194
entity,
195+
session,
195196
request_members,
196197
response_members,
197198
request_type_support,
@@ -211,13 +212,15 @@ ClientData::ClientData(
211212
const rmw_node_t * rmw_node,
212213
const rmw_client_t * rmw_client,
213214
std::shared_ptr<liveliness::Entity> entity,
215+
std::shared_ptr<ZenohSession> sess,
214216
const void * request_type_support_impl,
215217
const void * response_type_support_impl,
216218
std::shared_ptr<RequestTypeSupport> request_type_support,
217219
std::shared_ptr<ResponseTypeSupport> response_type_support)
218220
: rmw_node_(rmw_node),
219221
rmw_client_(rmw_client),
220222
entity_(std::move(entity)),
223+
sess_(std::move(sess)),
221224
request_type_support_impl_(request_type_support_impl),
222225
response_type_support_impl_(response_type_support_impl),
223226
request_type_support_(request_type_support),
@@ -232,7 +235,7 @@ ClientData::ClientData(
232235
}
233236

234237
///=============================================================================
235-
bool ClientData::init(const z_loaned_session_t * session)
238+
bool ClientData::init(std::shared_ptr<ZenohSession> session)
236239
{
237240
if (z_keyexpr_from_str(
238241
&this->keyexpr_,
@@ -250,7 +253,7 @@ bool ClientData::init(const z_loaned_session_t * session)
250253
z_view_keyexpr_t liveliness_ke;
251254
z_view_keyexpr_from_str(&liveliness_ke, liveliness_keyexpr.c_str());
252255
if (z_liveliness_declare_token(
253-
session,
256+
session->loan(),
254257
&this->token_,
255258
z_loan(liveliness_ke),
256259
NULL
@@ -266,6 +269,7 @@ bool ClientData::init(const z_loaned_session_t * session)
266269
z_drop(z_move(this->token_));
267270
});
268271

272+
sess_ = session;
269273
initialized_ = true;
270274

271275
free_ros_keyexpr.cancel();
@@ -470,7 +474,7 @@ rmw_ret_t ClientData::send_request(
470474
z_owned_closure_reply_t zn_closure_reply;
471475
z_closure(&zn_closure_reply, client_data_handler, client_data_drop, this);
472476
z_get(
473-
context_impl->session(),
477+
sess_->loan(),
474478
z_loan(keyexpr_), "",
475479
z_move(zn_closure_reply),
476480
&opts);
@@ -535,6 +539,7 @@ void ClientData::_shutdown()
535539
z_drop(z_move(keyexpr_));
536540
}
537541

542+
sess_.reset();
538543
is_shutdown_ = true;
539544
}
540545

rmw_zenoh_cpp/src/detail/rmw_client_data.hpp

+5-2
Original file line numberDiff line numberDiff line change
@@ -47,7 +47,7 @@ class ClientData final : public std::enable_shared_from_this<ClientData>
4747
public:
4848
// Make a shared_ptr of ClientData.
4949
static std::shared_ptr<ClientData> make(
50-
const z_loaned_session_t * session,
50+
std::shared_ptr<ZenohSession> session,
5151
const rmw_node_t * const node,
5252
const rmw_client_t * client,
5353
liveliness::NodeInfo node_info,
@@ -113,13 +113,14 @@ class ClientData final : public std::enable_shared_from_this<ClientData>
113113
const rmw_node_t * rmw_node,
114114
const rmw_client_t * client,
115115
std::shared_ptr<liveliness::Entity> entity,
116+
std::shared_ptr<ZenohSession> sess,
116117
const void * request_type_support_impl,
117118
const void * response_type_support_impl,
118119
std::shared_ptr<RequestTypeSupport> request_type_support,
119120
std::shared_ptr<ResponseTypeSupport> response_type_support);
120121

121122
// Initialize the Zenoh objects for this entity.
122-
bool init(const z_loaned_session_t * session);
123+
bool init(std::shared_ptr<ZenohSession> session);
123124

124125
// Shutdown this client (the mutex is expected to be held by the caller).
125126
void _shutdown();
@@ -131,6 +132,8 @@ class ClientData final : public std::enable_shared_from_this<ClientData>
131132
const rmw_client_t * rmw_client_;
132133
// The Entity generated for the service.
133134
std::shared_ptr<liveliness::Entity> entity_;
135+
// A shared session.
136+
std::shared_ptr<ZenohSession> sess_;
134137
// An owned keyexpression.
135138
z_owned_keyexpr_t keyexpr_;
136139
// Liveliness token for the service.

rmw_zenoh_cpp/src/detail/rmw_context_impl_s.cpp

+23-20
Original file line numberDiff line numberDiff line change
@@ -36,6 +36,7 @@
3636

3737
#include "rcpputils/scope_exit.hpp"
3838
#include "rmw/error_handling.h"
39+
#include "zenoh_utils.hpp"
3940

4041
// Megabytes of SHM to reserve.
4142
// TODO(clalancette): Make this configurable, or get it from the configuration
@@ -86,13 +87,18 @@ class rmw_context_impl_s::Data final
8687
});
8788

8889
// Initialize the zenoh session.
89-
if (z_open(&session_, z_move(config), NULL) != Z_OK) {
90+
z_owned_session_t raw_session;
91+
if (z_open(&raw_session, z_move(config), NULL) != Z_OK) {
9092
RMW_SET_ERROR_MSG("Error setting up zenoh session.");
9193
throw std::runtime_error("Error setting up zenoh session.");
9294
}
95+
if (session_ != nullptr) {
96+
session_.reset();
97+
}
98+
session_ = std::make_shared<rmw_zenoh_cpp::ZenohSession>(raw_session);
9399
auto close_session = rcpputils::make_scope_exit(
94-
[this]() {
95-
z_close(z_loan_mut(session_), NULL);
100+
[&raw_session]() {
101+
z_close(z_loan_mut(raw_session), NULL);
96102
});
97103

98104
// Verify if the zenoh router is running if configured.
@@ -102,7 +108,7 @@ class rmw_context_impl_s::Data final
102108
uint64_t connection_attempts = 0;
103109
constexpr std::chrono::milliseconds sleep_time(1000);
104110
constexpr int64_t ticks_between_print(std::chrono::milliseconds(1000) / sleep_time);
105-
while ((ret = rmw_zenoh_cpp::zenoh_router_check(z_loan(session_))) != RMW_RET_OK) {
111+
while ((ret = rmw_zenoh_cpp::zenoh_router_check(session_->loan())) != RMW_RET_OK) {
106112
if ((connection_attempts % ticks_between_print) == 0) {
107113
RMW_ZENOH_LOG_WARN_NAMED(
108114
"rmw_zenoh_cpp",
@@ -117,7 +123,7 @@ class rmw_context_impl_s::Data final
117123
}
118124

119125
// Initialize the graph cache.
120-
const z_id_t zid = z_info_zid(z_loan(session_));
126+
const z_id_t zid = z_info_zid(session_->loan());
121127
graph_cache_ = std::make_shared<rmw_zenoh_cpp::GraphCache>(zid);
122128
// Setup liveliness subscriptions for discovery.
123129
std::string liveliness_str = rmw_zenoh_cpp::liveliness::subscription_token(domain_id);
@@ -144,7 +150,7 @@ class rmw_context_impl_s::Data final
144150
z_view_keyexpr_t keyexpr;
145151
z_view_keyexpr_from_str(&keyexpr, liveliness_str.c_str());
146152
z_liveliness_get(
147-
z_loan(session_), z_loan(keyexpr),
153+
session_->loan(), z_loan(keyexpr),
148154
z_move(closure), NULL);
149155
z_owned_reply_t reply;
150156
while (z_recv(z_loan(handler), &reply) == Z_OK) {
@@ -203,7 +209,7 @@ class rmw_context_impl_s::Data final
203209
z_view_keyexpr_t liveliness_ke;
204210
z_view_keyexpr_from_str(&liveliness_ke, liveliness_str.c_str());
205211
if (z_liveliness_declare_subscriber(
206-
z_loan(session_),
212+
session_->loan(),
207213
&graph_subscriber_, z_loan(liveliness_ke),
208214
z_move(callback), &sub_options) != Z_OK)
209215
{
@@ -240,11 +246,8 @@ class rmw_context_impl_s::Data final
240246
// to avoid an AB/BA deadlock if shutdown is racing with graph_sub_data_handler().
241247
}
242248

243-
// Close the zenoh session
244-
if (z_close(z_loan_mut(session_), NULL) != Z_OK) {
245-
RMW_SET_ERROR_MSG("Error while closing zenoh session");
246-
return RMW_RET_ERROR;
247-
}
249+
// Drop the shared session.
250+
session_.reset();
248251

249252
return RMW_RET_OK;
250253
}
@@ -255,10 +258,10 @@ class rmw_context_impl_s::Data final
255258
return enclave_;
256259
}
257260

258-
const z_loaned_session_t * session() const
261+
std::shared_ptr<rmw_zenoh_cpp::ZenohSession> session() const
259262
{
260263
std::lock_guard<std::recursive_mutex> lock(mutex_);
261-
return z_loan(session_);
264+
return session_;
262265
}
263266

264267
std::optional<z_owned_shm_provider_t> & shm_provider()
@@ -288,7 +291,7 @@ class rmw_context_impl_s::Data final
288291
bool session_is_valid() const
289292
{
290293
std::lock_guard<std::recursive_mutex> lock(mutex_);
291-
return !z_session_is_closed(z_loan(session_));
294+
return !z_session_is_closed(session_->loan());
292295
}
293296

294297
std::shared_ptr<rmw_zenoh_cpp::GraphCache> graph_cache()
@@ -309,7 +312,7 @@ class rmw_context_impl_s::Data final
309312
}
310313

311314
// Check that the Zenoh session is still valid.
312-
if (z_session_is_closed(z_loan(session_))) {
315+
if (z_session_is_closed(session_->loan())) {
313316
RMW_ZENOH_LOG_ERROR_NAMED(
314317
"rmw_zenoh_cpp",
315318
"Unable to create NodeData as Zenoh session is invalid.");
@@ -319,7 +322,7 @@ class rmw_context_impl_s::Data final
319322
auto node_data = rmw_zenoh_cpp::NodeData::make(
320323
node,
321324
this->get_next_entity_id(),
322-
z_loan(session_),
325+
session_->loan(),
323326
domain_id_,
324327
ns,
325328
node_name,
@@ -395,8 +398,8 @@ class rmw_context_impl_s::Data final
395398
std::size_t domain_id_;
396399
// Enclave, name used to find security artifacts in a sros2 keystore.
397400
std::string enclave_;
398-
// An owned session.
399-
z_owned_session_t session_;
401+
// A shared session.
402+
std::shared_ptr<rmw_zenoh_cpp::ZenohSession> session_{nullptr};
400403
// An optional SHM manager that is initialized of SHM is enabled in the
401404
// zenoh session config.
402405
std::optional<z_owned_shm_provider_t> shm_provider_;
@@ -472,7 +475,7 @@ std::string rmw_context_impl_s::enclave() const
472475
}
473476

474477
///=============================================================================
475-
const z_loaned_session_t * rmw_context_impl_s::session() const
478+
std::shared_ptr<rmw_zenoh_cpp::ZenohSession> rmw_context_impl_s::session() const
476479
{
477480
return data_->session();
478481
}

rmw_zenoh_cpp/src/detail/rmw_context_impl_s.hpp

+2-2
Original file line numberDiff line numberDiff line change
@@ -47,8 +47,8 @@ class rmw_context_impl_s final
4747
// Get a copy of the enclave.
4848
std::string enclave() const;
4949

50-
// Loan the Zenoh session.
51-
const z_loaned_session_t * session() const;
50+
// Share the Zenoh session.
51+
std::shared_ptr<rmw_zenoh_cpp::ZenohSession> session() const;
5252

5353
// Get a reference to the shm_provider.
5454
// Note: This is not thread-safe.

rmw_zenoh_cpp/src/detail/rmw_node_data.cpp

+4-4
Original file line numberDiff line numberDiff line change
@@ -121,7 +121,7 @@ std::size_t NodeData::id() const
121121
///=============================================================================
122122
bool NodeData::create_pub_data(
123123
const rmw_publisher_t * const publisher,
124-
const z_loaned_session_t * session,
124+
std::shared_ptr<ZenohSession> session,
125125
std::size_t id,
126126
const std::string & topic_name,
127127
const rosidl_message_type_support_t * type_support,
@@ -187,7 +187,7 @@ void NodeData::delete_pub_data(const rmw_publisher_t * const publisher)
187187
///=============================================================================
188188
bool NodeData::create_sub_data(
189189
const rmw_subscription_t * const subscription,
190-
const z_loaned_session_t * session,
190+
std::shared_ptr<ZenohSession> session,
191191
std::shared_ptr<GraphCache> graph_cache,
192192
std::size_t id,
193193
const std::string & topic_name,
@@ -255,7 +255,7 @@ void NodeData::delete_sub_data(const rmw_subscription_t * const subscription)
255255
///=============================================================================
256256
bool NodeData::create_service_data(
257257
const rmw_service_t * const service,
258-
const z_loaned_session_t * session,
258+
std::shared_ptr<ZenohSession> session,
259259
std::size_t id,
260260
const std::string & service_name,
261261
const rosidl_service_type_support_t * type_supports,
@@ -322,7 +322,7 @@ void NodeData::delete_service_data(const rmw_service_t * const service)
322322
///=============================================================================
323323
bool NodeData::create_client_data(
324324
const rmw_client_t * const client,
325-
const z_loaned_session_t * session,
325+
std::shared_ptr<ZenohSession> session,
326326
std::size_t id,
327327
const std::string & service_name,
328328
const rosidl_service_type_support_t * type_supports,

rmw_zenoh_cpp/src/detail/rmw_node_data.hpp

+4-4
Original file line numberDiff line numberDiff line change
@@ -55,7 +55,7 @@ class NodeData final
5555
// Create a new PublisherData for a given rmw_publisher_t.
5656
bool create_pub_data(
5757
const rmw_publisher_t * const publisher,
58-
const z_loaned_session_t * session,
58+
std::shared_ptr<ZenohSession> sess,
5959
std::size_t id,
6060
const std::string & topic_name,
6161
const rosidl_message_type_support_t * type_support,
@@ -70,7 +70,7 @@ class NodeData final
7070
// Create a new SubscriptionData for a given rmw_subscription_t.
7171
bool create_sub_data(
7272
const rmw_subscription_t * const subscription,
73-
const z_loaned_session_t * session,
73+
std::shared_ptr<ZenohSession> sess,
7474
std::shared_ptr<GraphCache> graph_cache,
7575
std::size_t id,
7676
const std::string & topic_name,
@@ -86,7 +86,7 @@ class NodeData final
8686
// Create a new ServiceData for a given rmw_service_t.
8787
bool create_service_data(
8888
const rmw_service_t * const service,
89-
const z_loaned_session_t * session,
89+
std::shared_ptr<ZenohSession> session,
9090
std::size_t id,
9191
const std::string & service_name,
9292
const rosidl_service_type_support_t * type_support,
@@ -101,7 +101,7 @@ class NodeData final
101101
// Create a new ClientData for a given rmw_client_t.
102102
bool create_client_data(
103103
const rmw_client_t * const client,
104-
const z_loaned_session_t * session,
104+
std::shared_ptr<ZenohSession> session,
105105
std::size_t id,
106106
const std::string & service_name,
107107
const rosidl_service_type_support_t * type_support,

0 commit comments

Comments
 (0)