Go to the documentation of this file.00001 
00002 
00003 
00004 
00005 
00006 
00007 
00008 
00009 
00010 
00011 
00012 
00013 
00014 
00015 
00016 
00017 
00018 
00019 
00020 
00021 
00022 
00023 
00024 
00025 
00026 
00027 
00028 
00029 
00030 
00031 
00032 
00033 
00034 
00039 #ifndef DIAGNOSTIC_STATUS_ITEM_H
00040 #define DIAGNOSTIC_STATUS_ITEM_H
00041 
00042 #include <map>
00043 #include <string>
00044 #include <vector>
00045 #include <ros/ros.h>
00046 #include <diagnostic_msgs/DiagnosticStatus.h>
00047 #include <diagnostic_msgs/KeyValue.h>
00048 #include <boost/shared_ptr.hpp>
00049 
00050 namespace diagnostic_aggregator {
00051 
00055 inline std::string getOutputName(const std::string item_name)
00056 {
00057   std::string output_name = item_name;
00058   std::string slash_str = "/";
00059   std::string::size_type pos = 0;
00060   while ((pos = output_name.find(slash_str, pos)) != std::string::npos)
00061   {
00062     output_name.replace(pos, slash_str.size(), " ");
00063     pos++;
00064   }
00065 
00066   return output_name;
00067 }
00068 
00072 enum DiagnosticLevel
00073 {
00074   Level_OK = diagnostic_msgs::DiagnosticStatus::OK,
00075   Level_Warn = diagnostic_msgs::DiagnosticStatus::WARN,
00076   Level_Error = diagnostic_msgs::DiagnosticStatus::ERROR,
00077   Level_Stale = 3
00078 };
00079 
00083 inline DiagnosticLevel valToLevel(const int val)
00084 {
00085   if (val == diagnostic_msgs::DiagnosticStatus::OK)
00086     return Level_OK;
00087   if (val == diagnostic_msgs::DiagnosticStatus::WARN)
00088     return Level_Warn;
00089   if (val == diagnostic_msgs::DiagnosticStatus::ERROR)
00090     return Level_Error;
00091   if (val == 3)
00092     return Level_Stale;
00093   
00094   ROS_ERROR("Attempting to convert %d into DiagnosticLevel. Values are: {0: OK, 1: Warning, 2: Error, 3: Stale}", val);
00095   return Level_Error;
00096 }
00097 
00101 inline std::string valToMsg(const int val)
00102 {
00103   if (val == diagnostic_msgs::DiagnosticStatus::OK)
00104     return "OK";
00105   if (val == diagnostic_msgs::DiagnosticStatus::WARN)
00106     return "Warning";
00107   if (val == diagnostic_msgs::DiagnosticStatus::ERROR)
00108     return "Error";
00109   if (val == 3)
00110     return "Stale";
00111   
00112   ROS_ERROR("Attempting to convert diagnostic level %d into string. Values are: {0: \"OK\", 1: \"Warning\", 2: \"Error\", 3: \"Stale\"}", val);
00113   return "Error";
00114 }
00115 
00127 inline std::string removeLeadingNameChaff(const std::string &input_name, const std::string &chaff)
00128 {
00129   std::string output_name = input_name;
00130 
00131   if (chaff.size() == 0)
00132     return output_name;
00133 
00134   
00135   
00136   std::size_t last_slash = output_name.rfind("/");
00137   std::string start_of_name = output_name.substr(0, last_slash) + std::string("/");
00138 
00139   if (output_name.find(chaff) == last_slash + 1)
00140     output_name.replace(last_slash + 1, chaff.size(), "");
00141 
00142   if (output_name.find(":", last_slash) == last_slash + 1)
00143     output_name= start_of_name + output_name.substr(last_slash + 2);
00144 
00145   while (output_name.find(" ", last_slash) == last_slash + 1)
00146     output_name = start_of_name + output_name.substr(last_slash + 2);
00147 
00148   return output_name;
00149 }
00150 
00158 class StatusItem
00159 {
00160 public:
00164   StatusItem(const diagnostic_msgs::DiagnosticStatus *status);
00165 
00169   StatusItem(const std::string item_name, const std::string message = "Missing", const DiagnosticLevel level = Level_Stale);
00170 
00171   ~StatusItem();
00172 
00178   bool update(const diagnostic_msgs::DiagnosticStatus *status);
00179 
00191   boost::shared_ptr<diagnostic_msgs::DiagnosticStatus> toStatusMsg(const std::string &path, const bool stale = false) const;
00192 
00193   
00194 
00195 
00196   DiagnosticLevel getLevel() const { return level_; }
00197 
00201   std::string getMessage() const { return message_; }
00202 
00206   std::string getName() const { return name_; }
00207 
00211   std::string getHwId() const { return hw_id_; }
00212 
00216   const ros::Time getLastUpdateTime() const { return update_time_; }
00217 
00223   bool hasKey(const std::string &key) const
00224   {
00225     for (unsigned int i = 0; i < values_.size(); ++i)
00226     {
00227       if (values_[i].key == key)
00228         return true;
00229     }
00230 
00231     return false;
00232   }
00233 
00239   std::string getValue(const std::string &key) const
00240   {
00241     for (unsigned int i = 0; i < values_.size(); ++i)
00242     {
00243       if (values_[i].key == key)
00244         return values_[i].value;
00245     }
00246 
00247     return std::string("");
00248   }
00249 
00250 private:
00251   ros::Time update_time_;
00252 
00253   DiagnosticLevel level_;
00254   std::string output_name_; 
00255   std::string name_;
00256   std::string message_;
00257   std::string hw_id_;
00258   std::vector<diagnostic_msgs::KeyValue> values_;
00259 };
00260 
00261 }
00262 
00263 #endif //DIAGNOSTIC_STATUS_ITEM_H