Skip to content
Closed
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
6 changes: 5 additions & 1 deletion rcl_logging_spdlog/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -45,8 +45,12 @@ install(DIRECTORY include/${PROJECT_NAME}/
if(BUILD_TESTING)
find_package(ament_lint_auto REQUIRED)
ament_lint_auto_find_test_dependencies()

find_package(ament_cmake_gtest REQUIRED)

ament_add_gtest(test_logging_spdlog test/test_logging.cpp)
target_link_libraries(test_logging_spdlog ${PROJECT_NAME})
ament_target_dependencies(test_logging_spdlog rcutils)

ament_add_gtest(test_logging_interface test/test_logging_interface.cpp)
if(TARGET test_logging_interface)
target_link_libraries(test_logging_interface ${PROJECT_NAME})
Expand Down
94 changes: 94 additions & 0 deletions rcl_logging_spdlog/test/allocator_testing_utils.h
Original file line number Diff line number Diff line change
@@ -0,0 +1,94 @@
// Copyright 2017 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 ALLOCATOR_TESTING_UTILS_H_
#define ALLOCATOR_TESTING_UTILS_H_

#ifdef __cplusplus
extern "C"
{
#endif

#include <stddef.h>

#include "rcutils/allocator.h"

typedef struct __failing_allocator_state
{
bool is_failing;
} __failing_allocator_state;

void *
failing_malloc(size_t size, void * state)
{
if (((__failing_allocator_state *)state)->is_failing) {
return nullptr;
}
return rcutils_get_default_allocator().allocate(size, rcutils_get_default_allocator().state);
}

void *
failing_realloc(void * pointer, size_t size, void * state)
{
if (((__failing_allocator_state *)state)->is_failing) {
return nullptr;
}
return rcutils_get_default_allocator().reallocate(
pointer, size, rcutils_get_default_allocator().state);
}

void
failing_free(void * pointer, void * state)
{
if (((__failing_allocator_state *)state)->is_failing) {
return;
}
rcutils_get_default_allocator().deallocate(pointer, rcutils_get_default_allocator().state);
}

void *
failing_calloc(size_t number_of_elements, size_t size_of_element, void * state)
{
if (((__failing_allocator_state *)state)->is_failing) {
return nullptr;
}
return rcutils_get_default_allocator().zero_allocate(
number_of_elements, size_of_element, rcutils_get_default_allocator().state);
}

static inline rcutils_allocator_t
get_failing_allocator(void)
{
static __failing_allocator_state state;
state.is_failing = true;
auto failing_allocator = rcutils_get_default_allocator();
failing_allocator.allocate = failing_malloc;
failing_allocator.deallocate = failing_free;
failing_allocator.reallocate = failing_realloc;
failing_allocator.zero_allocate = failing_calloc;
failing_allocator.state = &state;
return failing_allocator;
}

static inline void
set_failing_allocator_is_failing(rcutils_allocator_t & failing_allocator, bool state)
{
((__failing_allocator_state *)failing_allocator.state)->is_failing = state;
}

#ifdef __cplusplus
}
#endif

#endif // ALLOCATOR_TESTING_UTILS_H_
127 changes: 127 additions & 0 deletions rcl_logging_spdlog/test/test_logging.cpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,127 @@
// Copyright 2020 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 <gtest/gtest.h>

#include <string>
#include <sstream>
#include <vector>

#include "./allocator_testing_utils.h"
#include "rcl_logging_spdlog/logging_interface.h"
#include "rcutils/allocator.h"
#include "rcutils/error_handling.h"
#include "rcutils/get_env.h"
#include "rcutils/logging.h"
#include "rcutils/process.h"

#ifdef _WIN32
#define popen _popen
#define cmd_cat "type"
#else
#define cmd_cat "cat"
#endif

/// This function will read the file generated by rcl_logging_spdlog and check
/// that the log messages are there.
void check_output(const std::vector<std::string> & desired_output_lines)
{
// First get the home directory.
const char * homedir = rcutils_get_home_dir();
if (homedir == nullptr) {
// We couldn't get the home directory; it is not really going to be
// possible to do logging properly, so get out of here without setting
// up logging.
FAIL();
}

rcutils_allocator_t allocator = rcutils_get_default_allocator();
// Get the program name.
char * basec = rcutils_get_executable_name(allocator);
if (basec == nullptr) {
// We couldn't get the program name, so get out of here without setting up
// logging.
FAIL();
}
char cmd_buffer[4096] = {0};

int print_ret = rcutils_snprintf(
cmd_buffer, sizeof(cmd_buffer),
"%s %s/.ros/log/%s_%i_*", cmd_cat, homedir,
basec, rcutils_get_pid());

if (print_ret < 0) {
FAIL();
}

FILE * fp;
char line[1035];

/* Open the command for reading. */
fp = popen(cmd_buffer, "r");
if (fp == NULL) {
FAIL();
}

/* Read the output a line at a time - output it. */
unsigned int desired_output_line = 0;
while (fgets(line, sizeof(line), fp) != NULL) {
if (desired_output_line > desired_output_lines.size()) {
FAIL();
}
EXPECT_STREQ(desired_output_lines[desired_output_line].c_str(), line);
desired_output_line++;
}
}

//////////////////////////////////////////////////
TEST(ConsoleTest, test_logging_spdlog)
{
rcutils_allocator_t allocator = rcutils_get_default_allocator();
rcutils_allocator_t failing_allocator = get_failing_allocator();

std::vector<std::string> desired_output_lines;

rcl_logging_ret_t ret = rcl_logging_external_initialize("", failing_allocator);
EXPECT_EQ(ret, 2);
rcutils_reset_error();

ret = rcl_logging_external_initialize("badfile\0", failing_allocator);
EXPECT_EQ(ret, 2);
rcutils_reset_error();

ret = rcl_logging_external_initialize("\0", allocator);
EXPECT_EQ(ret, 0);
rcutils_reset_error();

ret = rcl_logging_external_set_logger_level("", RCUTILS_LOG_SEVERITY_DEBUG);
EXPECT_EQ(ret, 0);

rcl_logging_external_log(RCUTILS_LOG_SEVERITY_WARN, "", "message_debug");
desired_output_lines.push_back("message_debug\n");

ret = rcl_logging_external_set_logger_level("", RCUTILS_LOG_SEVERITY_ERROR);
EXPECT_EQ(ret, 0);
rcl_logging_external_log(RCUTILS_LOG_SEVERITY_WARN, "", "message_warn");

ret = rcl_logging_external_set_logger_level("", RCUTILS_LOG_SEVERITY_ERROR);
EXPECT_EQ(ret, 0);
rcl_logging_external_log(RCUTILS_LOG_SEVERITY_ERROR, "", "message_error");
desired_output_lines.push_back("message_error\n");

ret = rcl_logging_external_shutdown();
EXPECT_EQ(ret, 0);

check_output(desired_output_lines);
}