DiagnosticStatusWrapper.h
Go to the documentation of this file.
00001 /*********************************************************************
00002 * Software License Agreement (BSD License)
00003 * 
00004 *  Copyright (c) 2008, 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 Willow Garage 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 
00039 #ifndef DIAGNOSTICMESSAGEWRAPPER_HH
00040 #define DIAGNOSTICMESSAGEWRAPPER_HH
00041 
00042 #include <vector>
00043 #include <string>
00044 #include <sstream>
00045 #include <stdarg.h>
00046 #include <cstdio>
00047 
00048 #include "ros/ros.h"
00049 
00050 #include "diagnostic_msgs/DiagnosticStatus.h"
00051 
00052 namespace diagnostic_updater
00053 {
00054 
00066   class DiagnosticStatusWrapper : public diagnostic_msgs::DiagnosticStatus
00067   {
00068     public:
00069 
00076       void summary(unsigned char lvl, const std::string s)
00077       {
00078         level = lvl;
00079         message = s;
00080       }
00081 
00101       void mergeSummary(unsigned char lvl, const std::string s)
00102       {
00103         if ((lvl>0) && (level>0))
00104         {
00105           if (!message.empty())
00106             message += "; ";
00107           message += s;
00108         }
00109         else if (lvl > level)
00110           message = s;
00111 
00112         if (lvl > level)
00113           level = lvl;
00114       }
00115 
00123       void mergeSummary(const diagnostic_msgs::DiagnosticStatus &src)
00124       {
00125         mergeSummary(src.level, src.message);
00126       }
00127       
00140       void mergeSummaryf(unsigned char lvl, const char *format, ...)
00141       {
00142         va_list va;
00143         char buff[1000]; // @todo This could be done more elegantly.
00144         va_start(va, format);
00145         if (vsnprintf(buff, 1000, format, va) >= 1000)
00146           ROS_DEBUG("Really long string in DiagnosticStatusWrapper::addf, it was truncated.");
00147         std::string value = std::string(buff);
00148         mergeSummary(lvl, value);
00149         va_end(va);
00150       }
00151 
00163       void summaryf(unsigned char lvl, const char *format, ...)
00164       {
00165         va_list va;
00166         char buff[1000]; // @todo This could be done more elegantly.
00167         va_start(va, format);
00168         if (vsnprintf(buff, 1000, format, va) >= 1000)
00169           ROS_DEBUG("Really long string in DiagnosticStatusWrapper::addf, it was truncated.");
00170         std::string value = std::string(buff);
00171         summary(lvl, value);
00172         va_end(va);
00173       }
00174                        
00179       void clearSummary()
00180       {
00181         summary(0, "");
00182       }
00183       
00189       void summary(const diagnostic_msgs::DiagnosticStatus &src)
00190       {
00191         summary(src.level, src.message);
00192       }
00193 
00203       template<class T>
00204         void add(const std::string &key, const T &val)
00205         {
00206           std::stringstream ss;
00207           ss << val;
00208           std::string sval = ss.str();
00209           add(key, sval);
00210         }
00211 
00220       void addf(const std::string &key, const char *format, ...); // In practice format will always be a char *
00221 
00228       void clear()
00229       {
00230         values.clear();
00231       }
00232   };
00233 
00234   template<>
00235     inline void DiagnosticStatusWrapper::add<std::string>(const std::string &key, const std::string &s)
00236     {
00237       diagnostic_msgs::KeyValue ds;
00238       ds.key = key;
00239       ds.value = s;
00240       values.push_back(ds);
00241     }
00242 
00244 template<>
00245 inline void DiagnosticStatusWrapper::add<bool>(const std::string &key, const bool &b)
00246 {
00247   diagnostic_msgs::KeyValue ds;
00248   ds.key = key;
00249   ds.value = b ? "True" : "False";
00250 
00251   values.push_back(ds);
00252 }
00253 
00254   // Need to place addf after DiagnosticStatusWrapper::add<std::string> or
00255   // gcc complains that the specialization occurs after instatiation.
00256   inline void DiagnosticStatusWrapper::addf(const std::string &key, const char *format, ...) // In practice format will always be a char *
00257   {
00258     va_list va;
00259     char buff[1000]; // @todo This could be done more elegantly.
00260     va_start(va, format);
00261     if (vsnprintf(buff, 1000, format, va) >= 1000)
00262       ROS_DEBUG("Really long string in DiagnosticStatusWrapper::addf, it was truncated.");
00263     std::string value = std::string(buff);
00264     add(key, value);
00265     va_end(va);
00266   }
00267 
00268 
00269 }
00270 #endif


diagnostic_updater
Author(s): Kevin Watts, Brice Rebsamen , Jeremy Leibs, Blaise Gassend
autogenerated on Mon Aug 14 2017 02:52:20