LogFile.cpp
Go to the documentation of this file.
00001 /*
00002  * Copyright (C) 2009 by Ulrich Friedrich Klank <klank@in.tum.de>
00003  *
00004  * This program is free software; you can redistribute it and/or modify
00005  * it under the terms of the GNU General Public License as published by
00006  * the Free Software Foundation; either version 3 of the License, or
00007  * (at your option) any later version.
00008  *
00009  * This program is distributed in the hope that it will be useful,
00010  * but WITHOUT ANY WARRANTY; without even the implied warranty of
00011  * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
00012  * GNU General Public License for more details.
00013  *
00014  * You should have received a copy of the GNU General Public License
00015  * along with this program.  If not, see <http://www.gnu.org/licenses/>.
00016  */
00017 
00018 
00019 #ifdef LOGFILE
00020 #include "LogFile.h"
00021 
00022 #include <ros/ros.h>
00023 #include <std_msgs/String.h>
00024 
00025 
00026 #ifdef BOOST_THREAD
00027 #include <boost/thread.hpp>
00028 #include <boost/bind.hpp>
00029 boost::mutex s_mutexLogFile;
00030 #include <boost/thread/mutex.hpp>
00031 #define BOOST(A) A
00032 
00033 #else
00034 #define BOOST (A) ;
00035 #endif
00036 
00037 using namespace cop;
00038 
00039 ros::Publisher s_pubDebug;
00040 
00041 LogFile::LogFile(std::string filename) :
00042     m_filename(filename)
00043 {
00044     if(m_filename.length() == 0)
00045     {
00046         m_filename = "LogFile.log";
00047     }
00048     try
00049     {
00050       ros::NodeHandle nh;
00051       s_pubDebug = nh.advertise<std_msgs::String>("/cop/logging", 5);
00052     }
00053     catch(...)
00054     {
00055       printf("\n\n\n PROBLEMS ADVERTISING IN LOGFILE\n\n\n");
00056     }
00057        
00058 }
00059 
00060 LogFile::~LogFile(void)
00061 {
00062 }
00063 
00064 
00065 void LogFile::ReportEvent(unsigned long ppid, std::string ppalg)
00066 {
00067   char test[1024];
00068   std_msgs::String st;
00069   sprintf(test, "%ld %s ",ppid, ppalg.c_str());
00070   st.data = test;
00071   s_pubDebug.publish(st);
00072 }
00073 
00074 
00075 void LogFile::ReportError(std::string action_name,  std::string caller, long timestamp, double risk, Elem* relatedElem, std::string problemDescription)
00076 {
00077 
00078    ROS_ERROR("The action %s reported problems: %s\n", action_name.c_str(), problemDescription.c_str());
00079    ROS_ERROR("  Caller: %s, Elem involved: %ld (Type: %s)\n", caller.c_str(), relatedElem->m_ID, relatedElem->GetNodeName().c_str());
00080    ROS_ERROR("  Time Information: %ld Risk: %f\n", timestamp, risk);
00081 }
00082 
00083 
00085 void LogFile::Log(std::string action_name,  std::string caller, double duration_s, double success, Elem* relatedElem)
00086 #ifdef BOOST_THREAD
00087 {
00088                 boost::thread(
00089             boost::bind(&LogFile::LogThread, this,
00090           action_name,
00091         caller,
00092       duration_s, success, relatedElem)) ;
00093 }
00094 
00095 void LogFile::LogThread(std::string action_name,  std::string caller, double duration_s, double success, Elem* relatedElem)
00096 #endif
00097 {
00098    FILE* file = NULL;
00099    XMLTag* tag = NULL;
00100    printf("Lock for logfile\n");
00101    BOOST(s_mutexLogFile.lock());
00102     try
00103     {
00104       tag = new XMLTag(XML_NODE_LOGENTRY);
00105       tag->AddProperty(XML_ATTRIBUTE_TIMESTAMP_LOG, tag->date());
00106       tag->AddProperty(XML_ATTRIBUTE_CALLER,  caller);
00107       tag->AddProperty(XML_ATTRIBUTE_DURATION, duration_s);
00108       tag->AddProperty(XML_ATTRIBUTE_SUCCESS, success);
00109 
00110       XMLTag* child = new XMLTag(XML_NODE_ACTION_DESCRIPTION);
00111       child->SetCData(action_name);
00112       tag->AddChild(child);
00113 
00114       if(relatedElem != NULL)
00115       {
00116         XMLTag* elem = relatedElem->Save(true);
00117         tag->AddChild(elem);
00118       }
00119       char* ch = tag->WriteToString();
00120 #ifdef WIN32
00121       fopen_s(&file,  m_filename.c_str(), "a");
00122   #else /*WIN32*/
00123 
00124       printf("Opening file: %s for appending logs\n", m_filename.c_str());
00125       file = fopen( m_filename.c_str(), "a");
00126       if(file == NULL)
00127       {
00128         printf("LogFile Log: Not able to open logfile to append an logentry\n");
00129       }
00130   #endif  /*WIN32*/
00131       if(file != NULL)
00132       {
00133         fwrite(ch , strlen(ch), 1, file);
00134         fclose(file);
00135         tag->FreeAfterWriteToString();
00136       }
00137     }
00138     catch(...)
00139     {
00140       printf("LogFile::Log: Unexpected Error in logging\n");
00141     }
00142     delete tag;
00143     printf("Unlock for logfile\n");
00144   BOOST(s_mutexLogFile.unlock());
00145 #ifdef _DEBUG
00146   printf("Leaving temporary logging thread.\n");
00147 #endif
00148 
00149 }
00150 #endif /*LOGFILE*/
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Properties Friends Defines


cognitive_perception
Author(s): Ulrich F Klank
autogenerated on Thu May 23 2013 07:38:34