print.h
Go to the documentation of this file.
00001 /*
00002  * Software License Agreement (BSD License)
00003  *
00004  *  Copyright (c) 2010, Willow Garage, Inc.
00005  *  All rights reserved.
00006  *
00007  *  Redistribution and use in source and binary forms, with or without
00008  *  modification, are permitted provided that the following conditions
00009  *  are met:
00010  *
00011  *   * Redistributions of source code must retain the above copyright
00012  *     notice, this list of conditions and the following disclaimer.
00013  *   * Redistributions in binary form must reproduce the above
00014  *     copyright notice, this list of conditions and the following
00015  *     disclaimer in the documentation and/or other materials provided
00016  *     with the distribution.
00017  *   * Neither the name of the copyright holder(s) nor the names of its
00018  *     contributors may be used to endorse or promote products derived
00019  *     from this software without specific prior written permission.
00020  *
00021  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00022  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00023  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00024  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00025  *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00026  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00027  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00028  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00029  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00030  *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00031  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00032  *  POSSIBILITY OF SUCH DAMAGE.
00033  *
00034  * $Id$
00035  *
00036  */
00037 #ifndef TERMINAL_TOOLS_PRINT_H_
00038 #define TERMINAL_TOOLS_PRINT_H_
00039 
00040 #include <stdio.h>
00041 #include <stdarg.h>
00042 
00043 #include <pcl/pcl_exports.h>
00044 #include <pcl/pcl_config.h>
00045 
00046 #define PCL_ALWAYS(...)  pcl::console::print (pcl::console::L_ALWAYS, __VA_ARGS__)
00047 #define PCL_ERROR(...)   pcl::console::print (pcl::console::L_ERROR, __VA_ARGS__)
00048 #define PCL_WARN(...)    pcl::console::print (pcl::console::L_WARN, __VA_ARGS__)
00049 #define PCL_INFO(...)    pcl::console::print (pcl::console::L_INFO, __VA_ARGS__)
00050 #define PCL_DEBUG(...)   pcl::console::print (pcl::console::L_DEBUG, __VA_ARGS__)
00051 #define PCL_VERBOSE(...) pcl::console::print (pcl::console::L_VERBOSE, __VA_ARGS__)
00052 
00053 #define PCL_ASSERT_ERROR_PRINT_CHECK(pred, msg) \
00054     do \
00055     { \
00056         if (!(pred)) \
00057         { \
00058             PCL_ERROR(msg); \
00059             PCL_ERROR("In File %s, in line %d\n" __FILE__, __LINE__); \
00060         } \
00061     } while (0)
00062 
00063 #define PCL_ASSERT_ERROR_PRINT_RETURN(pred, msg, err) \
00064     do \
00065     { \
00066         PCL_ASSERT_ERROR_PRINT_CHECK(pred, msg); \
00067         if (!(pred)) return err; \
00068     } while (0)
00069 
00070 namespace pcl
00071 {
00072   namespace console
00073   {
00074     enum TT_ATTIBUTES
00075     {
00076       TT_RESET     = 0,
00077       TT_BRIGHT    = 1,
00078       TT_DIM       = 2,
00079       TT_UNDERLINE = 3,
00080       TT_BLINK     = 4,
00081       TT_REVERSE   = 7,
00082       TT_HIDDEN    = 8
00083     };
00084 
00085     enum TT_COLORS
00086     {
00087       TT_BLACK,
00088       TT_RED,
00089       TT_GREEN,
00090       TT_YELLOW,
00091       TT_BLUE,
00092       TT_MAGENTA,
00093       TT_CYAN,
00094       TT_WHITE
00095     };
00096 
00097     enum VERBOSITY_LEVEL
00098     {
00099       L_ALWAYS,
00100       L_ERROR,
00101       L_WARN,
00102       L_INFO,
00103       L_DEBUG,
00104       L_VERBOSE
00105     };
00106 
00108     PCL_EXPORTS void 
00109     setVerbosityLevel (VERBOSITY_LEVEL level);
00110 
00112     PCL_EXPORTS VERBOSITY_LEVEL 
00113     getVerbosityLevel ();
00114 
00116     PCL_EXPORTS bool 
00117     initVerbosityLevel ();
00118 
00120     PCL_EXPORTS bool 
00121     isVerbosityLevelEnabled (VERBOSITY_LEVEL severity);
00122 
00129     PCL_EXPORTS void 
00130     change_text_color (FILE *stream, int attribute, int fg, int bg);
00131     
00137     PCL_EXPORTS void 
00138     change_text_color (FILE *stream, int attribute, int fg);
00139 
00143     PCL_EXPORTS void 
00144     reset_text_color (FILE *stream);
00145 
00152     PCL_EXPORTS void 
00153     print_color (FILE *stream, int attr, int fg, const char *format, ...);
00154 
00158     PCL_EXPORTS void 
00159     print_info  (const char *format, ...);
00160 
00165     PCL_EXPORTS void 
00166     print_info  (FILE *stream, const char *format, ...);
00167 
00171     PCL_EXPORTS void 
00172     print_highlight  (const char *format, ...);
00173 
00178     PCL_EXPORTS void 
00179     print_highlight  (FILE *stream, const char *format, ...);
00180 
00184     PCL_EXPORTS void 
00185     print_error (const char *format, ...);
00186 
00191     PCL_EXPORTS void 
00192     print_error (FILE *stream, const char *format, ...);
00193 
00197     PCL_EXPORTS void 
00198     print_warn (const char *format, ...);
00199 
00204     PCL_EXPORTS void 
00205     print_warn (FILE *stream, const char *format, ...);
00206 
00210     PCL_EXPORTS void 
00211     print_debug (const char *format, ...);
00212 
00217     PCL_EXPORTS void 
00218     print_debug (FILE *stream, const char *format, ...);
00219 
00220 
00224     PCL_EXPORTS void 
00225     print_value (const char *format, ...);
00226 
00231     PCL_EXPORTS void 
00232     print_value (FILE *stream, const char *format, ...);
00233 
00239     PCL_EXPORTS void 
00240     print (VERBOSITY_LEVEL level, FILE *stream, const char *format, ...);
00241 
00246     PCL_EXPORTS void 
00247     print (VERBOSITY_LEVEL level, const char *format, ...);
00248   }
00249 } 
00250 
00251 #endif // TERMINAL_TOOLS_PRINT_H_


pcl
Author(s): Open Perception
autogenerated on Wed Aug 26 2015 15:31:18