Skip to content
Closed
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
24 changes: 12 additions & 12 deletions rclcpp/test/test_logging.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -52,15 +52,15 @@ class TestLoggingMacros : public ::testing::Test
auto rcutils_logging_console_output_handler = [](
const rcutils_log_location_t * location,
int level, const char * name, rcutils_time_point_value_t timestamp,
const char * format, va_list * args) -> void
const char * log_str) -> void
{
g_log_calls += 1;
g_last_log_event.location = location;
g_last_log_event.level = level;
g_last_log_event.name = name ? name : "";
g_last_log_event.timestamp = timestamp;
char buffer[1024];
vsnprintf(buffer, sizeof(buffer), format, *args);
strncpy(buffer, log_str, sizeof(buffer));
g_last_log_event.message = buffer;
};

Expand Down Expand Up @@ -89,27 +89,27 @@ TEST_F(TestLoggingMacros, test_logging_named) {
}
EXPECT_EQ(RCUTILS_LOG_SEVERITY_DEBUG, g_last_log_event.level);
EXPECT_EQ("name", g_last_log_event.name);
EXPECT_EQ("message 3", g_last_log_event.message);
EXPECT_EQ("[DEBUG] [name]: message 3", g_last_log_event.message);
Copy link
Member

Choose a reason for hiding this comment

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

Changes like this will probably go away after changes I suggested in rcutils.

}

TEST_F(TestLoggingMacros, test_logging_string) {
for (std::string i : {"one", "two", "three"}) {
RCLCPP_DEBUG(g_logger, "message " + i);
}
EXPECT_EQ(3u, g_log_calls);
EXPECT_EQ("message three", g_last_log_event.message);
EXPECT_EQ("[DEBUG] [name]: message three", g_last_log_event.message);

RCLCPP_DEBUG(g_logger, "message " "four");
EXPECT_EQ("message four", g_last_log_event.message);
EXPECT_EQ("[DEBUG] [name]: message four", g_last_log_event.message);

RCLCPP_DEBUG(g_logger, std::string("message " "five"));
EXPECT_EQ("message five", g_last_log_event.message);
EXPECT_EQ("[DEBUG] [name]: message five", g_last_log_event.message);

RCLCPP_DEBUG(g_logger, std::string("message %s"), "six");
EXPECT_EQ("message six", g_last_log_event.message);
EXPECT_EQ("[DEBUG] [name]: message six", g_last_log_event.message);

RCLCPP_DEBUG(g_logger, "message seven");
EXPECT_EQ("message seven", g_last_log_event.message);
EXPECT_EQ("[DEBUG] [name]: message seven", g_last_log_event.message);
}

TEST_F(TestLoggingMacros, test_logging_once) {
Expand All @@ -119,7 +119,7 @@ TEST_F(TestLoggingMacros, test_logging_once) {
EXPECT_EQ(1u, g_log_calls);
EXPECT_EQ(RCUTILS_LOG_SEVERITY_INFO, g_last_log_event.level);
EXPECT_EQ("name", g_last_log_event.name);
EXPECT_EQ("message 1", g_last_log_event.message);
EXPECT_EQ("[INFO] [name]: message 1", g_last_log_event.message);

// Check that another instance has a context that's independent to the call above's
g_log_calls = 0;
Expand All @@ -129,15 +129,15 @@ TEST_F(TestLoggingMacros, test_logging_once) {
EXPECT_EQ(1u, g_log_calls);
EXPECT_EQ(RCUTILS_LOG_SEVERITY_INFO, g_last_log_event.level);
EXPECT_EQ("name", g_last_log_event.name);
EXPECT_EQ("second message 1", g_last_log_event.message);
EXPECT_EQ("[INFO] [name]: second message 1", g_last_log_event.message);
}

TEST_F(TestLoggingMacros, test_logging_expression) {
for (int i : {1, 2, 3, 4, 5, 6}) {
RCLCPP_INFO_EXPRESSION(g_logger, i % 3, "message %d", i);
}
EXPECT_EQ(4u, g_log_calls);
EXPECT_EQ("message 5", g_last_log_event.message);
EXPECT_EQ("[INFO] [name]: message 5", g_last_log_event.message);
}

int g_counter = 0;
Expand All @@ -153,7 +153,7 @@ TEST_F(TestLoggingMacros, test_logging_function) {
RCLCPP_INFO_FUNCTION(g_logger, &mod3, "message %d", i);
}
EXPECT_EQ(4u, g_log_calls);
EXPECT_EQ("message 5", g_last_log_event.message);
EXPECT_EQ("[INFO] [name]: message 5", g_last_log_event.message);
}

TEST_F(TestLoggingMacros, test_logging_skipfirst) {
Expand Down