GlobalFunctions.cpp
Go to the documentation of this file.
00001 /*********************************************************************
00002  * Software License Agreement (BSD License)
00003  *
00004  *  Copyright (c) 2013, Institute for Artificial Intelligence,
00005  *  Universität Bremen.
00006  *  All rights reserved.
00007  *
00008  *  Redistribution and use in source and binary forms, with or without
00009  *  modification, are permitted provided that the following conditions
00010  *  are met:
00011  *
00012  *   * Redistributions of source code must retain the above copyright
00013  *     notice, this list of conditions and the following disclaimer.
00014  *   * Redistributions in binary form must reproduce the above
00015  *     copyright notice, this list of conditions and the following
00016  *     disclaimer in the documentation and/or other materials provided
00017  *     with the distribution.
00018  *   * Neither the name of the Institute for Artificial Intelligence,
00019  *     Universität Bremen, nor the names of its contributors may be
00020  *     used to endorse or promote products derived from this software
00021  *     without specific prior written permission.
00022  *
00023  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00024  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00025  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00026  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00027  *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00028  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00029  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00030  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00031  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00032  *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00033  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00034  *  POSSIBILITY OF SUCH DAMAGE.
00035  *********************************************************************/
00036 
00040 #include <ForwardDeclarations.h>
00041 
00042 
00043 namespace beliefstate {
00044   static std::list<int> g_lstContextIDs;
00045   static std::list<int> g_lstPluginIDs;
00046   static ConfigSettings g_cfgsetSettings;
00047   static std::mutex g_mtxGlobalSettings;
00048   static std::map<std::string, CDesignator*> g_mapPluginSettings;
00049   static std::mutex g_mtxStatusMessages;
00050   static std::list<StatusMessage> g_lstStatusMessages;
00051   static int g_nHighestSequenceNumber = 0;
00052   static std::mutex m_mtxSequenceNumberLock;
00053   static std::map<std::string, int> g_mapIssuedGlobalTokens;
00054   static std::mutex g_mtxGlobalTokensLock;
00055   
00056   
00057   void revokeGlobalToken(std::string strToken) {
00058     g_mtxGlobalTokensLock.lock();
00059     g_mapIssuedGlobalTokens[strToken] = 0;
00060     g_mtxGlobalTokensLock.unlock();
00061   }
00062   
00063   bool wasGlobalTokenIssued(std::string strToken) {
00064     bool bReturn = false;
00065     
00066     g_mtxGlobalTokensLock.lock();
00067     bReturn = (g_mapIssuedGlobalTokens[strToken] > 0);
00068     g_mtxGlobalTokensLock.unlock();
00069     
00070     return bReturn;
00071   }
00072   
00073   bool waitForGlobalToken(std::string strToken, float fTimeout) {
00074     // TODO(winkler): The timeout is still not implemented, do that!
00075     
00076     while(true) {
00077       if(wasGlobalTokenIssued(strToken)) {
00078         return true;
00079       }
00080     }
00081     
00082     return false;
00083   }
00084   
00085   void issueGlobalToken(std::string strToken) {
00086     g_mtxGlobalTokensLock.lock();
00087     g_mapIssuedGlobalTokens[strToken] = 1;
00088     g_mtxGlobalTokensLock.unlock();
00089   }
00090   
00091   int rmfile(const char *path, const struct stat *sb, int flag, struct FTW *ftwbuf) {
00092     return ::remove(path);
00093   }
00094   
00095   void deleteDirectory(string strPath, bool bEvenIfNonEmpty) {
00096     if(bEvenIfNonEmpty) {
00097       ::nftw(strPath.c_str(), rmfile, 64, FTW_DEPTH | FTW_PHYS);
00098     } else {
00099       ::rmdir(strPath.c_str());
00100     }
00101   }
00102   
00103   int createContextID() {
00104     int nID = 0;
00105     
00106     while(contextIDTaken(nID)) {
00107       nID++;
00108     }
00109     
00110     g_lstContextIDs.push_back(nID);
00111     
00112     return nID;
00113   }
00114   
00115   bool contextIDTaken(int nID) {
00116     for(list<int>::iterator itID = g_lstContextIDs.begin();
00117         itID != g_lstContextIDs.end();
00118         itID++) {
00119       if(*itID == nID) {
00120         return true;
00121       }
00122     }
00123     
00124     return false;
00125   }
00126   
00127   void freeContextID(int nID) {
00128     g_lstContextIDs.remove(nID);
00129   }
00130   
00131   int createPluginID() {
00132     int nID = 0;
00133     
00134     while(pluginIDTaken(nID)) {
00135       nID++;
00136     }
00137     
00138     g_lstPluginIDs.push_back(nID);
00139     
00140     return nID;
00141   }
00142   
00143   bool pluginIDTaken(int nID) {
00144     for(list<int>::iterator itID = g_lstPluginIDs.begin();
00145         itID != g_lstPluginIDs.end();
00146         itID++) {
00147       if(*itID == nID) {
00148         return true;
00149       }
00150     }
00151     
00152     return false;
00153   }
00154   
00155   void freePluginID(int nID) {
00156     g_lstPluginIDs.remove(nID);
00157   }
00158   
00159   Result defaultResult() {
00160     Result resDefault;
00161     resDefault.bSuccess = true;
00162     resDefault.riResultIdentifier = RI_NONE;
00163     resDefault.strErrorMessage = "";
00164     resDefault.piPlugin = NULL;
00165     
00166     return resDefault;
00167   }
00168   
00169   ServiceEvent defaultServiceEvent(string strServiceName) {
00170     ServiceEvent seDefault;
00171     seDefault.strServiceName = strServiceName;
00172     seDefault.siServiceIdentifier = SI_REQUEST;
00173     seDefault.smResultModifier = SM_AGGREGATE_RESULTS;
00174     seDefault.bPreserve = false;
00175     seDefault.cdDesignator = NULL;
00176     seDefault.nSequenceNumber = nextSequenceNumber();
00177     
00178     return seDefault;
00179   }
00180   
00181   int nextSequenceNumber() {
00182     m_mtxSequenceNumberLock.lock();
00183     g_nHighestSequenceNumber++;
00184     int nReturn = g_nHighestSequenceNumber;
00185     m_mtxSequenceNumberLock.unlock();
00186     
00187     return nReturn;
00188   }
00189   
00190   void resetSequenceNumbers() {
00191     m_mtxSequenceNumberLock.lock();
00192     g_nHighestSequenceNumber = 0;
00193     m_mtxSequenceNumberLock.unlock();
00194   }
00195   
00196   Event defaultEvent(string strEventName) {
00197     Event evDefault;
00198     evDefault.strEventName = strEventName;
00199     evDefault.cdDesignator = NULL;
00200     evDefault.nOriginID = -1;
00201     evDefault.nOpenRequestID = -1;
00202     evDefault.bRequest = true;
00203     evDefault.bPreempt = true;
00204     evDefault.nSequenceNumber = nextSequenceNumber();
00205     
00206     return evDefault;
00207   }
00208   
00209   Event eventInResponseTo(Event evRequest, std::string strEventName) {
00210     if(strEventName == "") {
00211       strEventName = evRequest.strEventName;
00212     }
00213     
00214     Event evDefault = defaultEvent(strEventName);
00215     evDefault.nOpenRequestID = evRequest.nOpenRequestID;
00216     evDefault.bRequest = false;
00217     
00218     return evDefault;
00219   }
00220 
00221   ServiceEvent eventInResponseTo(ServiceEvent seRequest, std::string strServiceName) {
00222     if(strServiceName == "") {
00223       strServiceName = seRequest.strServiceName;
00224     }
00225     
00226     ServiceEvent seDefault = defaultServiceEvent(strServiceName);
00227     seDefault.siServiceIdentifier = SI_RESPONSE;
00228     seDefault.nServiceEventID = seRequest.nServiceEventID;
00229     
00230     return seDefault;
00231   }
00232   
00233   string colorSpecifierForID(int nID, bool bBold) {
00234     ConfigSettings cfgSet = configSettings();
00235     int nLength = cfgSet.vecPluginOutputColors.size();
00236     int nUseIndex = (nID + 3) % nLength;
00237     
00238     return cfgSet.vecPluginOutputColors[nUseIndex];
00239   }
00240   
00241   string normalColorSpecifier() {
00242     return "\033[0m";
00243   }
00244   
00245   ConfigSettings configSettings() {
00246     g_mtxGlobalSettings.lock();
00247     ConfigSettings cfgsetReturn = g_cfgsetSettings;
00248     g_mtxGlobalSettings.unlock();
00249     
00250     return cfgsetReturn;
00251   }
00252   
00253   void setConfigSettings(ConfigSettings cfgsetSettings) {
00254     g_mtxGlobalSettings.lock();
00255     g_cfgsetSettings = cfgsetSettings;
00256     g_mtxGlobalSettings.unlock();
00257   }
00258   
00259   CDesignator* getPluginConfig(string strPluginName) {
00260     CDesignator* cdReturn = NULL;
00261     map<string, CDesignator*>::iterator itPlugin = g_mapPluginSettings.find(strPluginName);
00262     
00263     if(itPlugin != g_mapPluginSettings.end()) {
00264       cdReturn = (*itPlugin).second;
00265     } else {
00266       cdReturn = new CDesignator();
00267       g_mapPluginSettings[strPluginName] = cdReturn;
00268     }
00269     
00270     return cdReturn;
00271   }
00272   
00273   void queueMessage(StatusMessage msgQueue) {
00274     g_mtxStatusMessages.lock();
00275     g_lstStatusMessages.push_back(msgQueue);
00276     g_mtxStatusMessages.unlock();
00277   }
00278   
00279   StatusMessage queueMessage(string strColorCode, bool bBold, string strPrefix, string strMessage) {
00280     StatusMessage msgQueue;
00281     msgQueue.strColorCode = strColorCode;
00282     msgQueue.bBold = bBold;
00283     msgQueue.strPrefix = strPrefix;
00284     msgQueue.strMessage = strMessage;
00285     
00286     queueMessage(msgQueue);
00287     
00288     return msgQueue;
00289   }
00290   
00291   list<StatusMessage> queuedMessages() {
00292     g_mtxStatusMessages.lock();
00293     list<StatusMessage> lstMessages;
00294     
00295     if(g_lstStatusMessages.size() > 0) {
00296       lstMessages = g_lstStatusMessages;
00297       g_lstStatusMessages.clear();
00298     }
00299     
00300     g_mtxStatusMessages.unlock();
00301     
00302     return lstMessages;
00303   }
00304 }


beliefstate
Author(s): Jan Winkler
autogenerated on Sun Oct 5 2014 22:30:15