Providing logging macro signature that accepts std::string (#573)

* Providing logging macro signature that accepts std::string

* - RCLCPP_ prefix to macros Add
- New tests added

* - Added doc to the functions and macros
- Functions declared as RCLCPP_PUBLIC

* - Small typo in doc corrected

* Fixed error when compiling with clang

* touch up docs
This commit is contained in:
Francisco Martín Rico 2018-10-26 00:49:38 +02:00 committed by William Woodall
parent 144c24c8fd
commit b600c18121
4 changed files with 60 additions and 2 deletions

View file

@ -210,6 +210,26 @@ sub_will_underflow(const T x, const T y)
return (y > 0) && (x < (std::numeric_limits<T>::min() + y)); return (y > 0) && (x < (std::numeric_limits<T>::min() + y));
} }
/// Return the given 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 given string
*/
RCLCPP_PUBLIC
const char *
get_c_string(const char * string_in);
/// Return the C string from the given std::string.
/**
* \param[in] string_in is a std::string
* \return the C string from the std::string
*/
RCLCPP_PUBLIC
const char *
get_c_string(const std::string & string_in);
} // namespace rclcpp } // namespace rclcpp
#endif // RCLCPP__UTILITIES_HPP_ #endif // RCLCPP__UTILITIES_HPP_

View file

@ -21,6 +21,7 @@
#include "rclcpp/logger.hpp" #include "rclcpp/logger.hpp"
#include "rcutils/logging_macros.h" #include "rcutils/logging_macros.h"
#include "rclcpp/utilities.hpp"
// These are used for compiling out logging macros lower than a minimum severity. // These are used for compiling out logging macros lower than a minimum severity.
#define RCLCPP_LOG_MIN_SEVERITY_DEBUG 0 #define RCLCPP_LOG_MIN_SEVERITY_DEBUG 0
@ -30,6 +31,9 @@
#define RCLCPP_LOG_MIN_SEVERITY_FATAL 4 #define RCLCPP_LOG_MIN_SEVERITY_FATAL 4
#define RCLCPP_LOG_MIN_SEVERITY_NONE 5 #define RCLCPP_LOG_MIN_SEVERITY_NONE 5
#define RCLCPP_FIRST_ARG(N, ...) N
#define RCLCPP_ALL_BUT_FIRST_ARGS(N, ...) __VA_ARGS__
/** /**
* \def RCLCPP_LOG_MIN_SEVERITY * \def RCLCPP_LOG_MIN_SEVERITY
* Define RCLCPP_LOG_MIN_SEVERITY=RCLCPP_LOG_MIN_SEVERITY_[DEBUG|INFO|WARN|ERROR|FATAL] * Define RCLCPP_LOG_MIN_SEVERITY=RCLCPP_LOG_MIN_SEVERITY_[DEBUG|INFO|WARN|ERROR|FATAL]
@ -82,7 +86,8 @@ def is_supported_feature_combination(feature_combination):
@[ for param_name, doc_line in feature_combinations[feature_combination].params.items()]@ @[ for param_name, doc_line in feature_combinations[feature_combination].params.items()]@
* \param @(param_name) @(doc_line) * \param @(param_name) @(doc_line)
@[ end for]@ @[ 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()]))...) \ #define RCLCPP_@(severity)@(suffix)(logger, @(''.join([p + ', ' for p in get_macro_parameters(feature_combination).keys()]))...) \
static_assert( \ static_assert( \
@ -94,7 +99,8 @@ def is_supported_feature_combination(feature_combination):
@(''.join([' ' + p + ', \\\n' for p in params]))@ @(''.join([' ' + p + ', \\\n' for p in params]))@
@[ end if]@ @[ end if]@
logger.get_name(), \ logger.get_name(), \
__VA_ARGS__) rclcpp::get_c_string(RCLCPP_FIRST_ARG(__VA_ARGS__, "")), \
RCLCPP_ALL_BUT_FIRST_ARGS(__VA_ARGS__,""))
@[ end for]@ @[ end for]@
#endif #endif

View file

@ -353,3 +353,15 @@ rclcpp::sleep_for(const std::chrono::nanoseconds & nanoseconds)
// Return true if the timeout elapsed successfully, otherwise false. // Return true if the timeout elapsed successfully, otherwise false.
return !g_is_interrupted; 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();
}

View file

@ -92,6 +92,26 @@ TEST_F(TestLoggingMacros, test_logging_named) {
EXPECT_EQ("message 3", g_last_log_event.message); 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);
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);
RCLCPP_DEBUG(g_logger, "message seven");
EXPECT_EQ("message seven", g_last_log_event.message);
}
TEST_F(TestLoggingMacros, test_logging_once) { TEST_F(TestLoggingMacros, test_logging_once) {
for (int i : {1, 2, 3}) { for (int i : {1, 2, 3}) {
RCLCPP_INFO_ONCE(g_logger, "message %d", i); RCLCPP_INFO_ONCE(g_logger, "message %d", i);