diff --git a/rmw/include/rmw/topic_endpoint_info.h b/rmw/include/rmw/topic_endpoint_info.h
index c05d397a..dcf1f730 100644
--- a/rmw/include/rmw/topic_endpoint_info.h
+++ b/rmw/include/rmw/topic_endpoint_info.h
@@ -21,6 +21,7 @@ extern "C"
#endif
#include "rcutils/allocator.h"
+#include "rcutils/types/string_map.h"
#include "rosidl_runtime_c/type_hash.h"
#include "rmw/types.h"
#include "rmw/visibility_control.h"
@@ -44,6 +45,8 @@ typedef struct RMW_PUBLIC_TYPE rmw_topic_endpoint_info_s
uint8_t endpoint_gid[RMW_GID_STORAGE_SIZE];
/// QoS profile of the endpoint
rmw_qos_profile_t qos_profile;
+ /// Buffer backend metadata advertised for this endpoint
+ rcutils_string_map_t buffer_backend_metadata;
} rmw_topic_endpoint_info_t;
/// Return zero initialized topic endpoint info data structure.
@@ -363,6 +366,42 @@ rmw_topic_endpoint_info_set_qos_profile(
rmw_topic_endpoint_info_t * topic_endpoint_info,
const rmw_qos_profile_t * qos_profile);
+/// Set buffer backend metadata in the given topic endpoint info data structure.
+/**
+ * Copies all key/value pairs from `buffer_backend_metadata` into the topic endpoint info.
+ * Keys are backend names and values are backend-specific metadata strings.
+ *
+ *
+ * Attribute | Adherence
+ * ------------------ | -------------
+ * Allocates Memory | Yes
+ * Thread-Safe | No
+ * Uses Atomics | No
+ * Lock-Free | No
+ *
+ * \par Thread-safety
+ * Setting a member is a reentrant procedure, but access to the
+ * topic endpoint info data structure is not synchronized.
+ * It is not safe to read or write the `buffer_backend_metadata` member of the
+ * given `topic_endpoint` while setting it.
+ *
+ * \param[inout] topic_endpoint_info Data structure to be populated.
+ * \param[in] buffer_backend_metadata Buffer backend metadata to be copied.
+ * \param[in] allocator Allocator to be used.
+ * \returns `RMW_RET_OK` if successful, or
+ * \returns `RMW_RET_INVALID_ARGUMENT` if any arguments are invalid, or
+ * \returns `RMW_RET_BAD_ALLOC` if memory allocation fails, or
+ * \returns `RMW_RET_ERROR` when an unspecified error occurs.
+ * \remark This function sets the RMW error state on failure.
+ */
+RMW_PUBLIC
+RMW_WARN_UNUSED
+rmw_ret_t
+rmw_topic_endpoint_info_set_buffer_backend_metadata(
+ rmw_topic_endpoint_info_t * topic_endpoint_info,
+ const rcutils_string_map_t * buffer_backend_metadata,
+ rcutils_allocator_t * allocator);
+
#ifdef __cplusplus
}
#endif
diff --git a/rmw/src/topic_endpoint_info.c b/rmw/src/topic_endpoint_info.c
index 10d819ae..3f7ee22d 100644
--- a/rmw/src/topic_endpoint_info.c
+++ b/rmw/src/topic_endpoint_info.c
@@ -15,7 +15,10 @@
#include "rmw/topic_endpoint_info.h"
#include "rcutils/macros.h"
+#include "rcutils/error_handling.h"
#include "rcutils/strdup.h"
+#include "rcutils/types/string_map.h"
+#include "rmw/convert_rcutils_ret_to_rmw_ret.h"
#include "rmw/error_handling.h"
#include "rmw/types.h"
@@ -90,6 +93,13 @@ rmw_topic_endpoint_info_fini(
if (ret != RMW_RET_OK) {
return ret;
}
+ rcutils_ret_t rcutils_ret =
+ rcutils_string_map_fini(&topic_endpoint_info->buffer_backend_metadata);
+ if (rcutils_ret != RCUTILS_RET_OK) {
+ RMW_SET_ERROR_MSG(rcutils_get_error_string().str);
+ rcutils_reset_error();
+ return rmw_convert_rcutils_ret_to_rmw_ret(rcutils_ret);
+ }
*topic_endpoint_info = rmw_get_zero_initialized_topic_endpoint_info();
@@ -246,3 +256,67 @@ rmw_topic_endpoint_info_set_qos_profile(
topic_endpoint_info->qos_profile = *qos_profile;
return RMW_RET_OK;
}
+
+rmw_ret_t
+rmw_topic_endpoint_info_set_buffer_backend_metadata(
+ rmw_topic_endpoint_info_t * topic_endpoint_info,
+ const rcutils_string_map_t * buffer_backend_metadata,
+ rcutils_allocator_t * allocator)
+{
+ RCUTILS_CAN_RETURN_WITH_ERROR_OF(RMW_RET_INVALID_ARGUMENT);
+ RCUTILS_CAN_RETURN_WITH_ERROR_OF(RMW_RET_BAD_ALLOC);
+
+ if (!topic_endpoint_info) {
+ RMW_SET_ERROR_MSG("topic_endpoint_info is null");
+ return RMW_RET_INVALID_ARGUMENT;
+ }
+ if (!buffer_backend_metadata) {
+ RMW_SET_ERROR_MSG("buffer_backend_metadata is null");
+ return RMW_RET_INVALID_ARGUMENT;
+ }
+ if (!allocator) {
+ RMW_SET_ERROR_MSG("allocator is null");
+ return RMW_RET_INVALID_ARGUMENT;
+ }
+
+ size_t size = 0;
+ rcutils_ret_t rcutils_ret = rcutils_string_map_get_size(buffer_backend_metadata, &size);
+ if (rcutils_ret != RCUTILS_RET_OK) {
+ RMW_SET_ERROR_MSG(rcutils_get_error_string().str);
+ rcutils_reset_error();
+ return rmw_convert_rcutils_ret_to_rmw_ret(rcutils_ret);
+ }
+
+ if (topic_endpoint_info->buffer_backend_metadata.impl) {
+ rcutils_ret = rcutils_string_map_fini(&topic_endpoint_info->buffer_backend_metadata);
+ if (rcutils_ret != RCUTILS_RET_OK) {
+ RMW_SET_ERROR_MSG(rcutils_get_error_string().str);
+ rcutils_reset_error();
+ return rmw_convert_rcutils_ret_to_rmw_ret(rcutils_ret);
+ }
+ }
+
+ topic_endpoint_info->buffer_backend_metadata = rcutils_get_zero_initialized_string_map();
+ rcutils_ret = rcutils_string_map_init(
+ &topic_endpoint_info->buffer_backend_metadata, size, *allocator);
+ if (rcutils_ret != RCUTILS_RET_OK) {
+ RMW_SET_ERROR_MSG(rcutils_get_error_string().str);
+ rcutils_reset_error();
+ return rmw_convert_rcutils_ret_to_rmw_ret(rcutils_ret);
+ }
+
+ rcutils_ret = rcutils_string_map_copy(
+ buffer_backend_metadata,
+ &topic_endpoint_info->buffer_backend_metadata);
+ if (rcutils_ret != RCUTILS_RET_OK) {
+ rcutils_ret_t fini_ret =
+ rcutils_string_map_fini(&topic_endpoint_info->buffer_backend_metadata);
+ (void)fini_ret;
+ topic_endpoint_info->buffer_backend_metadata = rcutils_get_zero_initialized_string_map();
+ RMW_SET_ERROR_MSG(rcutils_get_error_string().str);
+ rcutils_reset_error();
+ return rmw_convert_rcutils_ret_to_rmw_ret(rcutils_ret);
+ }
+
+ return RMW_RET_OK;
+}
diff --git a/rmw/test/test_topic_endpoint_info.cpp b/rmw/test/test_topic_endpoint_info.cpp
index 2a3603d3..4f106bac 100644
--- a/rmw/test/test_topic_endpoint_info.cpp
+++ b/rmw/test/test_topic_endpoint_info.cpp
@@ -15,6 +15,7 @@
#include "gmock/gmock.h"
#include "osrf_testing_tools_cpp/scope_exit.hpp"
#include "rcutils/allocator.h"
+#include "rcutils/types/string_map.h"
#include "rmw/error_handling.h"
#include "rmw/topic_endpoint_info.h"
@@ -217,6 +218,47 @@ TEST(test_topic_endpoint_info, set_qos_profile) {
false) << "Unequal avoid namespace conventions";
}
+TEST(test_topic_endpoint_info, set_buffer_backend_metadata) {
+ rmw_topic_endpoint_info_t topic_endpoint_info = rmw_get_zero_initialized_topic_endpoint_info();
+ rcutils_allocator_t allocator = rcutils_get_default_allocator();
+ rcutils_string_map_t metadata = rcutils_get_zero_initialized_string_map();
+ rcutils_ret_t rcutils_ret = rcutils_string_map_init(&metadata, 1, allocator);
+ ASSERT_EQ(rcutils_ret, RCUTILS_RET_OK);
+ OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT(
+ {
+ rcutils_ret_t fini_ret = rcutils_string_map_fini(&metadata);
+ EXPECT_EQ(fini_ret, RCUTILS_RET_OK);
+ });
+ rcutils_ret = rcutils_string_map_set(&metadata, "cuda", "version=1.0");
+ ASSERT_EQ(rcutils_ret, RCUTILS_RET_OK);
+
+ rmw_ret_t ret =
+ rmw_topic_endpoint_info_set_buffer_backend_metadata(&topic_endpoint_info, &metadata, nullptr);
+ EXPECT_EQ(ret, RMW_RET_INVALID_ARGUMENT) << "Expected invalid argument for null allocator";
+ rmw_reset_error();
+
+ ret = rmw_topic_endpoint_info_set_buffer_backend_metadata(
+ &topic_endpoint_info, nullptr, &allocator);
+ EXPECT_EQ(ret, RMW_RET_INVALID_ARGUMENT) << "Expected invalid argument for null metadata";
+ rmw_reset_error();
+
+ ret = rmw_topic_endpoint_info_set_buffer_backend_metadata(nullptr, &metadata, &allocator);
+ EXPECT_EQ(ret, RMW_RET_INVALID_ARGUMENT) <<
+ "Expected invalid argument for null topic_endpoint_info";
+ rmw_reset_error();
+
+ ret = rmw_topic_endpoint_info_set_buffer_backend_metadata(
+ &topic_endpoint_info, &metadata, &allocator);
+ EXPECT_EQ(ret, RMW_RET_OK) << "Expected OK for valid arguments";
+ EXPECT_STREQ(
+ rcutils_string_map_get(&topic_endpoint_info.buffer_backend_metadata, "cuda"),
+ "version=1.0");
+
+ ret = rmw_topic_endpoint_info_fini(&topic_endpoint_info, &allocator);
+ EXPECT_EQ(ret, RMW_RET_OK);
+ EXPECT_FALSE(topic_endpoint_info.buffer_backend_metadata.impl);
+}
+
TEST(test_topic_endpoint_info, zero_init) {
rmw_topic_endpoint_info_t topic_endpoint_info = rmw_get_zero_initialized_topic_endpoint_info();
EXPECT_FALSE(topic_endpoint_info.node_name);
@@ -245,6 +287,7 @@ TEST(test_topic_endpoint_info, zero_init) {
EXPECT_EQ(
topic_endpoint_info.qos_profile.avoid_ros_namespace_conventions,
false) << "Non-zero avoid namespace conventions";
+ EXPECT_FALSE(topic_endpoint_info.buffer_backend_metadata.impl);
}
TEST(test_topic_endpoint_info, fini) {
@@ -279,6 +322,16 @@ TEST(test_topic_endpoint_info, fini) {
EXPECT_EQ(ret, RMW_RET_OK) << "Expected OK for valid node_name arguments";
ret = rmw_topic_endpoint_info_set_topic_type(&topic_endpoint_info, "type", &allocator);
EXPECT_EQ(ret, RMW_RET_OK) << "Expected OK for valid topic_type arguments";
+ rcutils_string_map_t metadata = rcutils_get_zero_initialized_string_map();
+ rcutils_ret_t rcutils_ret = rcutils_string_map_init(&metadata, 1, allocator);
+ ASSERT_EQ(rcutils_ret, RCUTILS_RET_OK);
+ rcutils_ret = rcutils_string_map_set(&metadata, "cuda", "");
+ ASSERT_EQ(rcutils_ret, RCUTILS_RET_OK);
+ ret = rmw_topic_endpoint_info_set_buffer_backend_metadata(
+ &topic_endpoint_info, &metadata, &allocator);
+ EXPECT_EQ(ret, RMW_RET_OK) << "Expected OK for valid buffer backend metadata";
+ rcutils_ret = rcutils_string_map_fini(&metadata);
+ EXPECT_EQ(rcutils_ret, RCUTILS_RET_OK);
ret = rmw_topic_endpoint_info_fini(&topic_endpoint_info, nullptr);
EXPECT_EQ(ret, RMW_RET_INVALID_ARGUMENT) << "Expected invalid argument for null allocator";
rmw_reset_error();
@@ -314,4 +367,5 @@ TEST(test_topic_endpoint_info, fini) {
"Non-zero liveliness lease duration nsec";
EXPECT_EQ(topic_endpoint_info.qos_profile.avoid_ros_namespace_conventions, false) <<
"Non-zero avoid namespace conventions";
+ EXPECT_FALSE(topic_endpoint_info.buffer_backend_metadata.impl);
}