diff --git a/rclcpp/resource/logging.hpp.em b/rclcpp/resource/logging.hpp.em index 564113487a..737758a551 100644 --- a/rclcpp/resource/logging.hpp.em +++ b/rclcpp/resource/logging.hpp.em @@ -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::type>::type, \ + ::std::is_same::type>::type, \ typename ::rclcpp::Logger>::value, \ "First argument to logging macros must be an rclcpp::Logger"); \ RCUTILS_LOG_@(severity)@(suffix)_NAMED( \ diff --git a/rclcpp/test/test_logging.cpp b/rclcpp/test/test_logging.cpp index 58f3635392..992ef01209 100644 --- a/rclcpp/test/test_logging.cpp +++ b/rclcpp/test/test_logging.cpp @@ -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)); +}