Skip to content

Commit

Permalink
Allow passing logger by const ref (#820)
Browse files Browse the repository at this point in the history
Signed-off-by: Karsten Knese <karsten@openrobotics.org>
  • Loading branch information
Karsten1987 authored Aug 9, 2019
1 parent 78ab373 commit 25f1969
Show file tree
Hide file tree
Showing 2 changed files with 26 additions and 1 deletion.
2 changes: 1 addition & 1 deletion rclcpp/resource/logging.hpp.em
Original file line number Diff line number Diff line change
Expand Up @@ -95,7 +95,7 @@ def is_supported_feature_combination(feature_combination):
#define RCLCPP_@(severity)@(suffix)(logger, @(''.join([p + ', ' for p in get_macro_parameters(feature_combination).keys()]))...) \
do { \
static_assert( \
::std::is_same<typename std::remove_reference<typename std::remove_cv<decltype(logger)>::type>::type, \
::std::is_same<typename std::remove_cv<typename std::remove_reference<decltype(logger)>::type>::type, \
typename ::rclcpp::Logger>::value, \
"First argument to logging macros must be an rclcpp::Logger"); \
RCUTILS_LOG_@(severity)@(suffix)_NAMED( \
Expand Down
25 changes: 25 additions & 0 deletions rclcpp/test/test_logging.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -162,3 +162,28 @@ TEST_F(TestLoggingMacros, test_logging_skipfirst) {
EXPECT_EQ(i - 1, g_log_calls);
}
}

bool log_function(rclcpp::Logger logger)
{
RCLCPP_INFO(logger, "successful log");
return true;
}

bool log_function_const(const rclcpp::Logger logger)
{
RCLCPP_INFO(logger, "successful log");
return true;
}

bool log_function_const_ref(const rclcpp::Logger & logger)
{
RCLCPP_INFO(logger, "successful log");
return true;
}

TEST_F(TestLoggingMacros, test_log_from_node) {
auto logger = rclcpp::get_logger("test_logging_logger");
EXPECT_TRUE(log_function(logger));
EXPECT_TRUE(log_function_const(logger));
EXPECT_TRUE(log_function_const_ref(logger));
}

0 comments on commit 25f1969

Please sign in to comment.