Skip to content

Commit

Permalink
logging, remove_const before comparison (#680)
Browse files Browse the repository at this point in the history
* logging, remove_const before comparison

This change removes the const value from the logger before
comparing with std::is_same.

Signed-off-by: Víctor Mayoral Vilches <v.mayoralv@gmail.com>

* logging template, replace remove_const by remove_cv

Signed-off-by: Víctor Mayoral Vilches <v.mayoralv@gmail.com>

* Append typename

Located after compiling rclcpp_action from source

Signed-off-by: Víctor Mayoral Vilches <v.mayoralv@gmail.com>
  • Loading branch information
Víctor Mayoral Vilches authored and Karsten1987 committed Apr 15, 2019
1 parent 2476950 commit fcfe94e
Showing 1 changed file with 1 addition 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<decltype(logger)>::type, \
::std::is_same<typename std::remove_reference<typename std::remove_cv<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

0 comments on commit fcfe94e

Please sign in to comment.