Skip to content

Commit eed1c1a

Browse files
de-vri-eswjwwood
authored andcommitted
Fix compile error due to the user-defined string literals feature (#1010) (#1015)
1 parent f71191f commit eed1c1a

File tree

1 file changed

+4
-4
lines changed

1 file changed

+4
-4
lines changed

src/rviz/default_plugin/effort_display.h

Lines changed: 4 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -36,13 +36,13 @@ namespace tf
3636
# undef TF_MESSAGEFILTER_DEBUG
3737
#endif
3838
#define TF_MESSAGEFILTER_DEBUG(fmt, ...) \
39-
ROS_DEBUG_NAMED("message_filter", "MessageFilter [target=%s]: "fmt, getTargetFramesString().c_str(), __VA_ARGS__)
39+
ROS_DEBUG_NAMED("message_filter", "MessageFilter [target=%s]: " fmt, getTargetFramesString().c_str(), __VA_ARGS__)
4040

4141
#ifdef TF_MESSAGEFILTER_WARN
4242
# undef TF_MESSAGEFILTER_WARN
4343
#endif
4444
#define TF_MESSAGEFILTER_WARN(fmt, ...) \
45-
ROS_WARN_NAMED("message_filter", "MessageFilter [target=%s]: "fmt, getTargetFramesString().c_str(), __VA_ARGS__)
45+
ROS_WARN_NAMED("message_filter", "MessageFilter [target=%s]: " fmt, getTargetFramesString().c_str(), __VA_ARGS__)
4646

4747
class MessageFilterJointState : public MessageFilter<sensor_msgs::JointState>
4848
{
@@ -127,8 +127,8 @@ namespace tf
127127
clear();
128128

129129
TF_MESSAGEFILTER_DEBUG("Successful Transforms: %llu, Failed Transforms: %llu, Discarded due to age: %llu, Transform messages received: %llu, Messages received: %llu, Total dropped: %llu",
130-
(long long unsigned int)successful_transform_count_, (long long unsigned int)failed_transform_count_,
131-
(long long unsigned int)failed_out_the_back_count_, (long long unsigned int)transform_message_count_,
130+
(long long unsigned int)successful_transform_count_, (long long unsigned int)failed_transform_count_,
131+
(long long unsigned int)failed_out_the_back_count_, (long long unsigned int)transform_message_count_,
132132
(long long unsigned int)incoming_message_count_, (long long unsigned int)dropped_message_count_);
133133

134134
}

0 commit comments

Comments
 (0)