diff --git a/rmw/include/rmw/topic_endpoint_info_array.h b/rmw/include/rmw/topic_endpoint_info_array.h index e736b811..cdec3e76 100644 --- a/rmw/include/rmw/topic_endpoint_info_array.h +++ b/rmw/include/rmw/topic_endpoint_info_array.h @@ -28,7 +28,7 @@ extern "C" typedef struct RMW_PUBLIC_TYPE rmw_topic_endpoint_info_array_t { /// Size of the array. - size_t count; + size_t size; /// Pointer representing an array of rmw_topic_endpoint_info_t rmw_topic_endpoint_info_t * info_array; } rmw_topic_endpoint_info_array_t; @@ -60,6 +60,7 @@ rmw_topic_endpoint_info_array_check_zero( * type rmw_topic_endpoint_info_t. * This function allocates memory to this array to hold n elements, * where n is the value of the size param to this function. + * The member `size` is updated accordingly. * * topic_endpoint_info_array must be zero initialized before being passed into this function. * @@ -85,7 +86,7 @@ rmw_topic_endpoint_info_array_init_with_size( * The info_array member variable inside of rmw_topic_endpoint_info_array represents an array of * rmw_topic_endpoint_info_t. * When initializing this array, memory is allocated for it using the allocator. - * This function reclaims any allocated resources within the object and also sets the value of count + * This function reclaims any allocated resources within the object and also sets the value of size * to 0. * * \param[inout] topic_endpoint_info_array object to be finalized diff --git a/rmw/src/topic_endpoint_info.c b/rmw/src/topic_endpoint_info.c index d09dcbde..4cc91185 100644 --- a/rmw/src/topic_endpoint_info.c +++ b/rmw/src/topic_endpoint_info.c @@ -47,10 +47,6 @@ _rmw_topic_endpoint_info_fini_node_name( rmw_topic_endpoint_info_t * topic_endpoint_info, rcutils_allocator_t * allocator) { - if (!topic_endpoint_info->node_name) { - RMW_SET_ERROR_MSG("topic_endpoint_info->node_name is null"); - return RMW_RET_INVALID_ARGUMENT; - } return _rmw_topic_endpoint_info_fini_str(&topic_endpoint_info->node_name, allocator); } @@ -59,10 +55,6 @@ _rmw_topic_endpoint_info_fini_node_namespace( rmw_topic_endpoint_info_t * topic_endpoint_info, rcutils_allocator_t * allocator) { - if (!topic_endpoint_info->node_namespace) { - RMW_SET_ERROR_MSG("topic_endpoint_info->node_namespace is null"); - return RMW_RET_INVALID_ARGUMENT; - } return _rmw_topic_endpoint_info_fini_str(&topic_endpoint_info->node_namespace, allocator); } @@ -71,10 +63,6 @@ _rmw_topic_endpoint_info_fini_topic_type( rmw_topic_endpoint_info_t * topic_endpoint_info, rcutils_allocator_t * allocator) { - if (!topic_endpoint_info->topic_type) { - RMW_SET_ERROR_MSG("topic_endpoint_info->topic_type is null"); - return RMW_RET_INVALID_ARGUMENT; - } return _rmw_topic_endpoint_info_fini_str(&topic_endpoint_info->topic_type, allocator); } diff --git a/rmw/src/topic_endpoint_info_array.c b/rmw/src/topic_endpoint_info_array.c index aa6f4b2a..1cd1f47d 100644 --- a/rmw/src/topic_endpoint_info_array.c +++ b/rmw/src/topic_endpoint_info_array.c @@ -38,7 +38,7 @@ rmw_topic_endpoint_info_array_check_zero( RMW_SET_ERROR_MSG("topic_endpoint_info_array is null"); return RMW_RET_INVALID_ARGUMENT; } - if (topic_endpoint_info_array->count != 0 || topic_endpoint_info_array->info_array != NULL) { + if (topic_endpoint_info_array->size != 0 || topic_endpoint_info_array->info_array != NULL) { RMW_SET_ERROR_MSG("topic_endpoint_info_array is not zeroed"); return RMW_RET_ERROR; } @@ -65,6 +65,10 @@ rmw_topic_endpoint_info_array_init_with_size( RMW_SET_ERROR_MSG("failed to allocate memory for info_array"); return RMW_RET_BAD_ALLOC; } + topic_endpoint_info_array->size = size; + for (size_t i = 0; i < size; i++) { + topic_endpoint_info_array->info_array[i] = rmw_get_zero_initialized_topic_endpoint_info(); + } return RMW_RET_OK; } @@ -85,7 +89,7 @@ rmw_topic_endpoint_info_array_fini( rmw_ret_t ret; // free all const char * inside the topic_endpoint_info_t - for (size_t i = 0u; i < topic_endpoint_info_array->count; i++) { + for (size_t i = 0u; i < topic_endpoint_info_array->size; i++) { ret = rmw_topic_endpoint_info_fini(&topic_endpoint_info_array->info_array[i], allocator); if (ret != RMW_RET_OK) { return ret; @@ -94,6 +98,6 @@ rmw_topic_endpoint_info_array_fini( allocator->deallocate(topic_endpoint_info_array->info_array, allocator->state); topic_endpoint_info_array->info_array = NULL; - topic_endpoint_info_array->count = 0; + topic_endpoint_info_array->size = 0; return RMW_RET_OK; } diff --git a/rmw/test/test_topic_endpoint_info_array.cpp b/rmw/test/test_topic_endpoint_info_array.cpp index 70b35b6a..1907b5fe 100644 --- a/rmw/test/test_topic_endpoint_info_array.cpp +++ b/rmw/test/test_topic_endpoint_info_array.cpp @@ -16,24 +16,28 @@ #include "osrf_testing_tools_cpp/scope_exit.hpp" #include "rcutils/allocator.h" +#include "rmw/error_handling.h" #include "rmw/topic_endpoint_info_array.h" #include "rmw/types.h" TEST(test_topic_endpoint_info_array, zero_initialize) { rmw_topic_endpoint_info_array_t arr = rmw_get_zero_initialized_topic_endpoint_info_array(); - EXPECT_EQ(arr.count, 0u); + EXPECT_EQ(arr.size, 0u); EXPECT_FALSE(arr.info_array); } TEST(test_topic_endpoint_info_array, check_zero) { rmw_topic_endpoint_info_array_t arr = rmw_get_zero_initialized_topic_endpoint_info_array(); EXPECT_EQ(rmw_topic_endpoint_info_array_check_zero(&arr), RMW_RET_OK); - rmw_topic_endpoint_info_array_t arr_count_not_zero = {1, nullptr}; - EXPECT_EQ(rmw_topic_endpoint_info_array_check_zero(&arr_count_not_zero), RMW_RET_ERROR); + rmw_topic_endpoint_info_array_t arr_size_not_zero = {1, nullptr}; + EXPECT_EQ(rmw_topic_endpoint_info_array_check_zero(&arr_size_not_zero), RMW_RET_ERROR); + rmw_reset_error(); rmw_topic_endpoint_info_t topic_endpoint_info; rmw_topic_endpoint_info_array_t arr_info_array_not_null = {0, &topic_endpoint_info}; EXPECT_EQ(rmw_topic_endpoint_info_array_check_zero(&arr_info_array_not_null), RMW_RET_ERROR); + rmw_reset_error(); EXPECT_EQ(rmw_topic_endpoint_info_array_check_zero(nullptr), RMW_RET_INVALID_ARGUMENT); + rmw_reset_error(); } TEST(test_topic_endpoint_info_array, check_init_with_size) { @@ -47,10 +51,12 @@ TEST(test_topic_endpoint_info_array, check_init_with_size) { EXPECT_EQ( rmw_topic_endpoint_info_array_init_with_size(&arr, 1, nullptr), RMW_RET_INVALID_ARGUMENT); + rmw_reset_error(); EXPECT_EQ( rmw_topic_endpoint_info_array_init_with_size( nullptr, 1, &allocator), RMW_RET_INVALID_ARGUMENT); + rmw_reset_error(); EXPECT_FALSE(arr.info_array); rmw_ret_t ret = rmw_topic_endpoint_info_array_init_with_size(&arr, 5, &allocator); EXPECT_EQ(ret, RMW_RET_OK);