From 9a99a84de60af2d878ee6504342805b59bb3c403 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Francisco=20Mart=C3=ADn=20Rico?= Date: Sun, 21 Oct 2018 20:34:36 +0200 Subject: [PATCH 1/6] Providing logging macro signature that accepts std::string --- rclcpp/include/rclcpp/utilities.hpp | 6 ++++++ rclcpp/resource/logging.hpp.em | 6 +++++- rclcpp/src/rclcpp/utilities.cpp | 12 ++++++++++++ rclcpp/test/test_logging.cpp | 8 ++++++++ 4 files changed, 31 insertions(+), 1 deletion(-) diff --git a/rclcpp/include/rclcpp/utilities.hpp b/rclcpp/include/rclcpp/utilities.hpp index 1118417c2e..456596301c 100644 --- a/rclcpp/include/rclcpp/utilities.hpp +++ b/rclcpp/include/rclcpp/utilities.hpp @@ -210,6 +210,12 @@ sub_will_underflow(const T x, const T y) return (y > 0) && (x < (std::numeric_limits::min() + y)); } +const char * +get_c_string(const char * string_in); + +const char * +get_c_string(const std::string & string_in); + } // namespace rclcpp #endif // RCLCPP__UTILITIES_HPP_ diff --git a/rclcpp/resource/logging.hpp.em b/rclcpp/resource/logging.hpp.em index 24753f8116..edb36a1158 100644 --- a/rclcpp/resource/logging.hpp.em +++ b/rclcpp/resource/logging.hpp.em @@ -21,6 +21,7 @@ #include "rclcpp/logger.hpp" #include "rcutils/logging_macros.h" +#include "rclcpp/utilities.hpp" // These are used for compiling out logging macros lower than a minimum severity. #define RCLCPP_LOG_MIN_SEVERITY_DEBUG 0 @@ -30,6 +31,9 @@ #define RCLCPP_LOG_MIN_SEVERITY_FATAL 4 #define RCLCPP_LOG_MIN_SEVERITY_NONE 5 +#define FIRST_ARG(N, ...) N +#define ALL_BUT_FIRST_ARGS(N, ...) , ##__VA_ARGS__ + /** * \def RCLCPP_LOG_MIN_SEVERITY * Define RCLCPP_LOG_MIN_SEVERITY=RCLCPP_LOG_MIN_SEVERITY_[DEBUG|INFO|WARN|ERROR|FATAL] @@ -94,7 +98,7 @@ def is_supported_feature_combination(feature_combination): @(''.join([' ' + p + ', \\\n' for p in params]))@ @[ end if]@ logger.get_name(), \ - __VA_ARGS__) + rclcpp::get_c_string(FIRST_ARG(__VA_ARGS__, "")) ALL_BUT_FIRST_ARGS(__VA_ARGS__,"")) @[ end for]@ #endif diff --git a/rclcpp/src/rclcpp/utilities.cpp b/rclcpp/src/rclcpp/utilities.cpp index af417fc09c..b1b0041431 100644 --- a/rclcpp/src/rclcpp/utilities.cpp +++ b/rclcpp/src/rclcpp/utilities.cpp @@ -353,3 +353,15 @@ rclcpp::sleep_for(const std::chrono::nanoseconds & nanoseconds) // Return true if the timeout elapsed successfully, otherwise false. return !g_is_interrupted; } + +const char * +rclcpp::get_c_string(const char * string_in) +{ + return string_in; +} + +const char * +rclcpp::get_c_string(const std::string & string_in) +{ + return string_in.c_str(); +} diff --git a/rclcpp/test/test_logging.cpp b/rclcpp/test/test_logging.cpp index 3de6f5c284..b32539cfa1 100644 --- a/rclcpp/test/test_logging.cpp +++ b/rclcpp/test/test_logging.cpp @@ -92,6 +92,14 @@ TEST_F(TestLoggingMacros, test_logging_named) { EXPECT_EQ("message 3", g_last_log_event.message); } +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); +} + TEST_F(TestLoggingMacros, test_logging_once) { for (int i : {1, 2, 3}) { RCLCPP_INFO_ONCE(g_logger, "message %d", i); From 953db7a3e72c68a2a484700342cb43aa6624044e Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Francisco=20Mart=C3=ADn=20Rico?= Date: Wed, 24 Oct 2018 00:49:24 +0200 Subject: [PATCH 2/6] - RCLCPP_ prefix to macros Add - New tests added --- rclcpp/resource/logging.hpp.em | 7 ++++--- rclcpp/test/test_logging.cpp | 9 +++++++++ 2 files changed, 13 insertions(+), 3 deletions(-) diff --git a/rclcpp/resource/logging.hpp.em b/rclcpp/resource/logging.hpp.em index edb36a1158..b5890840b6 100644 --- a/rclcpp/resource/logging.hpp.em +++ b/rclcpp/resource/logging.hpp.em @@ -31,8 +31,8 @@ #define RCLCPP_LOG_MIN_SEVERITY_FATAL 4 #define RCLCPP_LOG_MIN_SEVERITY_NONE 5 -#define FIRST_ARG(N, ...) N -#define ALL_BUT_FIRST_ARGS(N, ...) , ##__VA_ARGS__ +#define RCLCPP_FIRST_ARG(N, ...) N +#define RCLCPP_ALL_BUT_FIRST_ARGS(N, ...) , ##__VA_ARGS__ /** * \def RCLCPP_LOG_MIN_SEVERITY @@ -98,7 +98,8 @@ def is_supported_feature_combination(feature_combination): @(''.join([' ' + p + ', \\\n' for p in params]))@ @[ end if]@ logger.get_name(), \ - rclcpp::get_c_string(FIRST_ARG(__VA_ARGS__, "")) ALL_BUT_FIRST_ARGS(__VA_ARGS__,"")) + rclcpp::get_c_string(RCLCPP_FIRST_ARG(__VA_ARGS__, "")) \ + RCLCPP_ALL_BUT_FIRST_ARGS(__VA_ARGS__,"")) @[ end for]@ #endif diff --git a/rclcpp/test/test_logging.cpp b/rclcpp/test/test_logging.cpp index b32539cfa1..6216130fe5 100644 --- a/rclcpp/test/test_logging.cpp +++ b/rclcpp/test/test_logging.cpp @@ -98,6 +98,15 @@ TEST_F(TestLoggingMacros, test_logging_string) { } EXPECT_EQ(3u, g_log_calls); EXPECT_EQ("message three", g_last_log_event.message); + + RCLCPP_DEBUG(g_logger, "message " "four"); + EXPECT_EQ("message four", g_last_log_event.message); + + RCLCPP_DEBUG(g_logger, std::string("message " "five")); + EXPECT_EQ("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); } TEST_F(TestLoggingMacros, test_logging_once) { From 6a0a6c7d383bc74f8a02066aad3bffaad1c04a31 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Francisco=20Mart=C3=ADn=20Rico?= Date: Wed, 24 Oct 2018 06:45:21 +0200 Subject: [PATCH 3/6] - Added doc to the functions and macros - Functions declared as RCLCPP_PUBLIC --- rclcpp/include/rclcpp/utilities.hpp | 15 +++++++++++++++ rclcpp/resource/logging.hpp.em | 3 ++- 2 files changed, 17 insertions(+), 1 deletion(-) diff --git a/rclcpp/include/rclcpp/utilities.hpp b/rclcpp/include/rclcpp/utilities.hpp index 456596301c..af46caeafa 100644 --- a/rclcpp/include/rclcpp/utilities.hpp +++ b/rclcpp/include/rclcpp/utilities.hpp @@ -210,9 +210,24 @@ sub_will_underflow(const T x, const T y) return (y > 0) && (x < (std::numeric_limits::min() + y)); } +/// Return the same string. +/** + * This function is overloaded to transform any string to C-style string + * + * \param[in] string_in is the string to be returned + * \return The same string. + */ +RCLCPP_PUBLIC const char * get_c_string(const char * string_in); +/// Return the string, converted to C string +/** + * + * \param[in] string_in is a std::string + * \return The string tranformed to C string. + */ +RCLCPP_PUBLIC const char * get_c_string(const std::string & string_in); diff --git a/rclcpp/resource/logging.hpp.em b/rclcpp/resource/logging.hpp.em index b5890840b6..3e89cb740f 100644 --- a/rclcpp/resource/logging.hpp.em +++ b/rclcpp/resource/logging.hpp.em @@ -86,7 +86,8 @@ def is_supported_feature_combination(feature_combination): @[ for param_name, doc_line in feature_combinations[feature_combination].params.items()]@ * \param @(param_name) @(doc_line) @[ end for]@ - * \param ... The format string, followed by the variable arguments for the format string + * \param ... The format string, followed by the variable arguments for the format string. + * It also accepts a single argument of type std::string. */ #define RCLCPP_@(severity)@(suffix)(logger, @(''.join([p + ', ' for p in get_macro_parameters(feature_combination).keys()]))...) \ static_assert( \ From 2339df583fb3f31c04b30d61b07e7f345904ca88 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Francisco=20Mart=C3=ADn=20Rico?= Date: Wed, 24 Oct 2018 07:40:01 +0200 Subject: [PATCH 4/6] - Small typo in doc corrected --- rclcpp/include/rclcpp/utilities.hpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/rclcpp/include/rclcpp/utilities.hpp b/rclcpp/include/rclcpp/utilities.hpp index af46caeafa..b7a093a5b6 100644 --- a/rclcpp/include/rclcpp/utilities.hpp +++ b/rclcpp/include/rclcpp/utilities.hpp @@ -225,7 +225,7 @@ get_c_string(const char * string_in); /** * * \param[in] string_in is a std::string - * \return The string tranformed to C string. + * \return The string transformed to C string. */ RCLCPP_PUBLIC const char * From 6683c476131598dc95140dc988d07489ff0ccce8 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Francisco=20Mart=C3=ADn=20Rico?= Date: Thu, 25 Oct 2018 21:33:13 +0200 Subject: [PATCH 5/6] Fixed error when compiling with clang --- rclcpp/resource/logging.hpp.em | 4 ++-- rclcpp/test/test_logging.cpp | 3 +++ 2 files changed, 5 insertions(+), 2 deletions(-) diff --git a/rclcpp/resource/logging.hpp.em b/rclcpp/resource/logging.hpp.em index 3e89cb740f..b6a869fa34 100644 --- a/rclcpp/resource/logging.hpp.em +++ b/rclcpp/resource/logging.hpp.em @@ -32,7 +32,7 @@ #define RCLCPP_LOG_MIN_SEVERITY_NONE 5 #define RCLCPP_FIRST_ARG(N, ...) N -#define RCLCPP_ALL_BUT_FIRST_ARGS(N, ...) , ##__VA_ARGS__ +#define RCLCPP_ALL_BUT_FIRST_ARGS(N, ...) __VA_ARGS__ /** * \def RCLCPP_LOG_MIN_SEVERITY @@ -99,7 +99,7 @@ def is_supported_feature_combination(feature_combination): @(''.join([' ' + p + ', \\\n' for p in params]))@ @[ end if]@ logger.get_name(), \ - rclcpp::get_c_string(RCLCPP_FIRST_ARG(__VA_ARGS__, "")) \ + rclcpp::get_c_string(RCLCPP_FIRST_ARG(__VA_ARGS__, "")), \ RCLCPP_ALL_BUT_FIRST_ARGS(__VA_ARGS__,"")) @[ end for]@ diff --git a/rclcpp/test/test_logging.cpp b/rclcpp/test/test_logging.cpp index 6216130fe5..58f3635392 100644 --- a/rclcpp/test/test_logging.cpp +++ b/rclcpp/test/test_logging.cpp @@ -107,6 +107,9 @@ TEST_F(TestLoggingMacros, test_logging_string) { RCLCPP_DEBUG(g_logger, std::string("message %s"), "six"); EXPECT_EQ("message six", g_last_log_event.message); + + RCLCPP_DEBUG(g_logger, "message seven"); + EXPECT_EQ("message seven", g_last_log_event.message); } TEST_F(TestLoggingMacros, test_logging_once) { From 1fb433f00d258a2b107bebeba53f30370ab25510 Mon Sep 17 00:00:00 2001 From: William Woodall Date: Thu, 25 Oct 2018 15:48:47 -0700 Subject: [PATCH 6/6] touch up docs --- rclcpp/include/rclcpp/utilities.hpp | 11 +++++------ 1 file changed, 5 insertions(+), 6 deletions(-) diff --git a/rclcpp/include/rclcpp/utilities.hpp b/rclcpp/include/rclcpp/utilities.hpp index b7a093a5b6..8a66fc61b7 100644 --- a/rclcpp/include/rclcpp/utilities.hpp +++ b/rclcpp/include/rclcpp/utilities.hpp @@ -210,22 +210,21 @@ sub_will_underflow(const T x, const T y) return (y > 0) && (x < (std::numeric_limits::min() + y)); } -/// Return the same string. +/// Return the given string. /** - * This function is overloaded to transform any string to C-style string + * This function is overloaded to transform any string to C-style string. * * \param[in] string_in is the string to be returned - * \return The same string. + * \return the given string */ RCLCPP_PUBLIC const char * get_c_string(const char * string_in); -/// Return the string, converted to C string +/// Return the C string from the given std::string. /** - * * \param[in] string_in is a std::string - * \return The string transformed to C string. + * \return the C string from the std::string */ RCLCPP_PUBLIC const char *