Skip to content

Commit e0858cd

Browse files
committed
Add get_clients_info_by_service and get_servers_info_by_service; introduce ServiceEntityInfo to handle service type hash in graph cache
Signed-off-by: Minju, Lee <[email protected]>
1 parent f10f8bf commit e0858cd

File tree

4 files changed

+342
-8
lines changed

4 files changed

+342
-8
lines changed

rmw_dds_common/include/rmw_dds_common/graph_cache.hpp

Lines changed: 73 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -26,6 +26,8 @@
2626
#include "rcutils/logging_macros.h"
2727

2828
#include "rmw/names_and_types.h"
29+
#include "rmw/service_endpoint_info.h"
30+
#include "rmw/service_endpoint_info_array.h"
2931
#include "rmw/topic_endpoint_info.h"
3032
#include "rmw/topic_endpoint_info_array.h"
3133
#include "rmw/types.h"
@@ -42,6 +44,7 @@ namespace rmw_dds_common
4244
// Forward-declaration, defined at end of file.
4345
struct EntityInfo;
4446
struct ParticipantInfo;
47+
struct ServiceEntityInfo;
4548

4649
/// Graph cache data structure.
4750
/**
@@ -86,6 +89,8 @@ class GraphCache
8689
* \param type_hash Hash of the description of the topic type.
8790
* \param participant_gid GUID of the participant.
8891
* \param qos QoS profile of the data writer.
92+
* \param service_type_hash Optional pointer to the service type hash,
93+
* used when the writer is part of a service (e.g., request or reply topic)
8994
* \return `true` if the cache was updated, `false` if the data writer
9095
* was already present.
9196
*/
@@ -97,7 +102,8 @@ class GraphCache
97102
const std::string & type_name,
98103
const rosidl_type_hash_t & type_hash,
99104
const rmw_gid_t & participant_gid,
100-
const rmw_qos_profile_t & qos);
105+
const rmw_qos_profile_t & qos,
106+
const rosidl_type_hash_t * service_type_hash = nullptr);
101107

102108
/// Add a data writer based on discovery.
103109
/**
@@ -122,6 +128,8 @@ class GraphCache
122128
* \param type_hash Hash of the description of the topic type.
123129
* \param participant_gid GUID of the participant.
124130
* \param qos QoS profile of the data reader.
131+
* \param service_type_hash Optional pointer to the service type hash,
132+
* used when the reader is part of a service (e.g., request or reply topic)
125133
* \return `true` if the cache was updated, `false` if the data reader
126134
* was already present.
127135
*/
@@ -133,7 +141,8 @@ class GraphCache
133141
const std::string & type_name,
134142
const rosidl_type_hash_t & type_hash,
135143
const rmw_gid_t & participant_gid,
136-
const rmw_qos_profile_t & qos);
144+
const rmw_qos_profile_t & qos,
145+
const rosidl_type_hash_t * service_type_hash = nullptr);
137146

138147
/// Add a data reader based on discovery.
139148
/**
@@ -159,6 +168,8 @@ class GraphCache
159168
* \param participant_gid GUID of the participant.
160169
* \param qos QoS profile of the entity.
161170
* \param is_reader Whether the entity is a data reader or a writer.
171+
* \param service_type_hash Optional pointer to the service type hash,
172+
* used when the entity is part of a service (e.g., request or reply topic)
162173
* \return `true` if the cache was updated, `false` if the entity
163174
* was already present.
164175
*/
@@ -171,7 +182,8 @@ class GraphCache
171182
const rosidl_type_hash_t & type_hash,
172183
const rmw_gid_t & participant_gid,
173184
const rmw_qos_profile_t & qos,
174-
bool is_reader);
185+
bool is_reader,
186+
const rosidl_type_hash_t * service_type_hash = nullptr);
175187

176188
/// Add a data reader or writer.
177189
/**
@@ -445,6 +457,46 @@ class GraphCache
445457
rcutils_allocator_t * allocator,
446458
rmw_topic_endpoint_info_array_t * endpoints_info) const;
447459

460+
/// Get an array with information about the clients for a service.
461+
/**
462+
* \param[in] readers_info array containing data readers for the service’s reply topic.
463+
* \param[in] writers_info array containing data writers for the service’s request topic.
464+
* \param[in] allocator Allocator to allocate memory when populating `endpoints_info`.
465+
* \param[out] endpoints_info A zero-initialized service endpoint information
466+
* array to be populated with client information derived from the topic readers and writers.
467+
*
468+
* \return RMW_RET_INVALID_ARGUMENT if any input is null, or
469+
* \return RMW_RET_ERROR if an unexpected error occurs, or
470+
* \return RMW_RET_OK if successful.
471+
*/
472+
RMW_DDS_COMMON_PUBLIC
473+
rmw_ret_t
474+
get_clients_info_by_service(
475+
const rmw_topic_endpoint_info_array_t * readers_info,
476+
const rmw_topic_endpoint_info_array_t * writers_info,
477+
rcutils_allocator_t * allocator,
478+
rmw_service_endpoint_info_array_t * endpoints_info) const;
479+
480+
/// Get an array with information about the servers for a service.
481+
/**
482+
* \param[in] readers_info array containing data readers for the service’s request topic.
483+
* \param[in] writers_info array containing data writers for the service’s reply topic.
484+
* \param[in] allocator Allocator to allocate memory when populating `endpoints_info`.
485+
* \param[out] endpoints_info A zero-initialized service endpoint information array
486+
* to be populated with server information derived from the topic readers and writers.
487+
*
488+
* \return RMW_RET_INVALID_ARGUMENT if any input is null, or
489+
* \return RMW_RET_ERROR if an unexpected error occurs, or
490+
* \return RMW_RET_OK if successful.
491+
*/
492+
RMW_DDS_COMMON_PUBLIC
493+
rmw_ret_t
494+
get_servers_info_by_service(
495+
const rmw_topic_endpoint_info_array_t * readers_info,
496+
const rmw_topic_endpoint_info_array_t * writers_info,
497+
rcutils_allocator_t * allocator,
498+
rmw_service_endpoint_info_array_t * endpoints_info) const;
499+
448500
/// Get all topic names and types.
449501
/**
450502
* \param[in] demangle_topic Function to demangle DDS topic names.
@@ -565,10 +617,14 @@ class GraphCache
565617
/// Sequence of endpoints gids.
566618
using GidSeq =
567619
decltype(std::declval<rmw_dds_common::msg::NodeEntitiesInfo>().writer_gid_seq);
620+
/// \internal
621+
/// Map from endpoint gids to service endpoints discovery info.
622+
using EntityGidToServiceInfo = std::map<rmw_gid_t, ServiceEntityInfo, Compare_rmw_gid_t>;
568623

569624
private:
570625
EntityGidToInfo data_writers_;
571626
EntityGidToInfo data_readers_;
627+
EntityGidToServiceInfo data_services_;
572628
ParticipantToNodesMap participants_;
573629
std::function<void()> on_change_callback_ = nullptr;
574630

@@ -617,6 +673,20 @@ struct EntityInfo
617673
{}
618674
};
619675

676+
/// Structure to represent the service discovery data from an endpoint (data reader or writer).
677+
struct ServiceEntityInfo
678+
{
679+
/// Hash of the associated service type, if applicable.
680+
/// This field is used to associate endpoints (readers or writers) that form a service,
681+
/// whether the middleware explicitly supports services or represents them as separate topics.
682+
/// See: https://github.com/ros2/rmw/pull/371#issuecomment-2763634820
683+
rosidl_type_hash_t service_type_hash;
684+
685+
explicit ServiceEntityInfo(const rosidl_type_hash_t & service_type_hash)
686+
: service_type_hash(service_type_hash)
687+
{}
688+
};
689+
620690
} // namespace rmw_dds_common
621691

622692
#endif // RMW_DDS_COMMON__GRAPH_CACHE_HPP_

rmw_dds_common/include/rmw_dds_common/qos.hpp

Lines changed: 31 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -255,6 +255,37 @@ encode_type_hash_for_user_data_qos(
255255
const rosidl_type_hash_t & type_hash,
256256
std::string & string_out);
257257

258+
/// Parse USER_DATA "key=value;key=value;"" encoding, finding value of key "sertypehash"
259+
/**
260+
* \param[in] user_data USER_DATA qos raw bytes
261+
* \param[in] user_data_size Length of user_data
262+
* \param[out] type_hash_out Filled with type hash data if found, or to zero value if key not found
263+
* \return RMW_RET_OK if key parsed successfully
264+
* \return RMW_RET_UNSUPPORTED if key not found
265+
* \return RMW_RET_INVALID_ARGUMENT if user_data is null
266+
* \return RMW_RET_ERROR if sertypehash key found, but value could not be parsed
267+
*/
268+
RMW_DDS_COMMON_PUBLIC
269+
rmw_ret_t
270+
parse_sertype_hash_from_user_data(
271+
const uint8_t * user_data,
272+
size_t user_data_size,
273+
rosidl_type_hash_t & type_hash_out);
274+
275+
/// Encode type hash as "sertypehash=hash_string;" for use in USER_DATA QoS
276+
/**
277+
* \param[in] type_hash Type hash value to encode
278+
* \param[out] string_out On success, will be set to "sertypehash=stringified_type_hash;"
279+
* If type_hash's version is 0, string_out will be set to empty
280+
* \return RMW_RET_OK on success, including empty string for unset version
281+
* \return RMW_RET_BAD_ALLOC if memory allocation fails
282+
*/
283+
RMW_DDS_COMMON_PUBLIC
284+
rmw_ret_t
285+
encode_sertype_hash_for_user_data_qos(
286+
const rosidl_type_hash_t & type_hash,
287+
std::string & string_out);
288+
258289
} // namespace rmw_dds_common
259290

260291
#endif // RMW_DDS_COMMON__QOS_HPP_

0 commit comments

Comments
 (0)