Skip to content

Commit

Permalink
Fix compile error due to the user-defined string literals feature (#1010
Browse files Browse the repository at this point in the history
)
  • Loading branch information
kartikmohta authored and wjwwood committed May 24, 2016
1 parent 94368e3 commit 311fd94
Showing 1 changed file with 4 additions and 4 deletions.
8 changes: 4 additions & 4 deletions src/rviz/default_plugin/effort_display.h
Original file line number Diff line number Diff line change
Expand Up @@ -36,13 +36,13 @@ namespace tf
# undef TF_MESSAGEFILTER_DEBUG
#endif
#define TF_MESSAGEFILTER_DEBUG(fmt, ...) \
ROS_DEBUG_NAMED("message_filter", "MessageFilter [target=%s]: "fmt, getTargetFramesString().c_str(), __VA_ARGS__)
ROS_DEBUG_NAMED("message_filter", "MessageFilter [target=%s]: " fmt, getTargetFramesString().c_str(), __VA_ARGS__)

#ifdef TF_MESSAGEFILTER_WARN
# undef TF_MESSAGEFILTER_WARN
#endif
#define TF_MESSAGEFILTER_WARN(fmt, ...) \
ROS_WARN_NAMED("message_filter", "MessageFilter [target=%s]: "fmt, getTargetFramesString().c_str(), __VA_ARGS__)
ROS_WARN_NAMED("message_filter", "MessageFilter [target=%s]: " fmt, getTargetFramesString().c_str(), __VA_ARGS__)

class MessageFilterJointState : public MessageFilter<sensor_msgs::JointState>
{
Expand Down Expand Up @@ -127,8 +127,8 @@ namespace tf
clear();

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

}
Expand Down

0 comments on commit 311fd94

Please sign in to comment.