Skip to content

Commit

Permalink
add support for STREAM logging macros (#926)
Browse files Browse the repository at this point in the history
* refactor template logic around feature combinations

Signed-off-by: Dirk Thomas <dirk-thomas@users.noreply.github.com>

* add support for STREAM logging macros

Signed-off-by: Dirk Thomas <dirk-thomas@users.noreply.github.com>
  • Loading branch information
dirk-thomas authored and mjcarroll committed Nov 18, 2019
1 parent b92db52 commit 6963c2d
Show file tree
Hide file tree
Showing 2 changed files with 59 additions and 16 deletions.
61 changes: 45 additions & 16 deletions rclcpp/resource/logging.hpp.em
Original file line number Diff line number Diff line change
Expand Up @@ -46,8 +46,8 @@

@{
from collections import OrderedDict
from copy import deepcopy
from rcutils.logging import feature_combinations
from rcutils.logging import get_macro_parameters
from rcutils.logging import get_suffix_from_features
from rcutils.logging import severities
from rcutils.logging import throttle_args
Expand All @@ -58,49 +58,70 @@ del throttle_params['get_time_point_value']
throttle_params['clock'] = 'rclcpp::Clock that will be used to get the time point.'
throttle_params.move_to_end('clock', last=False)

excluded_features = ['named']
def is_supported_feature_combination(feature_combination):
is_excluded = any([ef in feature_combination for ef in excluded_features])
return not is_excluded
rclcpp_feature_combinations = OrderedDict()
for combinations, feature in feature_combinations.items():
# skip feature combinations using 'named'
if 'named' in combinations:
continue
rclcpp_feature_combinations[combinations] = feature
# add a stream variant for each available feature combination
stream_arg = 'stream_arg'
for combinations, feature in list(rclcpp_feature_combinations.items()):
combinations = ('stream', ) + combinations
feature = deepcopy(feature)
feature.params[stream_arg] = 'The argument << into a stringstream'
rclcpp_feature_combinations[combinations] = feature

def get_rclcpp_suffix_from_features(features):
suffix = get_suffix_from_features(features)
if 'stream' in features:
suffix = '_STREAM' + suffix
return suffix
}@
@[for severity in severities]@
/** @@name Logging macros for severity @(severity).
*/
///@@{
#if (RCLCPP_LOG_MIN_SEVERITY > RCLCPP_LOG_MIN_SEVERITY_@(severity))
// empty logging macros for severity @(severity) when being disabled at compile time
@[ for feature_combination in [fc for fc in feature_combinations if is_supported_feature_combination(fc)]]@
@{suffix = get_suffix_from_features(feature_combination)}@
@[ for feature_combination in rclcpp_feature_combinations.keys()]@
@{suffix = get_rclcpp_suffix_from_features(feature_combination)}@
/// Empty logging macro due to the preprocessor definition of RCLCPP_LOG_MIN_SEVERITY.
#define RCLCPP_@(severity)@(suffix)(...)
@[ end for]@

#else
@[ for feature_combination in [fc for fc in feature_combinations if is_supported_feature_combination(fc)]]@
@{suffix = get_suffix_from_features(feature_combination)}@
@[ for feature_combination in rclcpp_feature_combinations.keys()]@
@{suffix = get_rclcpp_suffix_from_features(feature_combination)}@
// The RCLCPP_@(severity)@(suffix) macro is surrounded by do { .. } while (0)
// to implement the standard C macro idiom to make the macro safe in all
// contexts; see http://c-faq.com/cpp/multistmt.html for more information.
/**
* \def RCLCPP_@(severity)@(suffix)
* Log a message with severity @(severity)@
@[ if feature_combinations[feature_combination].doc_lines]@
@[ if rclcpp_feature_combinations[feature_combination].doc_lines]@
with the following conditions:
@[ else]@
.
@[ end if]@
@[ for doc_line in feature_combinations[feature_combination].doc_lines]@
@[ for doc_line in rclcpp_feature_combinations[feature_combination].doc_lines]@
* @(doc_line)
@[ end for]@
* \param logger The `rclcpp::Logger` to use
@[ for param_name, doc_line in feature_combinations[feature_combination].params.items()]@
@[ for param_name, doc_line in rclcpp_feature_combinations[feature_combination].params.items()]@
* \param @(param_name) @(doc_line)
@[ end for]@
@[ if 'stream' not in feature_combination]@
* \param ... The format string, followed by the variable arguments for the format string.
* It also accepts a single argument of type std::string.
@[ end if]@
*/
@{params = get_macro_parameters(feature_combination).keys()}@
#define RCLCPP_@(severity)@(suffix)(logger, @(''.join([p + ', ' for p in params]))...) \
@{params = rclcpp_feature_combinations[feature_combination].params.keys()}@
#define RCLCPP_@(severity)@(suffix)(logger@(''.join([', ' + p for p in params]))@
@[ if 'stream' not in feature_combination]@
, ...@
@[ end if]@
) \
do { \
static_assert( \
::std::is_same<typename std::remove_cv<typename std::remove_reference<decltype(logger)>::type>::type, \
Expand All @@ -118,14 +139,22 @@ def is_supported_feature_combination(feature_combination):
return RCUTILS_RET_OK; \
}; \
@[ end if] \
RCUTILS_LOG_@(severity)@(suffix)_NAMED( \
@[ if 'stream' in feature_combination]@
std::stringstream ss; \
ss << @(stream_arg); \
@[ end if]@
RCUTILS_LOG_@(severity)@(get_suffix_from_features(feature_combination))_NAMED( \
@{params = ['get_time_point' if p == 'clock' and 'throttle' in feature_combination else p for p in params]}@
@[ if params]@
@(''.join([' ' + p + ', \\\n' for p in params]))@
@(''.join([' ' + p + ', \\\n' for p in params if p != stream_arg]))@
@[ end if]@
logger.get_name(), \
@[ if 'stream' not in feature_combination]@
rclcpp::get_c_string(RCLCPP_FIRST_ARG(__VA_ARGS__, "")), \
RCLCPP_ALL_BUT_FIRST_ARGS(__VA_ARGS__,"")); \
@[ else]@
"%s", rclcpp::get_c_string(ss.str())); \
@[ end if]@
} while (0)

@[ end for]@
Expand Down
14 changes: 14 additions & 0 deletions rclcpp/test/test_logging.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -113,6 +113,20 @@ TEST_F(TestLoggingMacros, test_logging_string) {
EXPECT_EQ("message seven", g_last_log_event.message);
}

TEST_F(TestLoggingMacros, test_logging_stream) {
for (std::string i : {"one", "two", "three"}) {
RCLCPP_DEBUG_STREAM(g_logger, "message " << i);
}
EXPECT_EQ(3u, g_log_calls);
EXPECT_EQ("message three", g_last_log_event.message);

RCLCPP_DEBUG_STREAM(g_logger, 4 << "th message");
EXPECT_EQ("4th message", g_last_log_event.message);

RCLCPP_DEBUG_STREAM(g_logger, "message " << 5);
EXPECT_EQ("message 5", 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);
Expand Down

0 comments on commit 6963c2d

Please sign in to comment.