generic_analyzer_base.h
Go to the documentation of this file.
00001 /*********************************************************************
00002  * Software License Agreement (BSD License)
00003  *
00004  *  Copyright (c) 2009, 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 
00037 #ifndef GENERIC_ANALYZER_BASE_H
00038 #define GENERIC_ANALYZER_BASE_H
00039 
00040 #include <map>
00041 #include <ros/ros.h>
00042 #include <vector>
00043 #include <string>
00044 #include <sstream>
00045 #include <boost/shared_ptr.hpp>
00046 #include <boost/regex.hpp>
00047 #include <pluginlib/class_list_macros.h>
00048 #include "diagnostic_msgs/DiagnosticStatus.h"
00049 #include "diagnostic_msgs/KeyValue.h"
00050 #include "diagnostic_aggregator/analyzer.h"
00051 #include "diagnostic_aggregator/status_item.h"
00052 
00053 namespace diagnostic_aggregator {
00054 
00065 class GenericAnalyzerBase : public Analyzer
00066 {
00067 public:
00068   GenericAnalyzerBase() : 
00069     nice_name_(""), path_(""), timeout_(-1.0), num_items_expected_(-1),
00070     discard_stale_(false), has_initialized_(false), has_warned_(false) 
00071   { }
00072   
00073   virtual ~GenericAnalyzerBase() { items_.clear(); }
00074   
00075   /*
00076    *\brief Cannot be initialized from (string, NodeHandle) like defined Analyzers
00077    */
00078   bool init(const std::string path, const ros::NodeHandle &n) = 0;
00079 
00080   /*
00081    *\brief Must be initialized with path, and a "nice name"
00082    *
00083    * Must be initialized in order to prepend the path to all outgoing status messages.
00084    */
00085   bool init(const std::string path, const std::string nice_name, 
00086             double timeout = -1.0, int num_items_expected = -1, bool discard_stale = false)
00087   {
00088     num_items_expected_ = num_items_expected;
00089     timeout_ = timeout;
00090     nice_name_ = nice_name;
00091     path_ = path;
00092     discard_stale_ = discard_stale;
00093 
00094     if (discard_stale_ and timeout <= 0)
00095     {
00096       ROS_WARN("Cannot discard stale items if no timeout specified. No items will be discarded");
00097       discard_stale_ = false;
00098     }
00099 
00100     has_initialized_ = true;
00101     
00102     return true;
00103   }
00104 
00108   virtual bool analyze(const boost::shared_ptr<StatusItem> item)
00109   {
00110     if (!has_initialized_ && !has_warned_)
00111     {
00112       has_warned_ = true;
00113       ROS_ERROR("GenericAnalyzerBase is asked to analyze diagnostics without being initialized. init() must be called in order to correctly use this class.");
00114     }
00115 
00116     if (!has_initialized_)
00117       return false;
00118 
00119     items_[item->getName()] = item;
00120 
00121     return has_initialized_;
00122   }
00123   
00129   virtual std::vector<boost::shared_ptr<diagnostic_msgs::DiagnosticStatus> > report()
00130   {
00131     if (!has_initialized_ && !has_warned_)
00132     {
00133       has_warned_ = true;
00134       ROS_ERROR("GenericAnalyzerBase is asked to report diagnostics without being initialized. init() must be called in order to correctly use this class.");
00135     }
00136     if (!has_initialized_)
00137     {
00138       std::vector<boost::shared_ptr<diagnostic_msgs::DiagnosticStatus> > vec;
00139       return vec;
00140     }
00141 
00142     boost::shared_ptr<diagnostic_msgs::DiagnosticStatus> header_status(new diagnostic_msgs::DiagnosticStatus());
00143     header_status->name = path_;
00144     header_status->level = 0;
00145     header_status->message = "OK";
00146     
00147     std::vector<boost::shared_ptr<diagnostic_msgs::DiagnosticStatus> > processed;
00148     processed.push_back(header_status);
00149     
00150     bool all_stale = true;
00151     
00152     std::map<std::string, boost::shared_ptr<StatusItem> >::iterator it;
00153     for (it = items_.begin(); it != items_.end(); it++)
00154     {
00155       std::string name = it->first;
00156       boost::shared_ptr<StatusItem> item = it->second;
00157 
00158       bool stale = false;
00159       if (timeout_ > 0)
00160         stale = (ros::Time::now() - item->getLastUpdateTime()).toSec() > timeout_;
00161 
00162       // Erase item if its stale and we're discarding items
00163       if (discard_stale_ and stale)
00164       {
00165         items_.erase(it);
00166         continue;
00167       }
00168       
00169       int8_t level = item->getLevel();
00170       header_status->level = std::max(header_status->level, level);
00171       
00172       diagnostic_msgs::KeyValue kv;
00173       kv.key = name;
00174       kv.value = item->getMessage();
00175       
00176       header_status->values.push_back(kv);
00177       
00178       all_stale = all_stale && ((level == 3) || stale);
00179       
00180       //boost::shared_ptr<diagnostic_msgs::DiagnosticStatus> stat = item->toStatusMsg(path_, stale);
00181       
00182       processed.push_back(item->toStatusMsg(path_, stale));
00183 
00184       if (stale)
00185         header_status->level = 3;
00186     }
00187     
00188     // Header is not stale unless all subs are
00189     if (all_stale)
00190       header_status->level = 3;
00191     else if (header_status->level == 3)
00192       header_status->level = 2;
00193     
00194     header_status->message = valToMsg(header_status->level);
00195     
00196     // If we expect a given number of items, check that we have this number
00197     if (num_items_expected_ == 0 && items_.size() == 0)
00198     {
00199       header_status->level = 0;
00200       header_status->message = "OK";
00201     }
00202     else if (num_items_expected_ > 0 and int(items_.size()) != num_items_expected_)
00203     {
00204       int8_t lvl = 2;
00205       header_status->level = std::max(lvl, header_status->level);
00206 
00207       std::stringstream expec, item;
00208       expec << num_items_expected_;
00209       item << items_.size();
00210 
00211       if (items_.size() > 0)
00212         header_status->message = "Expected " + expec.str() + ", found " + item.str();
00213       else
00214         header_status->message = "No items found, expected " + expec.str();
00215     }
00216     
00217     return processed;
00218   }
00219   
00220 
00221   
00225   virtual bool match(const std::string name) = 0;
00226   
00230   virtual std::string getPath() const { return path_; }
00231 
00235   virtual std::string getName() const { return nice_name_; }
00236 
00237 protected:
00238   std::string nice_name_;
00239   std::string path_;
00240 
00241   double timeout_;
00242   int num_items_expected_;
00243 
00247   void addItem(std::string name, boost::shared_ptr<StatusItem> item)  { items_[name] = item; }
00248 
00249 private:
00253   std::map<std::string, boost::shared_ptr<StatusItem> > items_;
00254 
00255   bool discard_stale_, has_initialized_, has_warned_;
00256 };
00257 
00258 }
00259 #endif //GENERIC_ANALYZER_BASE_H


diagnostic_aggregator
Author(s): Kevin Watts, Brice Rebsamen
autogenerated on Sun Oct 5 2014 23:27:29