Skip to content

Commit f8e85b1

Browse files
committed
wrap the zenoh session with a shared pointer
Signed-off-by: Alejandro Hernández Cordero <ahcorde@gmail.com>
1 parent a6a09f4 commit f8e85b1

11 files changed

+48
-21
lines changed

rmw_zenoh_cpp/src/detail/rmw_client_data.cpp

+4-2
Original file line numberDiff line numberDiff line change
@@ -47,7 +47,7 @@ namespace rmw_zenoh_cpp
4747
{
4848
///=============================================================================
4949
std::shared_ptr<ClientData> ClientData::make(
50-
const std::shared_ptr<zenoh::Session> & session,
50+
std::shared_ptr<zenoh::Session> session,
5151
const rmw_node_t * const node,
5252
const rmw_client_t * client,
5353
liveliness::NodeInfo node_info,
@@ -174,7 +174,7 @@ ClientData::ClientData(
174174
}
175175

176176
///=============================================================================
177-
bool ClientData::init(const std::shared_ptr<zenoh::Session> & session)
177+
bool ClientData::init(const std::shared_ptr<zenoh::Session> session)
178178
{
179179
std::string topic_keyexpr = this->entity_->topic_info().value().topic_keyexpr_;
180180
keyexpr_ = zenoh::KeyExpr(topic_keyexpr);
@@ -192,6 +192,7 @@ bool ClientData::init(const std::shared_ptr<zenoh::Session> & session)
192192
return false;
193193
}
194194

195+
sess_ = session;
195196
initialized_ = true;
196197

197198
return true;
@@ -515,6 +516,7 @@ void ClientData::_shutdown()
515516
return;
516517
}
517518

519+
sess_.reset();
518520
is_shutdown_ = true;
519521
}
520522

rmw_zenoh_cpp/src/detail/rmw_client_data.hpp

+4-2
Original file line numberDiff line numberDiff line change
@@ -48,7 +48,7 @@ class ClientData final : public std::enable_shared_from_this<ClientData>
4848
public:
4949
// Make a shared_ptr of ClientData.
5050
static std::shared_ptr<ClientData> make(
51-
const std::shared_ptr<zenoh::Session> & session,
51+
std::shared_ptr<zenoh::Session> session,
5252
const rmw_node_t * const node,
5353
const rmw_client_t * client,
5454
liveliness::NodeInfo node_info,
@@ -120,7 +120,7 @@ class ClientData final : public std::enable_shared_from_this<ClientData>
120120
std::shared_ptr<ResponseTypeSupport> response_type_support);
121121

122122
// Initialize the Zenoh objects for this entity.
123-
bool init(const std::shared_ptr<zenoh::Session> & session);
123+
bool init(const std::shared_ptr<zenoh::Session> session);
124124

125125
// Shutdown this client (the mutex is expected to be held by the caller).
126126
void _shutdown();
@@ -132,6 +132,8 @@ class ClientData final : public std::enable_shared_from_this<ClientData>
132132
const rmw_client_t * rmw_client_;
133133
// The Entity generated for the service.
134134
std::shared_ptr<liveliness::Entity> entity_;
135+
// A shared session.
136+
std::shared_ptr<zenoh::Session> sess_;
135137
// An owned keyexpression.
136138
std::optional<zenoh::KeyExpr> keyexpr_;
137139
// Liveliness token for the service.

rmw_zenoh_cpp/src/detail/rmw_context_impl_s.cpp

+1-1
Original file line numberDiff line numberDiff line change
@@ -262,12 +262,12 @@ class rmw_context_impl_s::Data final
262262
return RMW_RET_ERROR;
263263
}
264264

265+
session_.reset();
265266
is_shutdown_ = true;
266267

267268
// We specifically do *not* hold the mutex_ while tearing down the session; this allows us
268269
// to avoid an AB/BA deadlock if shutdown is racing with graph_sub_data_handler().
269270
}
270-
session_.reset();
271271
return RMW_RET_OK;
272272
}
273273

rmw_zenoh_cpp/src/detail/rmw_node_data.cpp

+5-5
Original file line numberDiff line numberDiff line change
@@ -30,7 +30,7 @@ namespace rmw_zenoh_cpp
3030
std::shared_ptr<NodeData> NodeData::make(
3131
const rmw_node_t * const node,
3232
std::size_t id,
33-
const std::shared_ptr<zenoh::Session> & session,
33+
std::shared_ptr<zenoh::Session> session,
3434
std::size_t domain_id,
3535
const std::string & namespace_,
3636
const std::string & node_name,
@@ -118,7 +118,7 @@ std::size_t NodeData::id() const
118118
///=============================================================================
119119
bool NodeData::create_pub_data(
120120
const rmw_publisher_t * const publisher,
121-
const std::shared_ptr<zenoh::Session> & session,
121+
std::shared_ptr<zenoh::Session> session,
122122
std::size_t id,
123123
const std::string & topic_name,
124124
const rosidl_message_type_support_t * type_support,
@@ -184,7 +184,7 @@ void NodeData::delete_pub_data(const rmw_publisher_t * const publisher)
184184
///=============================================================================
185185
bool NodeData::create_sub_data(
186186
const rmw_subscription_t * const subscription,
187-
const std::shared_ptr<zenoh::Session> & session,
187+
std::shared_ptr<zenoh::Session> session,
188188
std::shared_ptr<GraphCache> graph_cache,
189189
std::size_t id,
190190
const std::string & topic_name,
@@ -252,7 +252,7 @@ void NodeData::delete_sub_data(const rmw_subscription_t * const subscription)
252252
///=============================================================================
253253
bool NodeData::create_service_data(
254254
const rmw_service_t * const service,
255-
const std::shared_ptr<zenoh::Session> & session,
255+
std::shared_ptr<zenoh::Session> session,
256256
std::size_t id,
257257
const std::string & service_name,
258258
const rosidl_service_type_support_t * type_supports,
@@ -319,7 +319,7 @@ void NodeData::delete_service_data(const rmw_service_t * const service)
319319
///=============================================================================
320320
bool NodeData::create_client_data(
321321
const rmw_client_t * const client,
322-
const std::shared_ptr<zenoh::Session> & session,
322+
std::shared_ptr<zenoh::Session> session,
323323
std::size_t id,
324324
const std::string & service_name,
325325
const rosidl_service_type_support_t * type_supports,

rmw_zenoh_cpp/src/detail/rmw_node_data.hpp

+5-5
Original file line numberDiff line numberDiff line change
@@ -43,7 +43,7 @@ class NodeData final
4343
static std::shared_ptr<NodeData> make(
4444
const rmw_node_t * const node,
4545
std::size_t id,
46-
const std::shared_ptr<zenoh::Session> & session,
46+
std::shared_ptr<zenoh::Session> session,
4747
std::size_t domain_id,
4848
const std::string & namespace_,
4949
const std::string & node_name,
@@ -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 std::shared_ptr<zenoh::Session> & session,
58+
std::shared_ptr<zenoh::Session> session,
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 std::shared_ptr<zenoh::Session> & session,
73+
std::shared_ptr<zenoh::Session> session,
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 std::shared_ptr<zenoh::Session> & session,
89+
std::shared_ptr<zenoh::Session> 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 std::shared_ptr<zenoh::Session> & session,
104+
std::shared_ptr<zenoh::Session> session,
105105
std::size_t id,
106106
const std::string & service_name,
107107
const rosidl_service_type_support_t * type_support,

rmw_zenoh_cpp/src/detail/rmw_publisher_data.cpp

+5-1
Original file line numberDiff line numberDiff line change
@@ -43,7 +43,7 @@ namespace rmw_zenoh_cpp
4343

4444
///=============================================================================
4545
std::shared_ptr<PublisherData> PublisherData::make(
46-
const std::shared_ptr<zenoh::Session> & session,
46+
std::shared_ptr<zenoh::Session> session,
4747
const rmw_node_t * const node,
4848
liveliness::NodeInfo node_info,
4949
std::size_t node_id,
@@ -158,6 +158,7 @@ std::shared_ptr<PublisherData> PublisherData::make(
158158
new PublisherData{
159159
node,
160160
std::move(entity),
161+
std::move(session),
161162
std::move(pub),
162163
std::move(pub_cache),
163164
std::move(token),
@@ -170,13 +171,15 @@ std::shared_ptr<PublisherData> PublisherData::make(
170171
PublisherData::PublisherData(
171172
const rmw_node_t * rmw_node,
172173
std::shared_ptr<liveliness::Entity> entity,
174+
std::shared_ptr<zenoh::Session> sess,
173175
zenoh::Publisher pub,
174176
std::optional<zenoh::ext::PublicationCache> pub_cache,
175177
zenoh::LivelinessToken token,
176178
const void * type_support_impl,
177179
std::unique_ptr<MessageTypeSupport> type_support)
178180
: rmw_node_(rmw_node),
179181
entity_(std::move(entity)),
182+
sess_(std::move(sess)),
180183
pub_(std::move(pub)),
181184
pub_cache_(std::move(pub_cache)),
182185
token_(std::move(token)),
@@ -421,6 +424,7 @@ rmw_ret_t PublisherData::shutdown()
421424
return RMW_RET_ERROR;
422425
}
423426

427+
sess_.reset();
424428
is_shutdown_ = true;
425429
return RMW_RET_OK;
426430
}

rmw_zenoh_cpp/src/detail/rmw_publisher_data.hpp

+4-1
Original file line numberDiff line numberDiff line change
@@ -43,7 +43,7 @@ class PublisherData final
4343
public:
4444
// Make a shared_ptr of PublisherData.
4545
static std::shared_ptr<PublisherData> make(
46-
const std::shared_ptr<zenoh::Session> & session,
46+
std::shared_ptr<zenoh::Session> session,
4747
const rmw_node_t * const node,
4848
liveliness::NodeInfo node_info,
4949
std::size_t node_id,
@@ -92,6 +92,7 @@ class PublisherData final
9292
PublisherData(
9393
const rmw_node_t * rmw_node,
9494
std::shared_ptr<liveliness::Entity> entity,
95+
std::shared_ptr<zenoh::Session> session,
9596
zenoh::Publisher pub,
9697
std::optional<zenoh::ext::PublicationCache> pub_cache,
9798
zenoh::LivelinessToken token,
@@ -104,6 +105,8 @@ class PublisherData final
104105
const rmw_node_t * rmw_node_;
105106
// The Entity generated for the publisher.
106107
std::shared_ptr<liveliness::Entity> entity_;
108+
// A shared session.
109+
std::shared_ptr<zenoh::Session> sess_;
107110
// An owned publisher.
108111
zenoh::Publisher pub_;
109112
// Optional publication cache when durability is transient_local.

rmw_zenoh_cpp/src/detail/rmw_service_data.cpp

+5-1
Original file line numberDiff line numberDiff line change
@@ -43,7 +43,7 @@ namespace rmw_zenoh_cpp
4343
{
4444
///=============================================================================
4545
std::shared_ptr<ServiceData> ServiceData::make(
46-
const std::shared_ptr<zenoh::Session> & session,
46+
std::shared_ptr<zenoh::Session> session,
4747
const rmw_node_t * const node,
4848
liveliness::NodeInfo node_info,
4949
std::size_t node_id,
@@ -128,6 +128,7 @@ std::shared_ptr<ServiceData> ServiceData::make(
128128
new ServiceData{
129129
node,
130130
std::move(entity),
131+
session,
131132
request_members,
132133
response_members,
133134
std::move(request_type_support),
@@ -191,12 +192,14 @@ std::shared_ptr<ServiceData> ServiceData::make(
191192
ServiceData::ServiceData(
192193
const rmw_node_t * rmw_node,
193194
std::shared_ptr<liveliness::Entity> entity,
195+
std::shared_ptr<zenoh::Session> session,
194196
const void * request_type_support_impl,
195197
const void * response_type_support_impl,
196198
std::unique_ptr<RequestTypeSupport> request_type_support,
197199
std::unique_ptr<ResponseTypeSupport> response_type_support)
198200
: rmw_node_(rmw_node),
199201
entity_(std::move(entity)),
202+
sess_(std::move(session)),
200203
request_type_support_impl_(request_type_support_impl),
201204
response_type_support_impl_(response_type_support_impl),
202205
request_type_support_(std::move(request_type_support)),
@@ -536,6 +539,7 @@ rmw_ret_t ServiceData::shutdown()
536539
}
537540
}
538541

542+
sess_.reset();
539543
is_shutdown_ = true;
540544
return RMW_RET_OK;
541545
}

rmw_zenoh_cpp/src/detail/rmw_service_data.hpp

+5-1
Original file line numberDiff line numberDiff line change
@@ -47,7 +47,7 @@ class ServiceData final : public std::enable_shared_from_this<ServiceData>
4747
public:
4848
// Make a shared_ptr of ServiceData.
4949
static std::shared_ptr<ServiceData> make(
50-
const std::shared_ptr<zenoh::Session> & session,
50+
std::shared_ptr<zenoh::Session> session,
5151
const rmw_node_t * const node,
5252
liveliness::NodeInfo node_info,
5353
std::size_t node_id,
@@ -99,6 +99,7 @@ class ServiceData final : public std::enable_shared_from_this<ServiceData>
9999
ServiceData(
100100
const rmw_node_t * rmw_node,
101101
std::shared_ptr<liveliness::Entity> entity,
102+
std::shared_ptr<zenoh::Session> session,
102103
const void * request_type_support_impl,
103104
const void * response_type_support_impl,
104105
std::unique_ptr<RequestTypeSupport> request_type_support,
@@ -110,6 +111,9 @@ class ServiceData final : public std::enable_shared_from_this<ServiceData>
110111
const rmw_node_t * rmw_node_;
111112
// The Entity generated for the service.
112113
std::shared_ptr<liveliness::Entity> entity_;
114+
115+
// A shared session
116+
std::shared_ptr<zenoh::Session> sess_;
113117
// The keyexpr string.
114118
std::string keyexpr_;
115119
// An owned queryable.

rmw_zenoh_cpp/src/detail/rmw_subscription_data.cpp

+6-1
Original file line numberDiff line numberDiff line change
@@ -56,7 +56,7 @@ SubscriptionData::Message::~Message()
5656

5757
///=============================================================================
5858
std::shared_ptr<SubscriptionData> SubscriptionData::make(
59-
const std::shared_ptr<zenoh::Session> & session,
59+
std::shared_ptr<zenoh::Session> session,
6060
std::shared_ptr<GraphCache> graph_cache,
6161
const rmw_node_t * const node,
6262
liveliness::NodeInfo node_info,
@@ -123,6 +123,7 @@ std::shared_ptr<SubscriptionData> SubscriptionData::make(
123123
node,
124124
graph_cache,
125125
std::move(entity),
126+
std::move(session),
126127
type_support->data,
127128
std::move(message_type_support)
128129
});
@@ -140,11 +141,13 @@ SubscriptionData::SubscriptionData(
140141
const rmw_node_t * rmw_node,
141142
std::shared_ptr<GraphCache> graph_cache,
142143
std::shared_ptr<liveliness::Entity> entity,
144+
std::shared_ptr<zenoh::Session> session,
143145
const void * type_support_impl,
144146
std::unique_ptr<MessageTypeSupport> type_support)
145147
: rmw_node_(rmw_node),
146148
graph_cache_(std::move(graph_cache)),
147149
entity_(std::move(entity)),
150+
sess_(std::move(session)),
148151
type_support_impl_(type_support_impl),
149152
type_support_(std::move(type_support)),
150153
last_known_published_msg_({}),
@@ -175,6 +178,8 @@ bool SubscriptionData::init()
175178

176179
rmw_context_impl_t * context_impl = static_cast<rmw_context_impl_t *>(rmw_node_->context->impl);
177180

181+
sess_ = context_impl->session();
182+
178183
// Instantiate the subscription with suitable options depending on the
179184
// adapted_qos_profile.
180185
// TODO(Yadunund): Rely on a separate function to return the sub

rmw_zenoh_cpp/src/detail/rmw_subscription_data.hpp

+4-1
Original file line numberDiff line numberDiff line change
@@ -62,7 +62,7 @@ class SubscriptionData final : public std::enable_shared_from_this<SubscriptionD
6262

6363
// Make a shared_ptr of SubscriptionData.
6464
static std::shared_ptr<SubscriptionData> make(
65-
const std::shared_ptr<zenoh::Session> & session,
65+
std::shared_ptr<zenoh::Session> session,
6666
std::shared_ptr<GraphCache> graph_cache,
6767
const rmw_node_t * const node,
6868
liveliness::NodeInfo node_info,
@@ -126,6 +126,7 @@ class SubscriptionData final : public std::enable_shared_from_this<SubscriptionD
126126
const rmw_node_t * rmw_node,
127127
std::shared_ptr<GraphCache> graph_cache,
128128
std::shared_ptr<liveliness::Entity> entity,
129+
std::shared_ptr<zenoh::Session> session,
129130
const void * type_support_impl,
130131
std::unique_ptr<MessageTypeSupport> type_support);
131132

@@ -139,6 +140,8 @@ class SubscriptionData final : public std::enable_shared_from_this<SubscriptionD
139140
std::shared_ptr<GraphCache> graph_cache_;
140141
// The Entity generated for the subscription.
141142
std::shared_ptr<liveliness::Entity> entity_;
143+
// A shared session
144+
std::shared_ptr<zenoh::Session> sess_;
142145
// An owned subscriber or querying_subscriber depending on the QoS settings.
143146
std::optional<std::variant<zenoh::Subscriber<void>, zenoh::ext::QueryingSubscriber<void>>> sub_;
144147
// Liveliness token for the subscription.

0 commit comments

Comments
 (0)