diff --git a/include/rcutils/logging.h b/include/rcutils/logging.h
index 3950555d..32a75c90 100644
--- a/include/rcutils/logging.h
+++ b/include/rcutils/logging.h
@@ -219,10 +219,6 @@ typedef void (* rcutils_logging_output_handler_t)(
va_list * // args
);
-/// The function pointer of the current output handler.
-RCUTILS_PUBLIC
-extern rcutils_logging_output_handler_t g_rcutils_logging_output_handler;
-
/// Get the current output handler.
/**
*
@@ -283,16 +279,6 @@ rcutils_ret_t rcutils_logging_format_message(
int severity, const char * name, rcutils_time_point_value_t timestamp,
const char * msg, rcutils_char_array_t * logging_output);
-/// The default severity level for loggers.
-/**
- * This level is used for (1) nameless log calls and (2) named log
- * calls where the effective level of the logger name is unspecified.
- *
- * \see rcutils_logging_get_logger_effective_level()
- */
-RCUTILS_PUBLIC
-extern int g_rcutils_logging_default_logger_level;
-
/// Get the default level for loggers.
/**
*
@@ -345,7 +331,7 @@ void rcutils_logging_set_default_logger_level(int level);
* \param[in] name The name of the logger, must be null terminated c string
* \return The level of the logger if it has been set, or
* \return `RCUTILS_LOG_SEVERITY_UNSET` if unset, or
- * \return `g_rcutils_logging_default_logger_level` for an empty name, or
+ * \return the default logger level for an empty name, or
* \return -1 on invalid arguments, or
* \return -1 if an error occurred
*/
@@ -370,7 +356,7 @@ int rcutils_logging_get_logger_level(const char * name);
* \param[in] name_length Logger name length
* \return The level of the logger if it has been set, or
* \return `RCUTILS_LOG_SEVERITY_UNSET` if unset, or
- * \return `g_rcutils_logging_default_logger_level` for `name_length` of `0`, or
+ * \return the default logger level for an empty name, or
* \return -1 on invalid arguments, or
* \return -1 if an error occurred
*/
@@ -380,8 +366,7 @@ int rcutils_logging_get_logger_leveln(const char * name, size_t name_length);
/// Set the severity level for a logger.
/**
- * If an empty string is specified as the name, the
- * `g_rcutils_logging_default_logger_level` will be set.
+ * If an empty string is specified as the name, the default logger level will be set.
*
*
* Attribute | Adherence
diff --git a/include/rcutils/types/hash_map.h b/include/rcutils/types/hash_map.h
index 2c22e0bb..55f43bfa 100644
--- a/include/rcutils/types/hash_map.h
+++ b/include/rcutils/types/hash_map.h
@@ -156,7 +156,7 @@ rcutils_get_zero_initialized_hash_map();
* ```
*
* \param[inout] hash_map rcutils_hash_map_t to be initialized
- * \param[in] initial_capacity the amount of initial capacity for the hash_map
+ * \param[in] initial_capacity the amount of initial capacity for the hash_map - this must be greater than zero and a power of 2
* \param[in] key_size the size (in bytes) of the key used to index the data
* \param[in] data_size the size (in bytes) of the data being stored
* \param[in] key_hashing_func a function that returns a hashed value for a key
diff --git a/src/char_array.c b/src/char_array.c
index 226b9f17..aa24b055 100644
--- a/src/char_array.c
+++ b/src/char_array.c
@@ -139,6 +139,12 @@ rcutils_char_array_expand_as_needed(rcutils_char_array_t * char_array, size_t ne
return RCUTILS_RET_OK;
}
+ // Make sure we expand by at least 1.5x the old capacity
+ size_t minimum_size = char_array->buffer_capacity + (char_array->buffer_capacity >> 1);
+ if (new_size < minimum_size) {
+ new_size = minimum_size;
+ }
+
return rcutils_char_array_resize(char_array, new_size);
}
diff --git a/src/find.c b/src/find.c
index ab39e42f..d5dbf7aa 100644
--- a/src/find.c
+++ b/src/find.c
@@ -12,11 +12,6 @@
// See the License for the specific language governing permissions and
// limitations under the License.
-#ifdef __cplusplus
-extern "C"
-{
-#endif
-
#include
#include
#include
@@ -65,14 +60,19 @@ rcutils_find_lastn(const char * str, char delimiter, size_t string_length)
return SIZE_MAX;
}
+#if defined(_GNU_SOURCE)
+ const char * ptr = memrchr(str, delimiter, string_length);
+ if (ptr == NULL) {
+ return SIZE_MAX;
+ }
+
+ return ptr - str;
+#else
for (size_t i = string_length - 1; i > 0; --i) {
if (str[i] == delimiter) {
return i;
}
}
return str[0] == delimiter ? 0 : SIZE_MAX;
-}
-
-#ifdef __cplusplus
-}
#endif
+}
diff --git a/src/hash_map.c b/src/hash_map.c
index ecab884a..ad3c3086 100644
--- a/src/hash_map.c
+++ b/src/hash_map.c
@@ -255,6 +255,13 @@ rcutils_hash_map_init(
return RCUTILS_RET_INVALID_ARGUMENT;
}
+ // Due to an optimization we use during lookup, we can currently only handle power-of-two
+ // capacities. Enforce that here.
+ if ((initial_capacity & (initial_capacity - 1)) != 0) {
+ RCUTILS_SET_ERROR_MSG("This hashmap only works with power-of-two capacities");
+ return RCUTILS_RET_INVALID_ARGUMENT;
+ }
+
hash_map->impl = allocator->allocate(sizeof(rcutils_hash_map_impl_t), allocator->state);
if (NULL == hash_map->impl) {
RCUTILS_SET_ERROR_MSG("failed to allocate memory for hash map impl");
@@ -329,7 +336,14 @@ static bool hash_map_find(
rcutils_hash_map_entry_t * bucket_entry = NULL;
*key_hash = hash_map->impl->key_hashing_func(key);
- *map_index = (*key_hash) % hash_map->impl->capacity;
+ // The below is equivalent to:
+ //
+ // *map_index = (*key_hash) % hash_map->impl->capacity;
+ //
+ // This implementation is significantly faster since it avoids a divide, but
+ // only works when the capacity is a power of two. We enforce that in the
+ // rcutils_hash_map_init() function.
+ *map_index = (*key_hash) & (hash_map->impl->capacity - 1);
// Find the bucket the entry should be in check that it's valid
rcutils_array_list_t * bucket = &(hash_map->impl->map[*map_index]);
@@ -394,7 +408,8 @@ rcutils_hash_map_set(rcutils_hash_map_t * hash_map, const void * key, const void
memcpy(entry->value, value, hash_map->impl->data_size);
memcpy(entry->key, key, hash_map->impl->key_size);
- bucket_index = key_hash % hash_map->impl->capacity;
+ // See the comment in hash_map_find for why we do this.
+ bucket_index = key_hash & (hash_map->impl->capacity - 1);
ret = hash_map_insert_entry(hash_map->impl->map, bucket_index, entry, allocator);
}
@@ -424,6 +439,11 @@ rcutils_hash_map_unset(rcutils_hash_map_t * hash_map, const void * key)
bool already_exists = false;
rcutils_hash_map_entry_t * entry = NULL;
+ // If there is nothing in the hash map, don't bother computing the key
+ if (hash_map->impl->size == 0) {
+ return RCUTILS_RET_OK;
+ }
+
already_exists = hash_map_find(hash_map, key, &key_hash, &map_index, &bucket_index, &entry);
if (!already_exists) {
@@ -457,6 +477,11 @@ rcutils_hash_map_key_exists(const rcutils_hash_map_t * hash_map, const void * ke
bool already_exists = false;
rcutils_hash_map_entry_t * entry = NULL;
+ // If there is nothing in the hash map, don't bother computing the key
+ if (hash_map->impl->size == 0) {
+ return RCUTILS_RET_OK;
+ }
+
already_exists = hash_map_find(hash_map, key, &key_hash, &map_index, &bucket_index, &entry);
return already_exists;
@@ -473,6 +498,11 @@ rcutils_hash_map_get(const rcutils_hash_map_t * hash_map, const void * key, void
bool already_exists = false;
rcutils_hash_map_entry_t * entry = NULL;
+ // If there is nothing in the hash map, don't bother computing the key
+ if (hash_map->impl->size == 0) {
+ return RCUTILS_RET_NOT_FOUND;
+ }
+
already_exists = hash_map_find(hash_map, key, &key_hash, &map_index, &bucket_index, &entry);
if (already_exists) {
@@ -499,6 +529,15 @@ rcutils_hash_map_get_next_key_and_data(
rcutils_hash_map_entry_t * entry = NULL;
rcutils_ret_t ret = RCUTILS_RET_OK;
+ // If there is nothing in the hash map, don't bother computing the key
+ if (hash_map->impl->size == 0) {
+ if (NULL != previous_key) {
+ return RCUTILS_RET_NOT_FOUND;
+ } else {
+ return RCUTILS_RET_HASH_MAP_NO_MORE_ENTRIES;
+ }
+ }
+
if (NULL != previous_key) {
already_exists = hash_map_find(hash_map, key, &key_hash, &map_index, &bucket_index, &entry);
if (!already_exists) {
diff --git a/src/logging.c b/src/logging.c
index 9854670d..00e1853e 100644
--- a/src/logging.c
+++ b/src/logging.c
@@ -89,14 +89,14 @@ static const char * g_rcutils_logging_default_output_format =
static rcutils_allocator_t g_rcutils_logging_allocator;
-rcutils_logging_output_handler_t g_rcutils_logging_output_handler = NULL;
+static rcutils_logging_output_handler_t g_rcutils_logging_output_handler = NULL;
static rcutils_string_map_t g_rcutils_logging_severities_map;
// If this is false, attempts to use the severities map will be skipped.
// This can happen if allocation of the map fails at initialization.
static bool g_rcutils_logging_severities_map_valid = false;
-int g_rcutils_logging_default_logger_level = 0;
+static int g_rcutils_logging_default_logger_level = 0;
static FILE * g_output_stream = NULL;
diff --git a/test/benchmark/benchmark_logging.cpp b/test/benchmark/benchmark_logging.cpp
index c4c29417..e6123f21 100644
--- a/test/benchmark/benchmark_logging.cpp
+++ b/test/benchmark/benchmark_logging.cpp
@@ -49,7 +49,7 @@ static void benchmark_logging(benchmark::State & state)
ret_value = rcutils_logging_shutdown();
(void) ret_value;
});
- g_rcutils_logging_default_logger_level = RCUTILS_LOG_SEVERITY_DEBUG;
+ rcutils_logging_set_default_logger_level(RCUTILS_LOG_SEVERITY_DEBUG);
auto rcutils_logging_console_output_handler = [](
const rcutils_log_location_t * location,
diff --git a/test/test_hash_map.cpp b/test/test_hash_map.cpp
index c5236ddc..a4536d10 100644
--- a/test/test_hash_map.cpp
+++ b/test/test_hash_map.cpp
@@ -95,6 +95,13 @@ TEST_F(HashMapBaseTest, init_map_initial_capacity_zero_fails) {
EXPECT_EQ(RCUTILS_RET_INVALID_ARGUMENT, ret) << rcutils_get_error_string().str;
}
+TEST_F(HashMapBaseTest, init_map_initial_capacity_not_power_of_two_fails) {
+ rcutils_ret_t ret = rcutils_hash_map_init(
+ &map, 3, sizeof(uint32_t), sizeof(uint32_t),
+ test_hash_map_uint32_hash_func, test_uint32_cmp, &allocator);
+ EXPECT_EQ(RCUTILS_RET_INVALID_ARGUMENT, ret) << rcutils_get_error_string().str;
+}
+
TEST_F(HashMapBaseTest, init_map_key_size_zero_fails) {
rcutils_ret_t ret = rcutils_hash_map_init(
&map, 2, 0, sizeof(uint32_t),
@@ -480,7 +487,7 @@ TEST_F(HashMapBaseTest, string_keys) {
const char * key2 = "two";
const char * lookup_key = "one";
rcutils_ret_t ret = rcutils_hash_map_init(
- &map, 10, sizeof(char *), sizeof(uint32_t),
+ &map, 8, sizeof(char *), sizeof(uint32_t),
rcutils_hash_map_string_hash_func, rcutils_hash_map_string_cmp_func,
&allocator);
EXPECT_EQ(RCUTILS_RET_OK, ret) << rcutils_get_error_string().str;
diff --git a/test/test_logging.cpp b/test/test_logging.cpp
index 89e7d485..50cc5aed 100644
--- a/test/test_logging.cpp
+++ b/test/test_logging.cpp
@@ -67,8 +67,8 @@ TEST(TestLogging, test_logging) {
EXPECT_EQ(RCUTILS_RET_OK, rcutils_logging_shutdown());
});
EXPECT_TRUE(g_rcutils_logging_initialized);
- g_rcutils_logging_default_logger_level = RCUTILS_LOG_SEVERITY_DEBUG;
- EXPECT_EQ(RCUTILS_LOG_SEVERITY_DEBUG, g_rcutils_logging_default_logger_level);
+ rcutils_logging_set_default_logger_level(RCUTILS_LOG_SEVERITY_DEBUG);
+ EXPECT_EQ(RCUTILS_LOG_SEVERITY_DEBUG, rcutils_logging_get_default_logger_level());
auto rcutils_logging_console_output_handler = [](
const rcutils_log_location_t * location,
diff --git a/test/test_logging_custom_env.cpp b/test/test_logging_custom_env.cpp
index b1efbe69..222396df 100644
--- a/test/test_logging_custom_env.cpp
+++ b/test/test_logging_custom_env.cpp
@@ -30,7 +30,7 @@ TEST(TestLoggingCustomEnv, test_logging) {
EXPECT_EQ(RCUTILS_RET_OK, rcutils_logging_shutdown());
});
EXPECT_TRUE(g_rcutils_logging_initialized);
- g_rcutils_logging_default_logger_level = RCUTILS_LOG_SEVERITY_DEBUG;
+ rcutils_logging_set_default_logger_level(RCUTILS_LOG_SEVERITY_DEBUG);
rcutils_ret_t ret;
rcutils_allocator_t allocator = rcutils_get_default_allocator();
diff --git a/test/test_logging_macros.cpp b/test/test_logging_macros.cpp
index b193ed5e..6637c4df 100644
--- a/test/test_logging_macros.cpp
+++ b/test/test_logging_macros.cpp
@@ -46,8 +46,8 @@ class TestLoggingMacros : public ::testing::Test
EXPECT_FALSE(g_rcutils_logging_initialized);
ASSERT_EQ(RCUTILS_RET_OK, rcutils_logging_initialize());
EXPECT_TRUE(g_rcutils_logging_initialized);
- g_rcutils_logging_default_logger_level = RCUTILS_LOG_SEVERITY_DEBUG;
- EXPECT_EQ(RCUTILS_LOG_SEVERITY_DEBUG, g_rcutils_logging_default_logger_level);
+ rcutils_logging_set_default_logger_level(RCUTILS_LOG_SEVERITY_DEBUG);
+ EXPECT_EQ(RCUTILS_LOG_SEVERITY_DEBUG, rcutils_logging_get_default_logger_level());
auto rcutils_logging_console_output_handler = [](
const rcutils_log_location_t * location,
@@ -120,14 +120,14 @@ TEST_F(TestLoggingMacros, test_logging_function) {
g_function_called = false;
// check that evaluation of a specified function does not occur if the severity is not enabled
- g_rcutils_logging_default_logger_level = RCUTILS_LOG_SEVERITY_INFO;
+ rcutils_logging_set_default_logger_level(RCUTILS_LOG_SEVERITY_INFO);
for (int i : {0, 1}) { // cover both true and false return values
g_counter = i;
RCUTILS_LOG_DEBUG_FUNCTION(¬_divisible_by_three, "message %d", i);
}
EXPECT_EQ(0u, g_log_calls);
EXPECT_FALSE(g_function_called);
- g_rcutils_logging_default_logger_level = RCUTILS_LOG_SEVERITY_DEBUG;
+ rcutils_logging_set_default_logger_level(RCUTILS_LOG_SEVERITY_DEBUG);
for (int i : {1, 2, 3, 4, 5, 6}) {
g_counter = i;