Skip to content
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
39 changes: 39 additions & 0 deletions rmw/include/rmw/topic_endpoint_info.h
Original file line number Diff line number Diff line change
Expand Up @@ -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"
Expand All @@ -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;
Comment on lines +48 to +49

Copy link
Copy Markdown
Collaborator

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

the struct previously held only const char * owning pointers, but it now holds a rcutils_string_map_t whose impl is a heap pointer with its own fini. any code path that copies an rmw_topic_endpoint_info_t by plain struct assignment or memcpy now aliases that impl between two structs.
the existing const char * members have the same hazard in principle, but the codebase already established a deep-copy discipline for strings.
i'd suggest a rmw_topic_endpoint_info deep-copy helper, or at minimum confirmation that no array/element copy in the current code and companion PRs.

} rmw_topic_endpoint_info_t;

/// Return zero initialized topic endpoint info data structure.
Expand Down Expand Up @@ -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.
*
* <hr>
* 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
Expand Down
74 changes: 74 additions & 0 deletions rmw/src/topic_endpoint_info.c
Original file line number Diff line number Diff line change
Expand Up @@ -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"

Expand Down Expand Up @@ -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();

Expand Down Expand Up @@ -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;
}
54 changes: 54 additions & 0 deletions rmw/test/test_topic_endpoint_info.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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"
Expand Down Expand Up @@ -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);
Expand Down Expand Up @@ -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) {
Expand Down Expand Up @@ -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();
Expand Down Expand Up @@ -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);
}