log_utils.h
Go to the documentation of this file.
00001 // -*- mode: c++ -*-
00002 /*********************************************************************
00003  * Software License Agreement (BSD License)
00004  *
00005  *  Copyright (c) 2015, JSK Lab
00006  *  All rights reserved.
00007  *
00008  *  Redistribution and use in source and binary forms, with or without
00009  *  modification, are permitted provided that the following conditions
00010  *  are met:
00011  *
00012  *   * Redistributions of source code must retain the above copyright
00013  *     notice, this list of conditions and the following disclaimer.
00014  *   * Redistributions in binary form must reproduce the above
00015  *     copyright notice, this list of conditions and the following
00016  *     disclaimer in the documentation and/o2r other materials provided
00017  *     with the distribution.
00018  *   * Neither the name of the JSK Lab nor the names of its
00019  *     contributors may be used to endorse or promote products derived
00020  *     from this software without specific prior written permission.
00021  *
00022  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00023  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00024  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00025  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00026  *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00027  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00028  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00029  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00030  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00031  *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00032  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00033  *  POSSIBILITY OF SUCH DAMAGE.
00034  *********************************************************************/
00035 
00036 
00037 #ifndef JSK_TOPIC_TOOLS_LOG_UTILS_H_
00038 #define JSK_TOPIC_TOOLS_LOG_UTILS_H_
00039 
00040 #include <ros/ros.h>
00041 #include <nodelet/nodelet.h>
00042 
00043 
00044 namespace jsk_topic_tools
00045 {
00046 
00052   bool warnNoRemap(const std::vector<std::string> names);
00053 
00054 
00060   const std::string getFunctionName(const std::string &name);
00061 
00062 }
00063 
00064 #define JSK_TOPIC_TOOLS_DEPRECATED_JSK_NODELET_XXX() \
00065   ROS_WARN_ONCE("DEPRECATION WARNING: JSK_NODELET_XXX log macros are deprecated, and please use NODELET_XXX instead." \
00066                 " (See https://github.com/jsk-ros-pkg/jsk_common/issues/1461)");
00067 #define JSK_TOPIC_TOOLS_DEPRECATED_JSK_ROS_XXX() \
00068   ROS_WARN_ONCE("DEPRECATION WARNING: JSK_ROS_XXX log utils are deprecated, and please use ROS_XXX instead." \
00069                 " (See https://github.com/jsk-ros-pkg/jsk_common/issues/1461)");
00070 
00071 #define JSK_NODELET_DEBUG(str,...) \
00072   JSK_TOPIC_TOOLS_DEPRECATED_JSK_NODELET_XXX(); \
00073   NODELET_DEBUG("[%s] " str, jsk_topic_tools::getFunctionName(__PRETTY_FUNCTION__).c_str(), ##__VA_ARGS__)
00074 #define JSK_NODELET_INFO(str,...) \
00075   JSK_TOPIC_TOOLS_DEPRECATED_JSK_NODELET_XXX(); \
00076   NODELET_INFO("[%s] " str, jsk_topic_tools::getFunctionName(__PRETTY_FUNCTION__).c_str(), ##__VA_ARGS__)
00077 #define JSK_NODELET_WARN(str,...) \
00078   JSK_TOPIC_TOOLS_DEPRECATED_JSK_NODELET_XXX(); \
00079   NODELET_WARN("[%s] " str, jsk_topic_tools::getFunctionName(__PRETTY_FUNCTION__).c_str(), ##__VA_ARGS__)
00080 #define JSK_NODELET_ERROR(str,...) \
00081   JSK_TOPIC_TOOLS_DEPRECATED_JSK_NODELET_XXX(); \
00082   NODELET_ERROR("[%s] " str, jsk_topic_tools::getFunctionName(__PRETTY_FUNCTION__).c_str(), ##__VA_ARGS__)
00083 #define JSK_NODELET_FATAL(str,...) \
00084   JSK_TOPIC_TOOLS_DEPRECATED_JSK_NODELET_XXX(); \
00085   NODELET_FATAL("[%s] " str, jsk_topic_tools::getFunctionName(__PRETTY_FUNCTION__).c_str(), ##__VA_ARGS__)
00086 
00087 #define JSK_NODELET_DEBUG_STREAM(...) \
00088   JSK_TOPIC_TOOLS_DEPRECATED_JSK_NODELET_XXX(); \
00089   NODELET_DEBUG_STREAM("[" << jsk_topic_tools::getFunctionName(__PRETTY_FUNCTION__).c_str() << "] " << __VA_ARGS__)
00090 #define JSK_NODELET_INFO_STREAM(...) \
00091   JSK_TOPIC_TOOLS_DEPRECATED_JSK_NODELET_XXX(); \
00092   NODELET_INFO_STREAM("[" << jsk_topic_tools::getFunctionName(__PRETTY_FUNCTION__).c_str() << "] " << __VA_ARGS__)
00093 #define JSK_NODELET_WARN_STREAM(...) \
00094   JSK_TOPIC_TOOLS_DEPRECATED_JSK_NODELET_XXX(); \
00095   NODELET_WARN_STREAM("[" << jsk_topic_tools::getFunctionName(__PRETTY_FUNCTION__).c_str() << "] " << __VA_ARGS__)
00096 #define JSK_NODELET_ERROR_STREAM(...) \
00097   JSK_TOPIC_TOOLS_DEPRECATED_JSK_NODELET_XXX(); \
00098   NODELET_ERROR_STREAM("[" << jsk_topic_tools::getFunctionName(__PRETTY_FUNCTION__).c_str() << "] " << __VA_ARGS__)
00099 #define JSK_NODELET_FATAL_STREAM(...) \
00100   JSK_TOPIC_TOOLS_DEPRECATED_JSK_NODELET_XXX(); \
00101   NODELET_FATAL_STREAM("[" << jsk_topic_tools::getFunctionName(__PRETTY_FUNCTION__).c_str() << "] " << __VA_ARGS__)
00102 
00103 #define JSK_NODELET_DEBUG_THROTTLE(rate, str, ...) \
00104   JSK_TOPIC_TOOLS_DEPRECATED_JSK_NODELET_XXX(); \
00105   NODELET_DEBUG_THROTTLE(rate, "[%s] " str, jsk_topic_tools::getFunctionName(__PRETTY_FUNCTION__).c_str(), ##__VA_ARGS__)
00106 #define JSK_NODELET_INFO_THROTTLE(rate, str, ...) \
00107   JSK_TOPIC_TOOLS_DEPRECATED_JSK_NODELET_XXX(); \
00108   NODELET_INFO_THROTTLE(rate, "[%s] " str, jsk_topic_tools::getFunctionName(__PRETTY_FUNCTION__).c_str(), ##__VA_ARGS__)
00109 #define JSK_NODELET_WARN_THROTTLE(rate, str, ...) \
00110   JSK_TOPIC_TOOLS_DEPRECATED_JSK_NODELET_XXX(); \
00111   NODELET_WARN_THROTTLE(rate, "[%s] " str, jsk_topic_tools::getFunctionName(__PRETTY_FUNCTION__).c_str(), ##__VA_ARGS__)
00112 #define JSK_NODELET_ERROR_THROTTLE(rate, str, ...) \
00113   JSK_TOPIC_TOOLS_DEPRECATED_JSK_NODELET_XXX(); \
00114   NODELET_ERROR_THROTTLE(rate, "[%s] " str, jsk_topic_tools::getFunctionName(__PRETTY_FUNCTION__).c_str(), ##__VA_ARGS__)
00115 #define JSK_NODELET_FATAL_THROTTLE(rate, str, ...) \
00116   JSK_TOPIC_TOOLS_DEPRECATED_JSK_NODELET_XXX(); \
00117   NODELET_FATAL_THROTTLE(rate, "[%s] " str, jsk_topic_tools::getFunctionName(__PRETTY_FUNCTION__).c_str(), ##__VA_ARGS__)
00118 
00119 #define JSK_NODELET_DEBUG_STREAM_THROTTLE(rate,...) \
00120   JSK_TOPIC_TOOLS_DEPRECATED_JSK_NODELET_XXX(); \
00121   NODELET_DEBUG_STREAM_THROTTLE(rate, "[" << jsk_topic_tools::getFunctionName(__PRETTY_FUNCTION__).c_str() << "] " << __VA_ARGS__)
00122 #define JSK_NODELET_INFO_STREAM_THROTTLE(rate,...) \
00123   JSK_TOPIC_TOOLS_DEPRECATED_JSK_NODELET_XXX(); \
00124   NODELET_INFO_STREAM_THROTTLE(rate, "[" << jsk_topic_tools::getFunctionName(__PRETTY_FUNCTION__).c_str() << "] " << __VA_ARGS__)
00125 #define JSK_NODELET_WARN_STREAM_THROTTLE(rate,...) \
00126   JSK_TOPIC_TOOLS_DEPRECATED_JSK_NODELET_XXX(); \
00127   NODELET_WARN_STREAM_THROTTLE(rate, "[" << jsk_topic_tools::getFunctionName(__PRETTY_FUNCTION__).c_str() << "] " << __VA_ARGS__)
00128 #define JSK_NODELET_ERROR_STREAM_THROTTLE(rate,...) \
00129   JSK_TOPIC_TOOLS_DEPRECATED_JSK_NODELET_XXX(); \
00130   NODELET_ERROR_STREAM_THROTTLE(rate, "[" << jsk_topic_tools::getFunctionName(__PRETTY_FUNCTION__).c_str() << "] " << __VA_ARGS__)
00131 #define JSK_NODELET_FATAL_STREAM_THROTTLE(rate,...) \
00132   JSK_TOPIC_TOOLS_DEPRECATED_JSK_NODELET_XXX(); \
00133   NODELET_FATAL_STREAM_THROTTLE(rate, "[" << jsk_topic_tools::getFunctionName(__PRETTY_FUNCTION__).c_str() << "] " << __VA_ARGS__)
00134 
00135 #define JSK_ROS_DEBUG(str,...) \
00136   JSK_TOPIC_TOOLS_DEPRECATED_JSK_ROS_XXX(); \
00137   ROS_DEBUG("[%s] " str, jsk_topic_tools::getFunctionName(__PRETTY_FUNCTION__).c_str(), ##__VA_ARGS__)
00138 #define JSK_ROS_INFO(str,...) \
00139   JSK_TOPIC_TOOLS_DEPRECATED_JSK_ROS_XXX(); \
00140   ROS_INFO("[%s] " str, jsk_topic_tools::getFunctionName(__PRETTY_FUNCTION__).c_str(), ##__VA_ARGS__)
00141 #define JSK_ROS_WARN(str,...) \
00142   JSK_TOPIC_TOOLS_DEPRECATED_JSK_ROS_XXX(); \
00143   ROS_WARN("[%s] " str, jsk_topic_tools::getFunctionName(__PRETTY_FUNCTION__).c_str(), ##__VA_ARGS__)
00144 #define JSK_ROS_ERROR(str,...) \
00145   JSK_TOPIC_TOOLS_DEPRECATED_JSK_ROS_XXX(); \
00146   ROS_ERROR("[%s] " str, jsk_topic_tools::getFunctionName(__PRETTY_FUNCTION__).c_str(), ##__VA_ARGS__)
00147 #define JSK_ROS_FATAL(str,...) \
00148   JSK_TOPIC_TOOLS_DEPRECATED_JSK_ROS_XXX(); \
00149   ROS_FATAL("[%s] " str, jsk_topic_tools::getFunctionName(__PRETTY_FUNCTION__).c_str(), ##__VA_ARGS__)
00150 
00151 #define JSK_ROS_DEBUG_STREAM(...) \
00152   JSK_TOPIC_TOOLS_DEPRECATED_JSK_ROS_XXX(); \
00153   ROS_DEBUG_STREAM("[" << jsk_topic_tools::getFunctionName(__PRETTY_FUNCTION__).c_str() << "] " << __VA_ARGS__)
00154 #define JSK_ROS_INFO_STREAM(...) \
00155   JSK_TOPIC_TOOLS_DEPRECATED_JSK_ROS_XXX(); \
00156   ROS_INFO_STREAM("[" << jsk_topic_tools::getFunctionName(__PRETTY_FUNCTION__).c_str() << "] " << __VA_ARGS__)
00157 #define JSK_ROS_WARN_STREAM(...) \
00158   JSK_TOPIC_TOOLS_DEPRECATED_JSK_ROS_XXX(); \
00159   ROS_WARN_STREAM("[" << jsk_topic_tools::getFunctionName(__PRETTY_FUNCTION__).c_str() << "] " << __VA_ARGS__)
00160 #define JSK_ROS_ERROR_STREAM(...) \
00161   JSK_TOPIC_TOOLS_DEPRECATED_JSK_ROS_XXX(); \
00162   ROS_ERROR_STREAM("[" << jsk_topic_tools::getFunctionName(__PRETTY_FUNCTION__).c_str() << "] " << __VA_ARGS__)
00163 #define JSK_ROS_FATAL_STREAM(...) \
00164   JSK_TOPIC_TOOLS_DEPRECATED_JSK_ROS_XXX(); \
00165   ROS_FATAL_STREAM("[" << jsk_topic_tools::getFunctionName(__PRETTY_FUNCTION__).c_str() << "] " << __VA_ARGS__)
00166 
00167 #define JSK_ROS_DEBUG_THROTTLE(rate, str, ...) \
00168   JSK_TOPIC_TOOLS_DEPRECATED_JSK_ROS_XXX(); \
00169   ROS_DEBUG_THROTTLE(rate, "[%s] " str, jsk_topic_tools::getFunctionName(__PRETTY_FUNCTION__).c_str(), ##__VA_ARGS__)
00170 #define JSK_ROS_INFO_THROTTLE(rate, str, ...) \
00171   JSK_TOPIC_TOOLS_DEPRECATED_JSK_ROS_XXX(); \
00172   ROS_INFO_THROTTLE(rate, "[%s] " str, jsk_topic_tools::getFunctionName(__PRETTY_FUNCTION__).c_str(), ##__VA_ARGS__)
00173 #define JSK_ROS_WARN_THROTTLE(rate, str, ...) \
00174   JSK_TOPIC_TOOLS_DEPRECATED_JSK_ROS_XXX(); \
00175   ROS_WARN_THROTTLE(rate, "[%s] " str, jsk_topic_tools::getFunctionName(__PRETTY_FUNCTION__).c_str(), ##__VA_ARGS__)
00176 #define JSK_ROS_ERROR_THROTTLE(rate, str, ...) \
00177   JSK_TOPIC_TOOLS_DEPRECATED_JSK_ROS_XXX(); \
00178   ROS_ERROR_THROTTLE(rate, "[%s] " str, jsk_topic_tools::getFunctionName(__PRETTY_FUNCTION__).c_str(), ##__VA_ARGS__)
00179 #define JSK_ROS_FATAL_THROTTLE(rate, str, ...) \
00180   JSK_TOPIC_TOOLS_DEPRECATED_JSK_ROS_XXX(); \
00181   ROS_FATAL_THROTTLE(rate, "[%s] " str, jsk_topic_tools::getFunctionName(__PRETTY_FUNCTION__).c_str(), ##__VA_ARGS__)
00182 
00183 #define JSK_ROS_DEBUG_STREAM_THROTTLE(rate,...) \
00184   JSK_TOPIC_TOOLS_DEPRECATED_JSK_ROS_XXX(); \
00185   ROS_DEBUG_STREAM_THROTTLE(rate, "[" << jsk_topic_tools::getFunctionName(__PRETTY_FUNCTION__).c_str() << "] " << __VA_ARGS__)
00186 #define JSK_ROS_INFO_STREAM_THROTTLE(rate,...) \
00187   JSK_TOPIC_TOOLS_DEPRECATED_JSK_ROS_XXX(); \
00188   ROS_INFO_STREAM_THROTTLE(rate, "[" << jsk_topic_tools::getFunctionName(__PRETTY_FUNCTION__).c_str() << "] " << __VA_ARGS__)
00189 #define JSK_ROS_WARN_STREAM_THROTTLE(rate,...) \
00190   JSK_TOPIC_TOOLS_DEPRECATED_JSK_ROS_XXX(); \
00191   ROS_WARN_STREAM_THROTTLE(rate, "[" << jsk_topic_tools::getFunctionName(__PRETTY_FUNCTION__).c_str() << "] " << __VA_ARGS__)
00192 #define JSK_ROS_ERROR_STREAM_THROTTLE(rate,...) \
00193   JSK_TOPIC_TOOLS_DEPRECATED_JSK_ROS_XXX(); \
00194   ROS_ERROR_STREAM_THROTTLE(rate, "[" << jsk_topic_tools::getFunctionName(__PRETTY_FUNCTION__).c_str() << "] " << __VA_ARGS__)
00195 #define JSK_ROS_FATAL_STREAM_THROTTLE(rate,...) \
00196   JSK_TOPIC_TOOLS_DEPRECATED_JSK_ROS_XXX(); \
00197   ROS_FATAL_STREAM_THROTTLE(rate, "[" << jsk_topic_tools::getFunctionName(__PRETTY_FUNCTION__).c_str() << "] " << __VA_ARGS__)
00198 
00199 #endif


jsk_topic_tools
Author(s): Kei Okada , Yusuke Furuta
autogenerated on Fri Sep 8 2017 03:38:56