From 84e7201d9835bba1eccd30354b9d612f5ec7ca92 Mon Sep 17 00:00:00 2001 From: Karsten Knese Date: Tue, 6 Nov 2018 15:53:55 -0800 Subject: [PATCH 1/8] add rcutils_unsigned_char_array_t --- CMakeLists.txt | 8 ++ include/rcutils/types.h | 1 + include/rcutils/types/unsigned_char_array.h | 107 ++++++++++++++++++ src/unsigned_char_array.c | 116 ++++++++++++++++++++ test/test_unsigned_char_array.cpp | 73 ++++++++++++ 5 files changed, 305 insertions(+) create mode 100644 include/rcutils/types/unsigned_char_array.h create mode 100644 src/unsigned_char_array.c create mode 100644 test/test_unsigned_char_array.cpp diff --git a/CMakeLists.txt b/CMakeLists.txt index 7e0cc441..693fcfe9 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -46,6 +46,7 @@ set(rcutils_sources src/string_map.c src/time.c ${time_impl_c} + src/unsigned_char_array.c ) set_source_files_properties( ${rcutils_sources} @@ -304,6 +305,13 @@ if(BUILD_TESTING) if(TARGET test_snprintf) target_link_libraries(test_snprintf ${PROJECT_NAME}) endif() + + rcutils_custom_add_gtest(test_unsigned_char_array + test/test_unsigned_char_array.cpp + ) + if(TARGET test_unsigned_char_array) + target_link_libraries(test_unsigned_char_array ${PROJECT_NAME}) + endif() endif() ament_export_dependencies(ament_cmake) diff --git a/include/rcutils/types.h b/include/rcutils/types.h index 2d3666dd..0d8893df 100644 --- a/include/rcutils/types.h +++ b/include/rcutils/types.h @@ -24,6 +24,7 @@ extern "C" #include "rcutils/types/string_array.h" #include "rcutils/types/string_map.h" #include "rcutils/types/rcutils_ret.h" +#include "rcutils/types/unsigned_char_array.h" #ifdef __cplusplus } diff --git a/include/rcutils/types/unsigned_char_array.h b/include/rcutils/types/unsigned_char_array.h new file mode 100644 index 00000000..3296d815 --- /dev/null +++ b/include/rcutils/types/unsigned_char_array.h @@ -0,0 +1,107 @@ +// Copyright 2018 Open Source Robotics Foundation, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#ifndef RCUTILS__TYPES__UNSIGNED_CHAR_ARRAY_H_ +#define RCUTILS__TYPES__UNSIGNED_CHAR_ARRAY_H_ + +#if __cplusplus +extern "C" +{ +#endif + +#include "rcutils/allocator.h" +#include "rcutils/types/rcutils_ret.h" +#include "rcutils/visibility_control.h" + +typedef struct RCUTILS_PUBLIC_TYPE rcutils_unsigned_char_array_t +{ + unsigned char * buffer; + size_t buffer_length; + size_t buffer_capacity; + rcutils_allocator_t allocator; +} rcutils_unsigned_char_array_t; + +/// Return a zero initialized unsigned char array struct. +/** + * \return rcutils_unsigned_char_array_t a zero initialized unsigned char array struct + */ +RCUTILS_PUBLIC +RCUTILS_WARN_UNUSED +rcutils_unsigned_char_array_t +rcutils_get_zero_initialized_unsigned_char_array(void); + +/// Initialize a zero initialized unsigned char array struct. +/** + * This function may leak if the unsigned char array struct is already + * pre-initialized. + * If the capacity is set to 0, no memory is allocated and the internal buffer + * is still NULL. + * + * \param char_array a pointer to the to be initialized unsigned char array struct + * \param buffer_capacity the size of the memory to allocate for the byte stream + * \param allocator the allocator to use for the memory allocation + * \return `RCUTILS_RET_OK` if successful, or + * \return `RCUTILS_RET_ERROR` if an unexpected error occurs + */ +RCUTILS_PUBLIC +RCUTILS_WARN_UNUSED +rcutils_ret_t +rcutils_unsigned_char_array_init( + rcutils_unsigned_char_array_t * char_array, + size_t buffer_capacity, + const rcutils_allocator_t * allocator); + +/// Finalize a unsigned char array struct. +/** + * Cleans up and deallocates any resources used in a rcutils_unsigned_char_array_t. + * Passing a rcutils_unsigned_char_array_t which has not been zero initialized using + * rcutils_get_zero_initialized_unsigned_char_array() to this function is undefined + * behavior. + * + * \param char_array pointer to the rcutils_unsigned_char_array_t to be cleaned up + * \return `RCUTILS_RET_OK` if successful, or + * \return `RCUTILS_RET_BAD_ALLOC` if memory allocation failed, or + * \return `RCUTILS_RET_ERROR` if an unexpected error occurs + */ +RCUTILS_PUBLIC +RCUTILS_WARN_UNUSED +rcutils_ret_t +rcutils_unsigned_char_array_fini(rcutils_unsigned_char_array_t * char_array); + +/// Resize the internal buffer of the unsigned char array. +/** + * The internal buffer of the unsigned char array can be resized dynamically if needed. + * If the new size is smaller than the current capacity, then the memory is + * truncated. + * Be aware, that this will deallocate the memory and therefore invalidates any + * pointers to this storage. + * If the new size is larger, new memory is getting allocated and the existing + * content is copied over. + * + * \param char_array pointer to the instance of rcutils_unsigned_char_array_t which is being resized + * \param new_size the new size of the internal buffer + * \return `RCUTILS_RET_OK` if successful, or + * \return `RCUTILS_RET_BAD_ALLOC` if memory allocation failed, or + * \return `RCUTILS_RET_ERROR` if an unexpected error occurs + */ +RCUTILS_PUBLIC +RCUTILS_WARN_UNUSED +rcutils_ret_t +rcutils_unsigned_char_array_resize(rcutils_unsigned_char_array_t * char_array, size_t new_size); + +#if __cplusplus +} +#endif + +#endif // RCUTILS__TYPES__UNSIGNED_CHAR_ARRAY_H_ diff --git a/src/unsigned_char_array.c b/src/unsigned_char_array.c new file mode 100644 index 00000000..fc90ee0d --- /dev/null +++ b/src/unsigned_char_array.c @@ -0,0 +1,116 @@ +// Copyright 2018 Open Source Robotics Foundation, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include "rcutils/error_handling.h" +#include "rcutils/types/unsigned_char_array.h" + +rcutils_unsigned_char_array_t +rcutils_get_zero_initialized_unsigned_char_array(void) +{ + static rcutils_unsigned_char_array_t char_array = { + .buffer = NULL, + .buffer_length = 0u, + .buffer_capacity = 0u + }; + char_array.allocator = rcutils_get_zero_initialized_allocator(); + return char_array; +} + +rcutils_ret_t +rcutils_unsigned_char_array_init( + rcutils_unsigned_char_array_t * char_array, + size_t buffer_capacity, + const rcutils_allocator_t * allocator) +{ + RCUTILS_CHECK_FOR_NULL_WITH_MSG( + char_array, + "char array pointer is null", + return RCUTILS_RET_ERROR); + + if (!rcutils_allocator_is_valid(allocator)) { + RCUTILS_SET_ERROR_MSG("char array has no valid allocator"); + return RCUTILS_RET_ERROR; + } + + char_array->buffer_length = 0; + char_array->buffer_capacity = buffer_capacity; + char_array->allocator = *allocator; + + if (buffer_capacity > 0u) { + char_array->buffer = (unsigned char *)allocator->allocate( + buffer_capacity * sizeof(unsigned char), allocator->state); + RCUTILS_CHECK_FOR_NULL_WITH_MSG( + char_array->buffer, + "failed to allocate memory for char array", + return RCUTILS_RET_BAD_ALLOC); + } + + return RCUTILS_RET_OK; +} + +rcutils_ret_t +rcutils_unsigned_char_array_fini(rcutils_unsigned_char_array_t * char_array) +{ + RCUTILS_CHECK_FOR_NULL_WITH_MSG( + char_array, + "char array pointer is null", + return RCUTILS_RET_ERROR); + + rcutils_allocator_t * allocator = &char_array->allocator; + if (!rcutils_allocator_is_valid(allocator)) { + RCUTILS_SET_ERROR_MSG("char array has no valid allocator"); + return RCUTILS_RET_ERROR; + } + + allocator->deallocate(char_array->buffer, allocator->state); + char_array->buffer = NULL; + char_array->buffer_length = 0u; + char_array->buffer_capacity = 0u; + + return RCUTILS_RET_OK; +} + +rcutils_ret_t +rcutils_unsigned_char_array_resize(rcutils_unsigned_char_array_t * char_array, size_t new_size) +{ + RCUTILS_CHECK_FOR_NULL_WITH_MSG( + char_array, + "char array pointer is null", + return RCUTILS_RET_ERROR); + + rcutils_allocator_t * allocator = &char_array->allocator; + if (!rcutils_allocator_is_valid(allocator)) { + RCUTILS_SET_ERROR_MSG("char array has no valid allocator"); + return RCUTILS_RET_ERROR; + } + + if (new_size == char_array->buffer_capacity) { + // nothing to do here + return RCUTILS_RET_OK; + } + + char_array->buffer = rcutils_reallocf( + char_array->buffer, new_size * sizeof(unsigned char), allocator); + RCUTILS_CHECK_FOR_NULL_WITH_MSG( + char_array->buffer, + "failed to reallocate memory for char array", + return RCUTILS_RET_BAD_ALLOC); + + char_array->buffer_capacity = new_size; + if (new_size < char_array->buffer_length) { + char_array->buffer_length = new_size; + } + + return RCUTILS_RET_OK; +} diff --git a/test/test_unsigned_char_array.cpp b/test/test_unsigned_char_array.cpp new file mode 100644 index 00000000..415a6ccb --- /dev/null +++ b/test/test_unsigned_char_array.cpp @@ -0,0 +1,73 @@ +// Copyright 2018 Open Source Robotics Foundation, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include + +#include "rcutils/allocator.h" + +#include "rcutils/types/unsigned_char_array.h" + +TEST(test_unsigned_char_array, default_initialization) { + auto char_array = rcutils_get_zero_initialized_unsigned_char_array(); + + auto allocator = rcutils_get_default_allocator(); + EXPECT_EQ(RCUTILS_RET_OK, rcutils_unsigned_char_array_init(&char_array, 0, &allocator)); + EXPECT_EQ(0u, char_array.buffer_capacity); + EXPECT_EQ(RCUTILS_RET_OK, rcutils_unsigned_char_array_fini(&char_array)); + EXPECT_EQ(0u, char_array.buffer_capacity); + EXPECT_FALSE(char_array.buffer); +} + +TEST(test_unsigned_char_array, resize) { + auto char_array = rcutils_get_zero_initialized_unsigned_char_array(); + auto allocator = rcutils_get_default_allocator(); + auto ret = rcutils_unsigned_char_array_init(&char_array, 5, &allocator); + ASSERT_EQ(RCUTILS_RET_OK, ret); + + for (size_t i = 0; i < 5; ++i) { + unsigned char c = 0xFF; + memcpy(char_array.buffer + i, &c, 1); + } + char_array.buffer_length = 5; + for (size_t i = 0; i < char_array.buffer_length; ++i) { + EXPECT_EQ(0xFF, char_array.buffer[i]); + } + + ret = rcutils_unsigned_char_array_resize(&char_array, 10); + ASSERT_EQ(RCUTILS_RET_OK, ret); + EXPECT_EQ(10u, char_array.buffer_capacity); + EXPECT_EQ(5u, char_array.buffer_length); + + for (size_t i = 0; i < 10; ++i) { + unsigned char c = 0xFF - i; + memcpy(char_array.buffer + i, &c, 1); + } + char_array.buffer_length = 10; + for (size_t i = 0; i < char_array.buffer_length; ++i) { + unsigned char c = 0xFF - i; + EXPECT_EQ(c, char_array.buffer[i]); + } + + ret = rcutils_unsigned_char_array_resize(&char_array, 3); + ASSERT_EQ(RCUTILS_RET_OK, ret); + EXPECT_EQ(3u, char_array.buffer_capacity); + EXPECT_EQ(3u, char_array.buffer_length); + EXPECT_EQ(0xFF, char_array.buffer[0]); + EXPECT_EQ(0xFF - 1, char_array.buffer[1]); + EXPECT_EQ(0xFF - 2, char_array.buffer[2]); + // the other fields are garbage. + + // cleanup only 3 fields + EXPECT_EQ(RCUTILS_RET_OK, rcutils_unsigned_char_array_fini(&char_array)); +} From 9601be5fc357db14e5e63b53fa4313e698e692e2 Mon Sep 17 00:00:00 2001 From: Karsten Knese Date: Wed, 7 Nov 2018 13:17:11 -0800 Subject: [PATCH 2/8] unsigned char to uint8 --- CMakeLists.txt | 10 +- include/rcutils/types.h | 2 +- .../{unsigned_char_array.h => uint8_array.h} | 50 ++++---- src/uint8_array.c | 116 ++++++++++++++++++ src/unsigned_char_array.c | 116 ------------------ test/test_uint8_array.cpp | 73 +++++++++++ test/test_unsigned_char_array.cpp | 73 ----------- 7 files changed, 220 insertions(+), 220 deletions(-) rename include/rcutils/types/{unsigned_char_array.h => uint8_array.h} (58%) create mode 100644 src/uint8_array.c delete mode 100644 src/unsigned_char_array.c create mode 100644 test/test_uint8_array.cpp delete mode 100644 test/test_unsigned_char_array.cpp diff --git a/CMakeLists.txt b/CMakeLists.txt index 693fcfe9..619d80c4 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -46,7 +46,7 @@ set(rcutils_sources src/string_map.c src/time.c ${time_impl_c} - src/unsigned_char_array.c + src/uint8_array.c ) set_source_files_properties( ${rcutils_sources} @@ -306,11 +306,11 @@ if(BUILD_TESTING) target_link_libraries(test_snprintf ${PROJECT_NAME}) endif() - rcutils_custom_add_gtest(test_unsigned_char_array - test/test_unsigned_char_array.cpp + rcutils_custom_add_gtest(test_uint8_array + test/test_uint8_array.cpp ) - if(TARGET test_unsigned_char_array) - target_link_libraries(test_unsigned_char_array ${PROJECT_NAME}) + if(TARGET test_uint8_array) + target_link_libraries(test_uint8_array ${PROJECT_NAME}) endif() endif() diff --git a/include/rcutils/types.h b/include/rcutils/types.h index 0d8893df..9c0c41e8 100644 --- a/include/rcutils/types.h +++ b/include/rcutils/types.h @@ -24,7 +24,7 @@ extern "C" #include "rcutils/types/string_array.h" #include "rcutils/types/string_map.h" #include "rcutils/types/rcutils_ret.h" -#include "rcutils/types/unsigned_char_array.h" +#include "rcutils/types/uint8_array.h" #ifdef __cplusplus } diff --git a/include/rcutils/types/unsigned_char_array.h b/include/rcutils/types/uint8_array.h similarity index 58% rename from include/rcutils/types/unsigned_char_array.h rename to include/rcutils/types/uint8_array.h index 3296d815..8bb5b861 100644 --- a/include/rcutils/types/unsigned_char_array.h +++ b/include/rcutils/types/uint8_array.h @@ -12,8 +12,8 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef RCUTILS__TYPES__UNSIGNED_CHAR_ARRAY_H_ -#define RCUTILS__TYPES__UNSIGNED_CHAR_ARRAY_H_ +#ifndef RCUTILS__TYPES__UINT8_ARRAY_H_ +#define RCUTILS__TYPES__UINT8_ARRAY_H_ #if __cplusplus extern "C" @@ -24,31 +24,31 @@ extern "C" #include "rcutils/types/rcutils_ret.h" #include "rcutils/visibility_control.h" -typedef struct RCUTILS_PUBLIC_TYPE rcutils_unsigned_char_array_t +typedef struct RCUTILS_PUBLIC_TYPE rcutils_uint8_array_t { - unsigned char * buffer; + uint8_t * buffer; size_t buffer_length; size_t buffer_capacity; rcutils_allocator_t allocator; -} rcutils_unsigned_char_array_t; +} rcutils_uint8_array_t; -/// Return a zero initialized unsigned char array struct. +/// Return a zero initialized uint8 array struct. /** - * \return rcutils_unsigned_char_array_t a zero initialized unsigned char array struct + * \return rcutils_uint8_array_t a zero initialized uint8 array struct */ RCUTILS_PUBLIC RCUTILS_WARN_UNUSED -rcutils_unsigned_char_array_t -rcutils_get_zero_initialized_unsigned_char_array(void); +rcutils_uint8_array_t +rcutils_get_zero_initialized_uint8_array(void); -/// Initialize a zero initialized unsigned char array struct. +/// Initialize a zero initialized uint8 array struct. /** - * This function may leak if the unsigned char array struct is already + * This function may leak if the uint8 array struct is already * pre-initialized. * If the capacity is set to 0, no memory is allocated and the internal buffer * is still NULL. * - * \param char_array a pointer to the to be initialized unsigned char array struct + * \param uint8_array a pointer to the to be initialized uint8 array struct * \param buffer_capacity the size of the memory to allocate for the byte stream * \param allocator the allocator to use for the memory allocation * \return `RCUTILS_RET_OK` if successful, or @@ -57,19 +57,19 @@ rcutils_get_zero_initialized_unsigned_char_array(void); RCUTILS_PUBLIC RCUTILS_WARN_UNUSED rcutils_ret_t -rcutils_unsigned_char_array_init( - rcutils_unsigned_char_array_t * char_array, +rcutils_uint8_array_init( + rcutils_uint8_array_t * uint8_array, size_t buffer_capacity, const rcutils_allocator_t * allocator); -/// Finalize a unsigned char array struct. +/// Finalize a uint8 array struct. /** - * Cleans up and deallocates any resources used in a rcutils_unsigned_char_array_t. - * Passing a rcutils_unsigned_char_array_t which has not been zero initialized using - * rcutils_get_zero_initialized_unsigned_char_array() to this function is undefined + * Cleans up and deallocates any resources used in a rcutils_uint8_array_t. + * Passing a rcutils_uint8_array_t which has not been zero initialized using + * rcutils_get_zero_initialized_uint8_array() to this function is undefined * behavior. * - * \param char_array pointer to the rcutils_unsigned_char_array_t to be cleaned up + * \param uint8_array pointer to the rcutils_uint8_array_t to be cleaned up * \return `RCUTILS_RET_OK` if successful, or * \return `RCUTILS_RET_BAD_ALLOC` if memory allocation failed, or * \return `RCUTILS_RET_ERROR` if an unexpected error occurs @@ -77,11 +77,11 @@ rcutils_unsigned_char_array_init( RCUTILS_PUBLIC RCUTILS_WARN_UNUSED rcutils_ret_t -rcutils_unsigned_char_array_fini(rcutils_unsigned_char_array_t * char_array); +rcutils_uint8_array_fini(rcutils_uint8_array_t * uint8_array); -/// Resize the internal buffer of the unsigned char array. +/// Resize the internal buffer of the uint8 array. /** - * The internal buffer of the unsigned char array can be resized dynamically if needed. + * The internal buffer of the uint8 array can be resized dynamically if needed. * If the new size is smaller than the current capacity, then the memory is * truncated. * Be aware, that this will deallocate the memory and therefore invalidates any @@ -89,7 +89,7 @@ rcutils_unsigned_char_array_fini(rcutils_unsigned_char_array_t * char_array); * If the new size is larger, new memory is getting allocated and the existing * content is copied over. * - * \param char_array pointer to the instance of rcutils_unsigned_char_array_t which is being resized + * \param uint8_array pointer to the instance of rcutils_uint8_array_t which is being resized * \param new_size the new size of the internal buffer * \return `RCUTILS_RET_OK` if successful, or * \return `RCUTILS_RET_BAD_ALLOC` if memory allocation failed, or @@ -98,10 +98,10 @@ rcutils_unsigned_char_array_fini(rcutils_unsigned_char_array_t * char_array); RCUTILS_PUBLIC RCUTILS_WARN_UNUSED rcutils_ret_t -rcutils_unsigned_char_array_resize(rcutils_unsigned_char_array_t * char_array, size_t new_size); +rcutils_uint8_array_resize(rcutils_uint8_array_t * uint8_array, size_t new_size); #if __cplusplus } #endif -#endif // RCUTILS__TYPES__UNSIGNED_CHAR_ARRAY_H_ +#endif // RCUTILS__TYPES__UINT8_ARRAY_H_ diff --git a/src/uint8_array.c b/src/uint8_array.c new file mode 100644 index 00000000..1d6857b7 --- /dev/null +++ b/src/uint8_array.c @@ -0,0 +1,116 @@ +// Copyright 2018 Open Source Robotics Foundation, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include "rcutils/error_handling.h" +#include "rcutils/types/uint8_array.h" + +rcutils_uint8_array_t +rcutils_get_zero_initialized_uint8_array(void) +{ + static rcutils_uint8_array_t uint8_array = { + .buffer = NULL, + .buffer_length = 0u, + .buffer_capacity = 0u + }; + uint8_array.allocator = rcutils_get_zero_initialized_allocator(); + return uint8_array; +} + +rcutils_ret_t +rcutils_uint8_array_init( + rcutils_uint8_array_t * uint8_array, + size_t buffer_capacity, + const rcutils_allocator_t * allocator) +{ + RCUTILS_CHECK_FOR_NULL_WITH_MSG( + uint8_array, + "uint8 array pointer is null", + return RCUTILS_RET_ERROR); + + if (!rcutils_allocator_is_valid(allocator)) { + RCUTILS_SET_ERROR_MSG("uint8 array has no valid allocator"); + return RCUTILS_RET_ERROR; + } + + uint8_array->buffer_length = 0; + uint8_array->buffer_capacity = buffer_capacity; + uint8_array->allocator = *allocator; + + if (buffer_capacity > 0u) { + uint8_array->buffer = (uint8_t *)allocator->allocate( + buffer_capacity * sizeof(uint8_t), allocator->state); + RCUTILS_CHECK_FOR_NULL_WITH_MSG( + uint8_array->buffer, + "failed to allocate memory for uint8 array", + return RCUTILS_RET_BAD_ALLOC); + } + + return RCUTILS_RET_OK; +} + +rcutils_ret_t +rcutils_uint8_array_fini(rcutils_uint8_array_t * uint8_array) +{ + RCUTILS_CHECK_FOR_NULL_WITH_MSG( + uint8_array, + "uint8 array pointer is null", + return RCUTILS_RET_ERROR); + + rcutils_allocator_t * allocator = &uint8_array->allocator; + if (!rcutils_allocator_is_valid(allocator)) { + RCUTILS_SET_ERROR_MSG("uint8 array has no valid allocator"); + return RCUTILS_RET_ERROR; + } + + allocator->deallocate(uint8_array->buffer, allocator->state); + uint8_array->buffer = NULL; + uint8_array->buffer_length = 0u; + uint8_array->buffer_capacity = 0u; + + return RCUTILS_RET_OK; +} + +rcutils_ret_t +rcutils_uint8_array_resize(rcutils_uint8_array_t * uint8_array, size_t new_size) +{ + RCUTILS_CHECK_FOR_NULL_WITH_MSG( + uint8_array, + "uint8 array pointer is null", + return RCUTILS_RET_ERROR); + + rcutils_allocator_t * allocator = &uint8_array->allocator; + if (!rcutils_allocator_is_valid(allocator)) { + RCUTILS_SET_ERROR_MSG("uint8 array has no valid allocator"); + return RCUTILS_RET_ERROR; + } + + if (new_size == uint8_array->buffer_capacity) { + // nothing to do here + return RCUTILS_RET_OK; + } + + uint8_array->buffer = rcutils_reallocf( + uint8_array->buffer, new_size * sizeof(uint8_t), allocator); + RCUTILS_CHECK_FOR_NULL_WITH_MSG( + uint8_array->buffer, + "failed to reallocate memory for uint8 array", + return RCUTILS_RET_BAD_ALLOC); + + uint8_array->buffer_capacity = new_size; + if (new_size < uint8_array->buffer_length) { + uint8_array->buffer_length = new_size; + } + + return RCUTILS_RET_OK; +} diff --git a/src/unsigned_char_array.c b/src/unsigned_char_array.c deleted file mode 100644 index fc90ee0d..00000000 --- a/src/unsigned_char_array.c +++ /dev/null @@ -1,116 +0,0 @@ -// Copyright 2018 Open Source Robotics Foundation, Inc. -// -// Licensed under the Apache License, Version 2.0 (the "License"); -// you may not use this file except in compliance with the License. -// You may obtain a copy of the License at -// -// http://www.apache.org/licenses/LICENSE-2.0 -// -// Unless required by applicable law or agreed to in writing, software -// distributed under the License is distributed on an "AS IS" BASIS, -// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -// See the License for the specific language governing permissions and -// limitations under the License. - -#include "rcutils/error_handling.h" -#include "rcutils/types/unsigned_char_array.h" - -rcutils_unsigned_char_array_t -rcutils_get_zero_initialized_unsigned_char_array(void) -{ - static rcutils_unsigned_char_array_t char_array = { - .buffer = NULL, - .buffer_length = 0u, - .buffer_capacity = 0u - }; - char_array.allocator = rcutils_get_zero_initialized_allocator(); - return char_array; -} - -rcutils_ret_t -rcutils_unsigned_char_array_init( - rcutils_unsigned_char_array_t * char_array, - size_t buffer_capacity, - const rcutils_allocator_t * allocator) -{ - RCUTILS_CHECK_FOR_NULL_WITH_MSG( - char_array, - "char array pointer is null", - return RCUTILS_RET_ERROR); - - if (!rcutils_allocator_is_valid(allocator)) { - RCUTILS_SET_ERROR_MSG("char array has no valid allocator"); - return RCUTILS_RET_ERROR; - } - - char_array->buffer_length = 0; - char_array->buffer_capacity = buffer_capacity; - char_array->allocator = *allocator; - - if (buffer_capacity > 0u) { - char_array->buffer = (unsigned char *)allocator->allocate( - buffer_capacity * sizeof(unsigned char), allocator->state); - RCUTILS_CHECK_FOR_NULL_WITH_MSG( - char_array->buffer, - "failed to allocate memory for char array", - return RCUTILS_RET_BAD_ALLOC); - } - - return RCUTILS_RET_OK; -} - -rcutils_ret_t -rcutils_unsigned_char_array_fini(rcutils_unsigned_char_array_t * char_array) -{ - RCUTILS_CHECK_FOR_NULL_WITH_MSG( - char_array, - "char array pointer is null", - return RCUTILS_RET_ERROR); - - rcutils_allocator_t * allocator = &char_array->allocator; - if (!rcutils_allocator_is_valid(allocator)) { - RCUTILS_SET_ERROR_MSG("char array has no valid allocator"); - return RCUTILS_RET_ERROR; - } - - allocator->deallocate(char_array->buffer, allocator->state); - char_array->buffer = NULL; - char_array->buffer_length = 0u; - char_array->buffer_capacity = 0u; - - return RCUTILS_RET_OK; -} - -rcutils_ret_t -rcutils_unsigned_char_array_resize(rcutils_unsigned_char_array_t * char_array, size_t new_size) -{ - RCUTILS_CHECK_FOR_NULL_WITH_MSG( - char_array, - "char array pointer is null", - return RCUTILS_RET_ERROR); - - rcutils_allocator_t * allocator = &char_array->allocator; - if (!rcutils_allocator_is_valid(allocator)) { - RCUTILS_SET_ERROR_MSG("char array has no valid allocator"); - return RCUTILS_RET_ERROR; - } - - if (new_size == char_array->buffer_capacity) { - // nothing to do here - return RCUTILS_RET_OK; - } - - char_array->buffer = rcutils_reallocf( - char_array->buffer, new_size * sizeof(unsigned char), allocator); - RCUTILS_CHECK_FOR_NULL_WITH_MSG( - char_array->buffer, - "failed to reallocate memory for char array", - return RCUTILS_RET_BAD_ALLOC); - - char_array->buffer_capacity = new_size; - if (new_size < char_array->buffer_length) { - char_array->buffer_length = new_size; - } - - return RCUTILS_RET_OK; -} diff --git a/test/test_uint8_array.cpp b/test/test_uint8_array.cpp new file mode 100644 index 00000000..1bb85790 --- /dev/null +++ b/test/test_uint8_array.cpp @@ -0,0 +1,73 @@ +// Copyright 2018 Open Source Robotics Foundation, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include + +#include "rcutils/allocator.h" + +#include "rcutils/types/uint8_array.h" + +TEST(test_uint8_array, default_initialization) { + auto uint8_array = rcutils_get_zero_initialized_uint8_array(); + + auto allocator = rcutils_get_default_allocator(); + EXPECT_EQ(RCUTILS_RET_OK, rcutils_uint8_array_init(&uint8_array, 0, &allocator)); + EXPECT_EQ(0u, uint8_array.buffer_capacity); + EXPECT_EQ(RCUTILS_RET_OK, rcutils_uint8_array_fini(&uint8_array)); + EXPECT_EQ(0u, uint8_array.buffer_capacity); + EXPECT_FALSE(uint8_array.buffer); +} + +TEST(test_uint8_array, resize) { + auto uint8_array = rcutils_get_zero_initialized_uint8_array(); + auto allocator = rcutils_get_default_allocator(); + auto ret = rcutils_uint8_array_init(&uint8_array, 5, &allocator); + ASSERT_EQ(RCUTILS_RET_OK, ret); + + for (size_t i = 0; i < 5; ++i) { + uint8_t c = 0xFF; + memcpy(uint8_array.buffer + i, &c, 1); + } + uint8_array.buffer_length = 5; + for (size_t i = 0; i < uint8_array.buffer_length; ++i) { + EXPECT_EQ(0xFF, uint8_array.buffer[i]); + } + + ret = rcutils_uint8_array_resize(&uint8_array, 10); + ASSERT_EQ(RCUTILS_RET_OK, ret); + EXPECT_EQ(10u, uint8_array.buffer_capacity); + EXPECT_EQ(5u, uint8_array.buffer_length); + + for (uint8_t i = 0; i < 10; ++i) { + uint8_t u = 0xFF - i; + memcpy(uint8_array.buffer + i, &u, 1); + } + uint8_array.buffer_length = 10; + for (size_t i = 0; i < uint8_array.buffer_length; ++i) { + uint8_t u = 0xFF - static_cast(i); + EXPECT_EQ(u, uint8_array.buffer[i]); + } + + ret = rcutils_uint8_array_resize(&uint8_array, 3); + ASSERT_EQ(RCUTILS_RET_OK, ret); + EXPECT_EQ(3u, uint8_array.buffer_capacity); + EXPECT_EQ(3u, uint8_array.buffer_length); + EXPECT_EQ(0xFF, uint8_array.buffer[0]); + EXPECT_EQ(0xFF - 1, uint8_array.buffer[1]); + EXPECT_EQ(0xFF - 2, uint8_array.buffer[2]); + // the other fields are garbage. + + // cleanup only 3 fields + EXPECT_EQ(RCUTILS_RET_OK, rcutils_uint8_array_fini(&uint8_array)); +} diff --git a/test/test_unsigned_char_array.cpp b/test/test_unsigned_char_array.cpp deleted file mode 100644 index 415a6ccb..00000000 --- a/test/test_unsigned_char_array.cpp +++ /dev/null @@ -1,73 +0,0 @@ -// Copyright 2018 Open Source Robotics Foundation, Inc. -// -// Licensed under the Apache License, Version 2.0 (the "License"); -// you may not use this file except in compliance with the License. -// You may obtain a copy of the License at -// -// http://www.apache.org/licenses/LICENSE-2.0 -// -// Unless required by applicable law or agreed to in writing, software -// distributed under the License is distributed on an "AS IS" BASIS, -// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -// See the License for the specific language governing permissions and -// limitations under the License. - -#include - -#include "rcutils/allocator.h" - -#include "rcutils/types/unsigned_char_array.h" - -TEST(test_unsigned_char_array, default_initialization) { - auto char_array = rcutils_get_zero_initialized_unsigned_char_array(); - - auto allocator = rcutils_get_default_allocator(); - EXPECT_EQ(RCUTILS_RET_OK, rcutils_unsigned_char_array_init(&char_array, 0, &allocator)); - EXPECT_EQ(0u, char_array.buffer_capacity); - EXPECT_EQ(RCUTILS_RET_OK, rcutils_unsigned_char_array_fini(&char_array)); - EXPECT_EQ(0u, char_array.buffer_capacity); - EXPECT_FALSE(char_array.buffer); -} - -TEST(test_unsigned_char_array, resize) { - auto char_array = rcutils_get_zero_initialized_unsigned_char_array(); - auto allocator = rcutils_get_default_allocator(); - auto ret = rcutils_unsigned_char_array_init(&char_array, 5, &allocator); - ASSERT_EQ(RCUTILS_RET_OK, ret); - - for (size_t i = 0; i < 5; ++i) { - unsigned char c = 0xFF; - memcpy(char_array.buffer + i, &c, 1); - } - char_array.buffer_length = 5; - for (size_t i = 0; i < char_array.buffer_length; ++i) { - EXPECT_EQ(0xFF, char_array.buffer[i]); - } - - ret = rcutils_unsigned_char_array_resize(&char_array, 10); - ASSERT_EQ(RCUTILS_RET_OK, ret); - EXPECT_EQ(10u, char_array.buffer_capacity); - EXPECT_EQ(5u, char_array.buffer_length); - - for (size_t i = 0; i < 10; ++i) { - unsigned char c = 0xFF - i; - memcpy(char_array.buffer + i, &c, 1); - } - char_array.buffer_length = 10; - for (size_t i = 0; i < char_array.buffer_length; ++i) { - unsigned char c = 0xFF - i; - EXPECT_EQ(c, char_array.buffer[i]); - } - - ret = rcutils_unsigned_char_array_resize(&char_array, 3); - ASSERT_EQ(RCUTILS_RET_OK, ret); - EXPECT_EQ(3u, char_array.buffer_capacity); - EXPECT_EQ(3u, char_array.buffer_length); - EXPECT_EQ(0xFF, char_array.buffer[0]); - EXPECT_EQ(0xFF - 1, char_array.buffer[1]); - EXPECT_EQ(0xFF - 2, char_array.buffer[2]); - // the other fields are garbage. - - // cleanup only 3 fields - EXPECT_EQ(RCUTILS_RET_OK, rcutils_unsigned_char_array_fini(&char_array)); -} From d3e6938bb7e458c8a64637e8fe875a0f1e63b429 Mon Sep 17 00:00:00 2001 From: Karsten Knese Date: Wed, 7 Nov 2018 14:39:55 -0800 Subject: [PATCH 3/8] include stdint.h --- include/rcutils/types/uint8_array.h | 2 ++ 1 file changed, 2 insertions(+) diff --git a/include/rcutils/types/uint8_array.h b/include/rcutils/types/uint8_array.h index 8bb5b861..f61a0e9c 100644 --- a/include/rcutils/types/uint8_array.h +++ b/include/rcutils/types/uint8_array.h @@ -20,6 +20,8 @@ extern "C" { #endif +#include + #include "rcutils/allocator.h" #include "rcutils/types/rcutils_ret.h" #include "rcutils/visibility_control.h" From 56e48d26758a1192d53c592f71fba997ade5b3f3 Mon Sep 17 00:00:00 2001 From: Karsten Knese Date: Mon, 12 Nov 2018 14:53:57 -0800 Subject: [PATCH 4/8] address comments --- include/rcutils/types/uint8_array.h | 18 +++++----- src/uint8_array.c | 52 ++++++++++++----------------- test/test_uint8_array.cpp | 15 ++++++--- 3 files changed, 40 insertions(+), 45 deletions(-) diff --git a/include/rcutils/types/uint8_array.h b/include/rcutils/types/uint8_array.h index f61a0e9c..e8961ea2 100644 --- a/include/rcutils/types/uint8_array.h +++ b/include/rcutils/types/uint8_array.h @@ -45,8 +45,7 @@ rcutils_get_zero_initialized_uint8_array(void); /// Initialize a zero initialized uint8 array struct. /** - * This function may leak if the uint8 array struct is already - * pre-initialized. + * This function may leak if the uint8 array struct is already initialized. * If the capacity is set to 0, no memory is allocated and the internal buffer * is still NULL. * @@ -54,7 +53,8 @@ rcutils_get_zero_initialized_uint8_array(void); * \param buffer_capacity the size of the memory to allocate for the byte stream * \param allocator the allocator to use for the memory allocation * \return `RCUTILS_RET_OK` if successful, or - * \return `RCUTILS_RET_ERROR` if an unexpected error occurs + * \return `RCUTILS_RET_INVALID_ARGUMENTS` if any of the arguments are incorrect, or + * \return 'RCUTILS_RET_BAD_ALLOC` if no memory could be allocated correctly */ RCUTILS_PUBLIC RCUTILS_WARN_UNUSED @@ -67,14 +67,14 @@ rcutils_uint8_array_init( /// Finalize a uint8 array struct. /** * Cleans up and deallocates any resources used in a rcutils_uint8_array_t. - * Passing a rcutils_uint8_array_t which has not been zero initialized using - * rcutils_get_zero_initialized_uint8_array() to this function is undefined + * The array passed to this function needs to have been initialized by + * rcutils_uint8_array_init() or similar. + * Passing an uninitialized instance to this function leads to undefined * behavior. * * \param uint8_array pointer to the rcutils_uint8_array_t to be cleaned up * \return `RCUTILS_RET_OK` if successful, or - * \return `RCUTILS_RET_BAD_ALLOC` if memory allocation failed, or - * \return `RCUTILS_RET_ERROR` if an unexpected error occurs + * \return `RCUTILS_RET_INVALID_ARGUMENTS` if the uint8_array or any of its members is wrong */ RCUTILS_PUBLIC RCUTILS_WARN_UNUSED @@ -88,14 +88,14 @@ rcutils_uint8_array_fini(rcutils_uint8_array_t * uint8_array); * truncated. * Be aware, that this will deallocate the memory and therefore invalidates any * pointers to this storage. - * If the new size is larger, new memory is getting allocated and the existing + * If the new size is larger, new memory is allocated and the existing * content is copied over. * * \param uint8_array pointer to the instance of rcutils_uint8_array_t which is being resized * \param new_size the new size of the internal buffer * \return `RCUTILS_RET_OK` if successful, or + * \return `RCUTILS_RET_INVALID_ARGUMENT` if new_size is set to zero * \return `RCUTILS_RET_BAD_ALLOC` if memory allocation failed, or - * \return `RCUTILS_RET_ERROR` if an unexpected error occurs */ RCUTILS_PUBLIC RCUTILS_WARN_UNUSED diff --git a/src/uint8_array.c b/src/uint8_array.c index 1d6857b7..85eeecf6 100644 --- a/src/uint8_array.c +++ b/src/uint8_array.c @@ -20,8 +20,8 @@ rcutils_get_zero_initialized_uint8_array(void) { static rcutils_uint8_array_t uint8_array = { .buffer = NULL, - .buffer_length = 0u, - .buffer_capacity = 0u + .buffer_length = 0lu, + .buffer_capacity = 0lu }; uint8_array.allocator = rcutils_get_zero_initialized_allocator(); return uint8_array; @@ -33,26 +33,21 @@ rcutils_uint8_array_init( size_t buffer_capacity, const rcutils_allocator_t * allocator) { - RCUTILS_CHECK_FOR_NULL_WITH_MSG( - uint8_array, - "uint8 array pointer is null", - return RCUTILS_RET_ERROR); - - if (!rcutils_allocator_is_valid(allocator)) { - RCUTILS_SET_ERROR_MSG("uint8 array has no valid allocator"); - return RCUTILS_RET_ERROR; - } + RCUTILS_CHECK_ARGUMENT_FOR_NULL(uint8_array, RCUTILS_RET_INVALID_ARGUMENT); + RCUTILS_CHECK_ALLOCATOR(allocator, return RCUTILS_RET_INVALID_ARGUMENT); - uint8_array->buffer_length = 0; + uint8_array->buffer_length = 0lu; uint8_array->buffer_capacity = buffer_capacity; uint8_array->allocator = *allocator; - if (buffer_capacity > 0u) { + if (buffer_capacity > 0lu) { uint8_array->buffer = (uint8_t *)allocator->allocate( buffer_capacity * sizeof(uint8_t), allocator->state); RCUTILS_CHECK_FOR_NULL_WITH_MSG( uint8_array->buffer, "failed to allocate memory for uint8 array", + uint8_array->buffer_capacity = 0lu; + uint8_array->buffer_length = 0lu; return RCUTILS_RET_BAD_ALLOC); } @@ -62,21 +57,15 @@ rcutils_uint8_array_init( rcutils_ret_t rcutils_uint8_array_fini(rcutils_uint8_array_t * uint8_array) { - RCUTILS_CHECK_FOR_NULL_WITH_MSG( - uint8_array, - "uint8 array pointer is null", - return RCUTILS_RET_ERROR); + RCUTILS_CHECK_ARGUMENT_FOR_NULL(uint8_array, RCUTILS_RET_INVALID_ARGUMENT); rcutils_allocator_t * allocator = &uint8_array->allocator; - if (!rcutils_allocator_is_valid(allocator)) { - RCUTILS_SET_ERROR_MSG("uint8 array has no valid allocator"); - return RCUTILS_RET_ERROR; - } + RCUTILS_CHECK_ALLOCATOR(allocator, return RCUTILS_RET_INVALID_ARGUMENT); allocator->deallocate(uint8_array->buffer, allocator->state); uint8_array->buffer = NULL; - uint8_array->buffer_length = 0u; - uint8_array->buffer_capacity = 0u; + uint8_array->buffer_length = 0lu; + uint8_array->buffer_capacity = 0lu; return RCUTILS_RET_OK; } @@ -84,17 +73,16 @@ rcutils_uint8_array_fini(rcutils_uint8_array_t * uint8_array) rcutils_ret_t rcutils_uint8_array_resize(rcutils_uint8_array_t * uint8_array, size_t new_size) { - RCUTILS_CHECK_FOR_NULL_WITH_MSG( - uint8_array, - "uint8 array pointer is null", - return RCUTILS_RET_ERROR); + RCUTILS_CHECK_ARGUMENT_FOR_NULL(uint8_array, RCUTILS_RET_INVALID_ARGUMENT); - rcutils_allocator_t * allocator = &uint8_array->allocator; - if (!rcutils_allocator_is_valid(allocator)) { - RCUTILS_SET_ERROR_MSG("uint8 array has no valid allocator"); - return RCUTILS_RET_ERROR; + if (new_size == 0lu) { + RCUTILS_SET_ERROR_MSG("new size of uint8_array has to be greater than zero"); + return RCUTILS_RET_INVALID_ARGUMENT; } + rcutils_allocator_t * allocator = &uint8_array->allocator; + RCUTILS_CHECK_ALLOCATOR(allocator, return RCUTILS_RET_INVALID_ARGUMENT); + if (new_size == uint8_array->buffer_capacity) { // nothing to do here return RCUTILS_RET_OK; @@ -105,6 +93,8 @@ rcutils_uint8_array_resize(rcutils_uint8_array_t * uint8_array, size_t new_size) RCUTILS_CHECK_FOR_NULL_WITH_MSG( uint8_array->buffer, "failed to reallocate memory for uint8 array", + uint8_array->buffer_capacity = 0lu; + uint8_array->buffer_length = 0lu; return RCUTILS_RET_BAD_ALLOC); uint8_array->buffer_capacity = new_size; diff --git a/test/test_uint8_array.cpp b/test/test_uint8_array.cpp index 1bb85790..748648ee 100644 --- a/test/test_uint8_array.cpp +++ b/test/test_uint8_array.cpp @@ -23,9 +23,9 @@ TEST(test_uint8_array, default_initialization) { auto allocator = rcutils_get_default_allocator(); EXPECT_EQ(RCUTILS_RET_OK, rcutils_uint8_array_init(&uint8_array, 0, &allocator)); - EXPECT_EQ(0u, uint8_array.buffer_capacity); + EXPECT_EQ(0lu, uint8_array.buffer_capacity); EXPECT_EQ(RCUTILS_RET_OK, rcutils_uint8_array_fini(&uint8_array)); - EXPECT_EQ(0u, uint8_array.buffer_capacity); + EXPECT_EQ(0lu, uint8_array.buffer_capacity); EXPECT_FALSE(uint8_array.buffer); } @@ -44,6 +44,11 @@ TEST(test_uint8_array, resize) { EXPECT_EQ(0xFF, uint8_array.buffer[i]); } + ret = rcutils_uint8_array_resize(&uint8_array, 0); + ASSERT_EQ(RCUTILS_RET_INVALID_ARGUMENT, ret); + EXPECT_EQ(5lu, uint8_array.buffer_capacity); + EXPECT_EQ(5lu, uint8_array.buffer_length); + ret = rcutils_uint8_array_resize(&uint8_array, 10); ASSERT_EQ(RCUTILS_RET_OK, ret); EXPECT_EQ(10u, uint8_array.buffer_capacity); @@ -53,7 +58,7 @@ TEST(test_uint8_array, resize) { uint8_t u = 0xFF - i; memcpy(uint8_array.buffer + i, &u, 1); } - uint8_array.buffer_length = 10; + uint8_array.buffer_length = 10lu; for (size_t i = 0; i < uint8_array.buffer_length; ++i) { uint8_t u = 0xFF - static_cast(i); EXPECT_EQ(u, uint8_array.buffer[i]); @@ -61,8 +66,8 @@ TEST(test_uint8_array, resize) { ret = rcutils_uint8_array_resize(&uint8_array, 3); ASSERT_EQ(RCUTILS_RET_OK, ret); - EXPECT_EQ(3u, uint8_array.buffer_capacity); - EXPECT_EQ(3u, uint8_array.buffer_length); + EXPECT_EQ(3lu, uint8_array.buffer_capacity); + EXPECT_EQ(3lu, uint8_array.buffer_length); EXPECT_EQ(0xFF, uint8_array.buffer[0]); EXPECT_EQ(0xFF - 1, uint8_array.buffer[1]); EXPECT_EQ(0xFF - 2, uint8_array.buffer[2]); From d40ed610fd87d04ded5bdfb33755464dc95de043 Mon Sep 17 00:00:00 2001 From: William Woodall Date: Mon, 12 Nov 2018 15:21:04 -0800 Subject: [PATCH 5/8] Update include/rcutils/types/uint8_array.h Co-Authored-By: Karsten1987 --- include/rcutils/types/uint8_array.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/include/rcutils/types/uint8_array.h b/include/rcutils/types/uint8_array.h index e8961ea2..cd281ae3 100644 --- a/include/rcutils/types/uint8_array.h +++ b/include/rcutils/types/uint8_array.h @@ -74,7 +74,7 @@ rcutils_uint8_array_init( * * \param uint8_array pointer to the rcutils_uint8_array_t to be cleaned up * \return `RCUTILS_RET_OK` if successful, or - * \return `RCUTILS_RET_INVALID_ARGUMENTS` if the uint8_array or any of its members is wrong + * \return `RCUTILS_RET_INVALID_ARGUMENTS` if the uint8_array argument is invalid */ RCUTILS_PUBLIC RCUTILS_WARN_UNUSED From 6a2844dfbf80c863250d97e2e5197cedbabed011 Mon Sep 17 00:00:00 2001 From: William Woodall Date: Mon, 12 Nov 2018 15:21:15 -0800 Subject: [PATCH 6/8] Update include/rcutils/types/uint8_array.h Co-Authored-By: Karsten1987 --- include/rcutils/types/uint8_array.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/include/rcutils/types/uint8_array.h b/include/rcutils/types/uint8_array.h index cd281ae3..e0ff942c 100644 --- a/include/rcutils/types/uint8_array.h +++ b/include/rcutils/types/uint8_array.h @@ -68,7 +68,7 @@ rcutils_uint8_array_init( /** * Cleans up and deallocates any resources used in a rcutils_uint8_array_t. * The array passed to this function needs to have been initialized by - * rcutils_uint8_array_init() or similar. + * rcutils_uint8_array_init(). * Passing an uninitialized instance to this function leads to undefined * behavior. * From a3842e4b172aab844a8080ae7482b0e4eeaab222 Mon Sep 17 00:00:00 2001 From: William Woodall Date: Mon, 12 Nov 2018 15:21:20 -0800 Subject: [PATCH 7/8] Update include/rcutils/types/uint8_array.h Co-Authored-By: Karsten1987 --- include/rcutils/types/uint8_array.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/include/rcutils/types/uint8_array.h b/include/rcutils/types/uint8_array.h index e0ff942c..fd16c199 100644 --- a/include/rcutils/types/uint8_array.h +++ b/include/rcutils/types/uint8_array.h @@ -53,7 +53,7 @@ rcutils_get_zero_initialized_uint8_array(void); * \param buffer_capacity the size of the memory to allocate for the byte stream * \param allocator the allocator to use for the memory allocation * \return `RCUTILS_RET_OK` if successful, or - * \return `RCUTILS_RET_INVALID_ARGUMENTS` if any of the arguments are incorrect, or + * \return `RCUTILS_RET_INVALID_ARGUMENTS` if any arguments are invalid, or * \return 'RCUTILS_RET_BAD_ALLOC` if no memory could be allocated correctly */ RCUTILS_PUBLIC From 06702b07e2f473509745ce5c517b3f6c6e0d1fe0 Mon Sep 17 00:00:00 2001 From: Karsten Knese Date: Mon, 12 Nov 2018 15:38:18 -0800 Subject: [PATCH 8/8] allow RCUTILS_RET_ERROR --- include/rcutils/types/uint8_array.h | 7 ++++--- 1 file changed, 4 insertions(+), 3 deletions(-) diff --git a/include/rcutils/types/uint8_array.h b/include/rcutils/types/uint8_array.h index fd16c199..cf767aac 100644 --- a/include/rcutils/types/uint8_array.h +++ b/include/rcutils/types/uint8_array.h @@ -55,6 +55,7 @@ rcutils_get_zero_initialized_uint8_array(void); * \return `RCUTILS_RET_OK` if successful, or * \return `RCUTILS_RET_INVALID_ARGUMENTS` if any arguments are invalid, or * \return 'RCUTILS_RET_BAD_ALLOC` if no memory could be allocated correctly + * \return `RCUTILS_RET_ERROR` if an unexpected error occurs */ RCUTILS_PUBLIC RCUTILS_WARN_UNUSED @@ -75,6 +76,7 @@ rcutils_uint8_array_init( * \param uint8_array pointer to the rcutils_uint8_array_t to be cleaned up * \return `RCUTILS_RET_OK` if successful, or * \return `RCUTILS_RET_INVALID_ARGUMENTS` if the uint8_array argument is invalid + * \return `RCUTILS_RET_ERROR` if an unexpected error occurs */ RCUTILS_PUBLIC RCUTILS_WARN_UNUSED @@ -86,16 +88,15 @@ rcutils_uint8_array_fini(rcutils_uint8_array_t * uint8_array); * The internal buffer of the uint8 array can be resized dynamically if needed. * If the new size is smaller than the current capacity, then the memory is * truncated. - * Be aware, that this will deallocate the memory and therefore invalidates any + * Be aware, that this might deallocate the memory and therefore invalidates any * pointers to this storage. - * If the new size is larger, new memory is allocated and the existing - * content is copied over. * * \param uint8_array pointer to the instance of rcutils_uint8_array_t which is being resized * \param new_size the new size of the internal buffer * \return `RCUTILS_RET_OK` if successful, or * \return `RCUTILS_RET_INVALID_ARGUMENT` if new_size is set to zero * \return `RCUTILS_RET_BAD_ALLOC` if memory allocation failed, or + * \return `RCUTILS_RET_ERROR` if an unexpected error occurs */ RCUTILS_PUBLIC RCUTILS_WARN_UNUSED