Skip to content

Commit

Permalink
Update test code with c++ style and remove unnecessary code
Browse files Browse the repository at this point in the history
Signed-off-by: Chen Lihui <[email protected]>
  • Loading branch information
Chen Lihui authored and Chen Lihui committed Jun 23, 2020
1 parent c7a1082 commit 31776b6
Show file tree
Hide file tree
Showing 2 changed files with 29 additions and 37 deletions.
2 changes: 1 addition & 1 deletion rcl/include/rcl/arguments.h
Original file line number Diff line number Diff line change
Expand Up @@ -359,7 +359,7 @@ rcl_remove_ros_arguments(
* \param[in] arguments An arguments structure that has been parsed.
* \param[out] log_level Log level settings as parsed from command line arguments.
* This structure must be finalized by the caller.
* The output is NULL if no log were parsed.
* The output is NULL if no logs were parsed.
* \return `RCL_RET_OK` if everything goes correctly, or
* \return `RCL_RET_INVALID_ARGUMENT` if any function arguments are invalid, or
* \return `RCL_RET_BAD_ALLOC` if allocating memory failed, or
Expand Down
64 changes: 28 additions & 36 deletions rcl/test/rcl/test_log_level.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -30,14 +30,6 @@

class CLASSNAME (TestLogLevelFixture, RMW_IMPLEMENTATION) : public ::testing::Test
{
public:
void SetUp()
{
}

void TearDown()
{
}
};

#define EXPECT_INVALID_RET_FOR_ARGUMENTS_LOG_LEVEL(...) \
Expand All @@ -51,7 +43,7 @@ class CLASSNAME (TestLogLevelFixture, RMW_IMPLEMENTATION) : public ::testing::Te
ASSERT_EQ(RCL_RET_INVALID_ROS_ARGS, ret); \
}

TEST_F(CLASSNAME(TestLogLevelFixture, RMW_IMPLEMENTATION), error_log_level) {
TEST(CLASSNAME(TestLogLevelFixture, RMW_IMPLEMENTATION), error_log_level) {
EXPECT_INVALID_RET_FOR_ARGUMENTS_LOG_LEVEL(
"process_name", "--ros-args", "--log-level",
"=debug");
Expand Down Expand Up @@ -95,18 +87,18 @@ TEST_F(CLASSNAME(TestLogLevelFixture, RMW_IMPLEMENTATION), error_log_level) {
}); \
}

TEST_F(CLASSNAME(TestLogLevelFixture, RMW_IMPLEMENTATION), no_log_level) {
TEST(CLASSNAME(TestLogLevelFixture, RMW_IMPLEMENTATION), no_log_level) {
rcl_log_level_t * log_level = NULL;
GET_LOG_LEVEL_FROM_ARGUMENTS(log_level, "process_name");
OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT(
{
rcl_log_level_fini(log_level);
});
EXPECT_EQ(-1, log_level->default_log_level);
EXPECT_EQ((size_t)0, log_level->num_loggers);
EXPECT_EQ(static_cast<size_t>(0), log_level->num_loggers);
}

TEST_F(CLASSNAME(TestLogLevelFixture, RMW_IMPLEMENTATION), default_log_level) {
TEST(CLASSNAME(TestLogLevelFixture, RMW_IMPLEMENTATION), default_log_level) {
rcl_log_level_t * log_level = NULL;
GET_LOG_LEVEL_FROM_ARGUMENTS(
log_level, "process_name", "--ros-args",
Expand All @@ -115,11 +107,11 @@ TEST_F(CLASSNAME(TestLogLevelFixture, RMW_IMPLEMENTATION), default_log_level) {
{
rcl_log_level_fini(log_level);
});
EXPECT_EQ((int)RCUTILS_LOG_SEVERITY_DEBUG, log_level->default_log_level);
EXPECT_EQ((size_t)0, log_level->num_loggers);
EXPECT_EQ(static_cast<int>(RCUTILS_LOG_SEVERITY_DEBUG), log_level->default_log_level);
EXPECT_EQ(static_cast<size_t>(0), log_level->num_loggers);
}

TEST_F(CLASSNAME(TestLogLevelFixture, RMW_IMPLEMENTATION), logger_log_level_debug) {
TEST(CLASSNAME(TestLogLevelFixture, RMW_IMPLEMENTATION), logger_log_level_debug) {
rcl_log_level_t * log_level = NULL;
GET_LOG_LEVEL_FROM_ARGUMENTS(
log_level, "process_name", "--ros-args",
Expand All @@ -129,12 +121,12 @@ TEST_F(CLASSNAME(TestLogLevelFixture, RMW_IMPLEMENTATION), logger_log_level_debu
rcl_log_level_fini(log_level);
});
EXPECT_EQ(-1, log_level->default_log_level);
EXPECT_EQ((size_t)1, log_level->num_loggers);
EXPECT_EQ(static_cast<size_t>(1), log_level->num_loggers);
EXPECT_STREQ("rcl", log_level->logger_settings[0].name);
EXPECT_EQ((int)RCUTILS_LOG_SEVERITY_DEBUG, log_level->logger_settings[0].level);
EXPECT_EQ(static_cast<int>(RCUTILS_LOG_SEVERITY_DEBUG), log_level->logger_settings[0].level);
}

TEST_F(CLASSNAME(TestLogLevelFixture, RMW_IMPLEMENTATION), logger_log_level_info) {
TEST(CLASSNAME(TestLogLevelFixture, RMW_IMPLEMENTATION), logger_log_level_info) {
rcl_log_level_t * log_level = NULL;
GET_LOG_LEVEL_FROM_ARGUMENTS(
log_level, "process_name", "--ros-args",
Expand All @@ -144,12 +136,12 @@ TEST_F(CLASSNAME(TestLogLevelFixture, RMW_IMPLEMENTATION), logger_log_level_info
rcl_log_level_fini(log_level);
});
EXPECT_EQ(-1, log_level->default_log_level);
EXPECT_EQ((size_t)1, log_level->num_loggers);
EXPECT_EQ(static_cast<size_t>(1), log_level->num_loggers);
EXPECT_STREQ("rcl", log_level->logger_settings[0].name);
EXPECT_EQ((int)RCUTILS_LOG_SEVERITY_INFO, log_level->logger_settings[0].level);
EXPECT_EQ(static_cast<int>(RCUTILS_LOG_SEVERITY_INFO), log_level->logger_settings[0].level);
}

TEST_F(CLASSNAME(TestLogLevelFixture, RMW_IMPLEMENTATION), default_log_level_with_logger) {
TEST(CLASSNAME(TestLogLevelFixture, RMW_IMPLEMENTATION), default_log_level_with_logger) {
rcl_log_level_t * log_level = NULL;
GET_LOG_LEVEL_FROM_ARGUMENTS(
log_level, "process_name", "--ros-args",
Expand All @@ -158,13 +150,13 @@ TEST_F(CLASSNAME(TestLogLevelFixture, RMW_IMPLEMENTATION), default_log_level_wit
{
rcl_log_level_fini(log_level);
});
EXPECT_EQ((int)RCUTILS_LOG_SEVERITY_DEBUG, log_level->default_log_level);
EXPECT_EQ((size_t)1, log_level->num_loggers);
EXPECT_EQ(static_cast<int>(RCUTILS_LOG_SEVERITY_DEBUG), log_level->default_log_level);
EXPECT_EQ(static_cast<size_t>(1), log_level->num_loggers);
EXPECT_STREQ("rcl", log_level->logger_settings[0].name);
EXPECT_EQ((int)RCUTILS_LOG_SEVERITY_DEBUG, log_level->logger_settings[0].level);
EXPECT_EQ(static_cast<int>(RCUTILS_LOG_SEVERITY_DEBUG), log_level->logger_settings[0].level);
}

TEST_F(CLASSNAME(TestLogLevelFixture, RMW_IMPLEMENTATION), logger_with_default_log_level) {
TEST(CLASSNAME(TestLogLevelFixture, RMW_IMPLEMENTATION), logger_with_default_log_level) {
rcl_log_level_t * log_level = NULL;
GET_LOG_LEVEL_FROM_ARGUMENTS(
log_level, "process_name", "--ros-args",
Expand All @@ -173,13 +165,13 @@ TEST_F(CLASSNAME(TestLogLevelFixture, RMW_IMPLEMENTATION), logger_with_default_l
{
rcl_log_level_fini(log_level);
});
EXPECT_EQ((int)RCUTILS_LOG_SEVERITY_DEBUG, log_level->default_log_level);
EXPECT_EQ((size_t)1, log_level->num_loggers);
EXPECT_EQ(static_cast<int>(RCUTILS_LOG_SEVERITY_DEBUG), log_level->default_log_level);
EXPECT_EQ(static_cast<size_t>(1), log_level->num_loggers);
EXPECT_STREQ("rcl", log_level->logger_settings[0].name);
EXPECT_EQ((int)RCUTILS_LOG_SEVERITY_DEBUG, log_level->logger_settings[0].level);
EXPECT_EQ(static_cast<int>(RCUTILS_LOG_SEVERITY_DEBUG), log_level->logger_settings[0].level);
}

TEST_F(
TEST(
CLASSNAME(TestLogLevelFixture, RMW_IMPLEMENTATION),
multiple_log_level_with_default_at_front) {
rcl_log_level_t * log_level = NULL;
Expand All @@ -190,13 +182,13 @@ TEST_F(
{
rcl_log_level_fini(log_level);
});
EXPECT_EQ((int)RCUTILS_LOG_SEVERITY_DEBUG, log_level->default_log_level);
EXPECT_EQ((size_t)1, log_level->num_loggers);
EXPECT_EQ(static_cast<int>(RCUTILS_LOG_SEVERITY_DEBUG), log_level->default_log_level);
EXPECT_EQ(static_cast<size_t>(1), log_level->num_loggers);
EXPECT_STREQ("rcl", log_level->logger_settings[0].name);
EXPECT_EQ((int)RCUTILS_LOG_SEVERITY_DEBUG, log_level->logger_settings[0].level);
EXPECT_EQ(static_cast<int>(RCUTILS_LOG_SEVERITY_DEBUG), log_level->logger_settings[0].level);
}

TEST_F(
TEST(
CLASSNAME(TestLogLevelFixture, RMW_IMPLEMENTATION),
multiple_log_level_with_default_at_back) {
rcl_log_level_t * log_level = NULL;
Expand All @@ -207,8 +199,8 @@ TEST_F(
{
rcl_log_level_fini(log_level);
});
EXPECT_EQ((int)RCUTILS_LOG_SEVERITY_DEBUG, log_level->default_log_level);
EXPECT_EQ((size_t)1, log_level->num_loggers);
EXPECT_EQ(static_cast<int>(RCUTILS_LOG_SEVERITY_DEBUG), log_level->default_log_level);
EXPECT_EQ(static_cast<size_t>(1), log_level->num_loggers);
EXPECT_STREQ("rcl", log_level->logger_settings[0].name);
EXPECT_EQ((int)RCUTILS_LOG_SEVERITY_DEBUG, log_level->logger_settings[0].level);
EXPECT_EQ(static_cast<int>(RCUTILS_LOG_SEVERITY_DEBUG), log_level->logger_settings[0].level);
}

0 comments on commit 31776b6

Please sign in to comment.