rospack.cpp
Go to the documentation of this file.
00001 /*
00002  * Copyright (C) 2008, Willow Garage, Inc., Morgan Quigley
00003  * 
00004  * Redistribution and use in source and binary forms, with or without
00005  * modification, are permitted provided that the following conditions are met:
00006  *   * Redistributions of source code must retain the above copyright notice,
00007  *     this list of conditions and the following disclaimer.
00008  *   * Redistributions in binary form must reproduce the above copyright
00009  *     notice, this list of conditions and the following disclaimer in the
00010  *     documentation and/or other materials provided with the distribution.
00011  *   * Neither the names of Stanford University or Willow Garage, Inc. nor the names of its
00012  *     contributors may be used to endorse or promote products derived from
00013  *     this software without specific prior written permission.
00014  *
00015  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
00016  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
00017  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
00018  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
00019  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
00020  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
00021  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
00022  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
00023  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
00024  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00025  * POSSIBILITY OF SUCH DAMAGE.
00026  */
00027 
00028 #include "rospack/rospack.h"
00029 #include "utils.h"
00030 #include "tinyxml-2.5.3/tinyxml.h"
00031 
00032 #include <boost/filesystem.hpp>
00033 #include <boost/algorithm/string.hpp>
00034 #include <stdexcept>
00035 
00036 #if defined(WIN32)
00037   #include <windows.h>
00038   #include <direct.h>
00039   #include <libgen.h> // for dirname
00040   #include <fcntl.h>  // for O_RDWR, O_EXCL, O_CREAT
00041 #else //!defined(WIN32)
00042   #include <sys/types.h>
00043   #include <libgen.h>
00044   #include <pwd.h>
00045   #include <unistd.h>
00046   #include <sys/time.h>
00047 #endif
00048 
00049 #include <climits>
00050 
00051 #include <sys/stat.h>
00052 #include <stdio.h>
00053 #include <stdlib.h>
00054 #include <time.h>
00055 #include <string.h>
00056 #include <errno.h>
00057 
00058 // TODO:
00059 //   recrawl on:
00060 //     package not found in cache
00061 //     package found in cache, but no manifest.xml present in filesystem
00062 
00063 namespace fs = boost::filesystem;
00064 
00065 namespace rospack
00066 {
00067 static const char* MANIFEST_TAG_PACKAGE = "package";
00068 static const char* MANIFEST_TAG_STACK = "stack";
00069 static const char* ROSPACK_MANIFEST_NAME = "manifest.xml";
00070 static const char* ROSSTACK_MANIFEST_NAME = "stack.xml";
00071 static const char* ROSPACK_CACHE_NAME = "rospack_cache";
00072 static const char* ROSSTACK_CACHE_NAME = "rosstack_cache";
00073 static const char* ROSPACK_NOSUBDIRS = "rospack_nosubdirs";
00074 static const char* DOTROS_NAME = ".ros";
00075 static const char* MSG_GEN_GENERATED_DIR = "msg_gen";
00076 static const char* MSG_GEN_GENERATED_FILE = "generated";
00077 static const char* SRV_GEN_GENERATED_DIR = "srv_gen";
00078 static const char* SRV_GEN_GENERATED_FILE = "generated";
00079 static const char* MANIFEST_TAG_ROSDEP = "rosdep";
00080 static const char* MANIFEST_TAG_VERSIONCONTROL = "versioncontrol";
00081 static const char* MANIFEST_TAG_EXPORT = "export";
00082 static const char* MANIFEST_ATTR_NAME = "name";
00083 static const char* MANIFEST_ATTR_TYPE = "type";
00084 static const char* MANIFEST_ATTR_URL = "url";
00085 static const char* MANIFEST_PREFIX = "${prefix}";
00086 static const int MAX_CRAWL_DEPTH = 1000;
00087 static const int MAX_DEPENDENCY_DEPTH = 1000;
00088 static const double DEFAULT_MAX_CACHE_AGE = 60.0;
00089 
00090 rospack_tinyxml::TiXmlElement* get_manifest_root(Stackage* stackage);
00091 double time_since_epoch();
00092 
00093 #ifdef __APPLE__
00094   static const std::string g_ros_os = "osx";
00095 #else
00096   #if defined(WIN32)
00097     static const std::string g_ros_os = "win32";
00098   #else
00099     static const std::string g_ros_os = "linux";
00100   #endif
00101 #endif
00102 
00103 class Exception : public std::runtime_error
00104 {
00105   public:
00106     Exception(const std::string& what)
00107             : std::runtime_error(what)
00108     {}
00109 };
00110 
00111 class Stackage
00112 {
00113   public:
00114     // \brief name of the stackage
00115     std::string name_;
00116     // \brief absolute path to the stackage
00117     std::string path_;
00118     // \brief absolute path to the stackage manifest
00119     std::string manifest_path_;
00120     // \brief have we already loaded the manifest?
00121     bool manifest_loaded_;
00122     // \brief TinyXML structure, filled in during parsing
00123     rospack_tinyxml::TiXmlDocument manifest_;
00124     std::vector<Stackage*> deps_;
00125     bool deps_computed_;
00126 
00127     Stackage(const std::string& name,
00128              const std::string& path,
00129              const std::string& manifest_path) :
00130             name_(name),
00131             path_(path),
00132             manifest_path_(manifest_path),
00133             manifest_loaded_(false),
00134             deps_computed_(false)
00135   {
00136   }
00137 
00138 };
00139 
00140 class DirectoryCrawlRecord
00141 {
00142   public:
00143     std::string path_;
00144     bool zombie_;
00145     double start_time_;
00146     double crawl_time_;
00147     size_t start_num_pkgs_;
00148     DirectoryCrawlRecord(std::string path, 
00149                          double start_time, 
00150                          size_t start_num_pkgs) :
00151             path_(path),
00152             zombie_(false),
00153             start_time_(start_time),
00154             crawl_time_(0.0),
00155             start_num_pkgs_(start_num_pkgs) {}
00156 };
00157 bool cmpDirectoryCrawlRecord(DirectoryCrawlRecord* i,
00158                              DirectoryCrawlRecord* j)
00159 {
00160   return (i->crawl_time_ < j->crawl_time_);
00161 }
00162 
00164 // Rosstackage methods (public/protected)
00166 Rosstackage::Rosstackage(const std::string& manifest_name,
00167                          const std::string& cache_name,
00168                          const std::string& name,
00169                          const std::string& tag) :
00170         manifest_name_(manifest_name),
00171         cache_name_(cache_name),
00172         crawled_(false),
00173         name_(name),
00174         tag_(tag)
00175 {
00176 }
00177 
00178 void 
00179 Rosstackage::logWarn(const std::string& msg,
00180                      bool append_errno)
00181 {
00182   log("Warning", msg, append_errno);
00183 }
00184 void
00185 Rosstackage::logError(const std::string& msg,
00186                       bool append_errno)
00187 {
00188   log("Error", msg, append_errno);
00189 }
00190 
00191 bool
00192 Rosstackage::getSearchPathFromEnv(std::vector<std::string>& sp)
00193 {
00194   char* rr = getenv("ROS_ROOT");
00195   char* rpp = getenv("ROS_PACKAGE_PATH");
00196 
00197   // ROS_ROOT is optional, and will be phased out
00198   if(rr)
00199   {
00200     try 
00201     {
00202       if(fs::is_directory(rr))
00203         sp.push_back(rr);
00204       else
00205         logWarn(std::string("ROS_ROOT=") + rr + " is not a directory");
00206     }
00207     catch(fs::filesystem_error& e)
00208     {
00209       logWarn(std::string("error while looking at ROS_ROOT ") + rr + ": " + e.what());
00210     }
00211   }
00212   if(rpp)
00213   {
00214     // I can't see that boost filesystem has an elegant cross platform
00215     // representation for this anywhere like qt/python have.
00216     #if defined(WIN32)
00217       const char *path_delim = ";";
00218     #else //!defined(WIN32)
00219       const char *path_delim = ":";
00220     #endif
00221 
00222     std::vector<std::string> rpp_strings;
00223     boost::split(rpp_strings, rpp, 
00224                  boost::is_any_of(path_delim),
00225                  boost::token_compress_on);
00226     for(std::vector<std::string>::const_iterator it = rpp_strings.begin();
00227         it != rpp_strings.end();
00228         ++it)
00229     {
00230       sp.push_back(*it);
00231     }
00232   }
00233   return true;
00234 }
00235 
00236 void
00237 Rosstackage::setQuiet(bool quiet)
00238 {
00239   quiet_ = quiet;
00240 }
00241 
00242 bool
00243 Rosstackage::isStackage(const std::string& path)
00244 {
00245   try
00246   {
00247     if(!fs::is_directory(path))
00248       return false;
00249   }
00250   catch(fs::filesystem_error& e)
00251   {
00252     logWarn(std::string("error while looking at ") + path + ": " + e.what());
00253     return false;
00254   }
00255 
00256   try
00257   {
00258     for(fs::directory_iterator dit = fs::directory_iterator(path);
00259         dit != fs::directory_iterator();
00260         ++dit)
00261     {
00262       if(!fs::is_regular_file(dit->path()))
00263         continue;
00264 
00265       if(dit->path().filename() == manifest_name_)
00266         return true;
00267     }
00268   }
00269   catch(fs::filesystem_error& e)
00270   {
00271     logWarn(std::string("error while crawling ") + path + ": " + e.what());
00272   }
00273   return false;
00274 }
00275 
00276 void
00277 Rosstackage::crawl(std::vector<std::string> search_path,
00278                    bool force)
00279 {
00280   if(!force)
00281   {
00282     if(readCache())
00283     {
00284       // If the cache was valid, then the paths in the cache match the ones
00285       // we've been asked to crawl.  Store them, so that later, methods
00286       // like find() can refer to them when recrawling.
00287       search_paths_.clear();
00288       for(std::vector<std::string>::const_iterator it = search_path.begin();
00289           it != search_path.end();
00290           ++it)
00291         search_paths_.push_back(*it);
00292       return;
00293     }
00294   }
00295 
00296   if(crawled_)
00297   {
00298     bool same_paths = true;
00299     if(search_paths_.size() == search_path.size())
00300       same_paths = false;
00301     else
00302     {
00303       for(unsigned int i=0; i<search_paths_.size(); i++)
00304       {
00305         if(search_paths_[i] != search_path[i])
00306         {
00307           same_paths = false;
00308           break;
00309         }
00310       }
00311     }
00312 
00313     if(same_paths)
00314       return;
00315   }
00316 
00317 
00318   std::tr1::unordered_map<std::string, Stackage*>::const_iterator it = stackages_.begin();
00319   while(it != stackages_.end())
00320   {
00321     delete it->second;
00322     it = stackages_.erase(it);
00323   }
00324   dups_.clear();
00325   search_paths_.clear();
00326   for(std::vector<std::string>::const_iterator it = search_path.begin();
00327       it != search_path.end();
00328       ++it)
00329     search_paths_.push_back(*it);
00330 
00331   std::vector<DirectoryCrawlRecord*> dummy;
00332   std::tr1::unordered_set<std::string> dummy2;
00333   for(std::vector<std::string>::const_iterator p = search_paths_.begin();
00334       p != search_paths_.end();
00335       ++p)
00336     crawlDetail(*p, force, 1, false, dummy, dummy2);
00337   
00338   crawled_ = true;
00339 
00340   writeCache();
00341 }
00342 
00343 bool 
00344 Rosstackage::inStackage(std::string& name)
00345 {
00346   fs::path path;
00347   try
00348   {
00349     // Search upward, as suggested in #3697.  This method is only used when
00350     // a package is not given on the command-line, and so should not have
00351     // performance impact in common usage.
00352     for(fs::path path = fs::current_path();
00353         !path.empty();
00354         path = path.parent_path())
00355     {
00356       if(Rosstackage::isStackage(path.string()))
00357       {
00358 #if !defined(BOOST_FILESYSTEM_VERSION) || (BOOST_FILESYSTEM_VERSION == 2)
00359         name = fs::path(path).filename();
00360 #else
00361         // in boostfs3, filename() returns a path, which needs to be stringified
00362         name = fs::path(path).filename().string();
00363 #endif
00364         return true;
00365       }
00366     }
00367     // Search failed.
00368     return false;
00369   }
00370   catch(fs::filesystem_error& e)
00371   {
00372     // can't determine current directory, or encountered trouble while
00373     // searching upward; too bad
00374     return false;
00375   }
00376 }
00377 
00378 
00379 bool
00380 Rosstackage::find(const std::string& name, std::string& path)
00381 {
00382   Stackage* s = findWithRecrawl(name);
00383   if(s)
00384   {
00385     path = s->path_;
00386     return true;
00387   }
00388   else
00389     return false;
00390 }
00391 
00392 bool
00393 Rosstackage::contents(const std::string& name, 
00394                       std::set<std::string>& packages)
00395 {
00396   Rospack rp2;
00397   std::tr1::unordered_map<std::string, Stackage*>::const_iterator it = stackages_.find(name);
00398   if(it != stackages_.end())
00399   {
00400     std::vector<std::string> search_paths;
00401     search_paths.push_back(it->second->path_);
00402     rp2.crawl(search_paths, true);
00403     std::set<std::pair<std::string, std::string> > names_paths;
00404     rp2.list(names_paths);
00405     for(std::set<std::pair<std::string, std::string> >::const_iterator iit = names_paths.begin();
00406         iit != names_paths.end();
00407         ++iit)
00408       packages.insert(iit->first);
00409     return true;
00410   }
00411   else
00412   {
00413     logError(std::string("stack ") + name + " not found");
00414     return false;
00415   }
00416 }
00417 
00418 bool
00419 Rosstackage::contains(const std::string& name, 
00420                       std::string& stack,
00421                       std::string& path)
00422 {
00423   Rospack rp2;
00424   for(std::tr1::unordered_map<std::string, Stackage*>::const_iterator it = stackages_.begin();
00425       it != stackages_.end();
00426       ++it)
00427   {
00428     std::vector<std::string> search_paths;
00429     search_paths.push_back(it->second->path_);
00430     rp2.crawl(search_paths, true);
00431     std::set<std::pair<std::string, std::string> > names_paths;
00432     rp2.list(names_paths);
00433     for(std::set<std::pair<std::string, std::string> >::const_iterator iit = names_paths.begin();
00434         iit != names_paths.end();
00435         ++iit)
00436     {
00437       if(iit->first == name)
00438       {
00439         stack = it->first;
00440         path = it->second->path_;
00441         return true;
00442       }
00443     }
00444   }
00445 
00446   logError(std::string("stack containing package ") + name + " not found");
00447   return false;
00448 }
00449 
00450 void 
00451 Rosstackage::list(std::set<std::pair<std::string, std::string> >& list)
00452 {
00453   for(std::tr1::unordered_map<std::string, Stackage*>::const_iterator it = stackages_.begin();
00454       it != stackages_.end();
00455       ++it)
00456   {
00457     std::pair<std::string, std::string> item; 
00458     item.first = it->first; 
00459     item.second = it->second->path_; 
00460     list.insert(item); 
00461   }
00462 }
00463 
00464 void 
00465 Rosstackage::listDuplicates(std::vector<std::string>& dups)
00466 {
00467   dups.resize(dups_.size());
00468   int i = 0;
00469   for(std::tr1::unordered_set<std::string>::const_iterator it = dups_.begin();
00470       it != dups_.end();
00471       ++it)
00472   {
00473     dups[i] = (*it);
00474     i++;
00475   }
00476 }
00477 
00478 bool
00479 Rosstackage::deps(const std::string& name, bool direct,
00480                   std::vector<std::string>& deps)
00481 {
00482   std::vector<Stackage*> stackages;
00483   // Disable errors for the first try
00484   bool old_quiet = quiet_;
00485   setQuiet(true);
00486   if(!depsDetail(name, direct, stackages))
00487   {
00488     // Recrawl
00489     crawl(search_paths_, true);
00490     stackages.clear();
00491     setQuiet(old_quiet);
00492     if(!depsDetail(name, direct, stackages))
00493       return false;
00494   }
00495   setQuiet(old_quiet);
00496   for(std::vector<Stackage*>::const_iterator it = stackages.begin();
00497       it != stackages.end();
00498       ++it)
00499     deps.push_back((*it)->name_);
00500   return true;
00501 }
00502 
00503 bool
00504 Rosstackage::depsOn(const std::string& name, bool direct,
00505                        std::vector<std::string>& deps)
00506 {
00507   std::vector<Stackage*> stackages;
00508   if(!depsOnDetail(name, direct, stackages))
00509     return false;
00510   for(std::vector<Stackage*>::const_iterator it = stackages.begin();
00511       it != stackages.end();
00512       ++it)
00513     deps.push_back((*it)->name_);
00514   return true;
00515 }
00516 
00517 bool
00518 Rosstackage::depsIndent(const std::string& name, bool direct,
00519                         std::vector<std::string>& deps)
00520 {
00521   Stackage* stackage = findWithRecrawl(name);
00522   if(!stackage)
00523     return false;
00524   try
00525   {
00526     computeDeps(stackage);
00527     std::vector<Stackage*> deps_vec;
00528     std::tr1::unordered_set<Stackage*> deps_hash;
00529     std::vector<std::string> indented_deps;
00530     gatherDepsFull(stackage, direct, POSTORDER, 0, deps_hash, deps_vec, true, indented_deps);
00531     for(std::vector<std::string>::const_iterator it = indented_deps.begin();
00532         it != indented_deps.end();
00533         ++it)
00534       deps.push_back(*it);
00535   }
00536   catch(Exception& e)
00537   {
00538     logError(e.what());
00539     return false;
00540   }
00541   return true;
00542 }
00543 
00544 bool
00545 Rosstackage::depsWhy(const std::string& from,
00546                      const std::string& to,
00547                      std::string& output)
00548 {
00549   Stackage* from_s = findWithRecrawl(from);
00550   if(!from_s)
00551     return false;
00552   Stackage* to_s = findWithRecrawl(to);
00553   if(!to_s)
00554     return false;
00555 
00556   std::list<std::list<Stackage*> > acc_list;
00557   try
00558   {
00559     depsWhyDetail(from_s, to_s, acc_list);
00560   }
00561   catch(Exception& e)
00562   {
00563     logError(e.what());
00564     return true;
00565   }
00566   output.append(std::string("Dependency chains from ") + 
00567                 from + " to " + to + ":\n");
00568   for(std::list<std::list<Stackage*> >::const_iterator it = acc_list.begin();
00569       it != acc_list.end();
00570       ++it)
00571   {
00572     output.append("* ");
00573     for(std::list<Stackage*>::const_iterator iit = it->begin();
00574         iit != it->end();
00575         ++iit)
00576     {
00577       if(iit != it->begin())
00578         output.append("-> ");
00579       output.append((*iit)->name_ + " ");
00580     }
00581     output.append("\n");
00582   }
00583   return true;
00584 }
00585 
00586 bool
00587 Rosstackage::depsManifests(const std::string& name, bool direct, 
00588                            std::vector<std::string>& manifests)
00589 {
00590   Stackage* stackage = findWithRecrawl(name);
00591   if(!stackage)
00592     return false;
00593   try
00594   {
00595     computeDeps(stackage);
00596     std::vector<Stackage*> deps_vec;
00597     gatherDeps(stackage, direct, POSTORDER, deps_vec);
00598     for(std::vector<Stackage*>::const_iterator it = deps_vec.begin();
00599         it != deps_vec.end();
00600         ++it)
00601       manifests.push_back((*it)->manifest_path_);
00602   }
00603   catch(Exception& e)
00604   {
00605     logError(e.what());
00606     return false;
00607   }
00608   return true;
00609 }
00610 
00611 bool
00612 Rosstackage::rosdeps(const std::string& name, bool direct, 
00613                      std::set<std::string>& rosdeps)
00614 {
00615   Stackage* stackage = findWithRecrawl(name);
00616   if(!stackage)
00617     return false;
00618   try
00619   {
00620     computeDeps(stackage);
00621     std::vector<Stackage*> deps_vec;
00622     // rosdeps include the current package
00623     deps_vec.push_back(stackage);
00624     if(!direct)
00625       gatherDeps(stackage, direct, POSTORDER, deps_vec);
00626     for(std::vector<Stackage*>::const_iterator it = deps_vec.begin();
00627         it != deps_vec.end();
00628         ++it)
00629     {
00630       rospack_tinyxml::TiXmlElement* root = get_manifest_root(*it);
00631       for(rospack_tinyxml::TiXmlElement* ele = root->FirstChildElement(MANIFEST_TAG_ROSDEP);
00632           ele;
00633           ele = ele->NextSiblingElement(MANIFEST_TAG_ROSDEP))
00634       {
00635         const char *att_str;
00636         if((att_str = ele->Attribute(MANIFEST_ATTR_NAME)))
00637         {
00638           rosdeps.insert(std::string("name: ") + att_str);
00639         }
00640       }
00641     }
00642   }
00643   catch(Exception& e)
00644   {
00645     logError(e.what());
00646     return false;
00647   }
00648   return true;
00649 }
00650 
00651 bool
00652 Rosstackage::vcs(const std::string& name, bool direct, 
00653                  std::vector<std::string>& vcs)
00654 {
00655   Stackage* stackage = findWithRecrawl(name);
00656   if(!stackage)
00657     return false;
00658   try
00659   {
00660     computeDeps(stackage);
00661     std::vector<Stackage*> deps_vec;
00662     // vcs include the current package
00663     deps_vec.push_back(stackage);
00664     if(!direct)
00665       gatherDeps(stackage, direct, POSTORDER, deps_vec);
00666     for(std::vector<Stackage*>::const_iterator it = deps_vec.begin();
00667         it != deps_vec.end();
00668         ++it)
00669     {
00670       rospack_tinyxml::TiXmlElement* root = get_manifest_root(*it);
00671       for(rospack_tinyxml::TiXmlElement* ele = root->FirstChildElement(MANIFEST_TAG_VERSIONCONTROL);
00672           ele;
00673           ele = ele->NextSiblingElement(MANIFEST_TAG_VERSIONCONTROL))
00674       {
00675         std::string result;
00676         const char *att_str;
00677         if((att_str = ele->Attribute(MANIFEST_ATTR_TYPE)))
00678         {
00679           result.append("type: ");
00680           result.append(att_str);
00681         }
00682         if((att_str = ele->Attribute(MANIFEST_ATTR_URL)))
00683         {
00684           result.append("\turl: ");
00685           result.append(att_str);
00686         }
00687         vcs.push_back(result);
00688       }
00689     }
00690   }
00691   catch(Exception& e)
00692   {
00693     logError(e.what());
00694     return false;
00695   }
00696   return true;
00697 }
00698 
00699 bool 
00700 Rosstackage::exports(const std::string& name, const std::string& lang,
00701                      const std::string& attrib, bool deps_only,
00702                      std::vector<std::string>& flags)
00703 {
00704   Stackage* stackage = findWithRecrawl(name);
00705   if(!stackage)
00706     return false;
00707   try
00708   {
00709     computeDeps(stackage);
00710     std::vector<Stackage*> deps_vec;
00711     if(!deps_only)
00712       deps_vec.push_back(stackage);
00713     gatherDeps(stackage, false, PREORDER, deps_vec);
00714     for(std::vector<Stackage*>::const_iterator it = deps_vec.begin();
00715         it != deps_vec.end();
00716         ++it)
00717     {
00718       rospack_tinyxml::TiXmlElement* root = get_manifest_root(*it);
00719       for(rospack_tinyxml::TiXmlElement* ele = root->FirstChildElement(MANIFEST_TAG_EXPORT);
00720           ele;
00721           ele = ele->NextSiblingElement(MANIFEST_TAG_EXPORT))
00722       {
00723         bool os_match = false;
00724         const char *best_match = NULL;
00725         for(rospack_tinyxml::TiXmlElement* ele2 = ele->FirstChildElement(lang);
00726             ele2;
00727             ele2 = ele2->NextSiblingElement(lang))
00728         {
00729           const char *os_str;
00730           if ((os_str = ele2->Attribute("os")))
00731           {
00732             if(g_ros_os == std::string(os_str))
00733             {
00734               if(os_match)
00735                 logWarn(std::string("ignoring duplicate ") + lang + " tag with os=" + os_str + " in export block");
00736               else
00737               {
00738                 best_match = ele2->Attribute(attrib.c_str());
00739                 os_match = true;
00740               }
00741             }
00742           }
00743           if(!os_match)
00744           {
00745             if(!best_match)
00746               best_match = ele2->Attribute(attrib.c_str());
00747             else
00748               logWarn(std::string("ignoring duplicate ") + lang + " tag in export block");
00749           }
00750 
00751         }
00752         if(best_match)
00753         {
00754           std::string expanded_str;
00755           if(!expandExportString(*it, best_match, expanded_str))
00756             return false;
00757           flags.push_back(expanded_str);
00758         }
00759       }
00760 
00761       // We automatically point to msg_gen and msg_srv directories if
00762       // certain files are present.
00763       // But only if we're looking for cpp/cflags, #3884.
00764       if((lang == "cpp") && (attrib == "cflags"))
00765       {
00766         fs::path msg_gen = fs::path((*it)->path_) / MSG_GEN_GENERATED_DIR;
00767         fs::path srv_gen = fs::path((*it)->path_) / SRV_GEN_GENERATED_DIR;
00768         if(fs::is_regular_file(msg_gen / MSG_GEN_GENERATED_FILE))
00769         {
00770           msg_gen /= fs::path("cpp") / "include";
00771           flags.push_back(std::string("-I" + msg_gen.string()));
00772         }
00773         if(fs::is_regular_file(srv_gen / SRV_GEN_GENERATED_FILE))
00774         {
00775           srv_gen /= fs::path("cpp") / "include";
00776           flags.push_back(std::string("-I" + srv_gen.string()));
00777         }
00778       }
00779     }
00780   }
00781   catch(Exception& e)
00782   {
00783     logError(e.what());
00784     return false;
00785   }
00786   return true;
00787 }
00788 
00789 bool 
00790 Rosstackage::plugins(const std::string& name, const std::string& attrib, 
00791                      const std::string& top,
00792                      std::vector<std::string>& flags)
00793 {
00794   // Find everybody who depends directly on the package in question
00795   std::vector<Stackage*> stackages;
00796   if(!depsOnDetail(name, true, stackages))
00797     return false;
00798   // Also look in the package itself
00799   std::tr1::unordered_map<std::string, Stackage*>::const_iterator it = stackages_.find(name);
00800   if(it != stackages_.end())
00801   {
00802     // don't warn here; it was done in depsOnDetail()
00803     stackages.push_back(it->second);
00804   }
00805   // If top was given, filter to include only those package on which top
00806   // depends.
00807   if(top.size())
00808   {
00809     std::vector<Stackage*> top_deps;
00810     if(!depsDetail(top, false, top_deps))
00811       return false;
00812     std::tr1::unordered_set<Stackage*> top_deps_set;
00813     for(std::vector<Stackage*>::iterator it = top_deps.begin();
00814         it != top_deps.end();
00815         ++it)
00816       top_deps_set.insert(*it);
00817     std::vector<Stackage*>::iterator it = stackages.begin();
00818     while(it != stackages.end())
00819     {
00820       if((*it)->name_ != top &&
00821          (top_deps_set.find(*it) == top_deps_set.end()))
00822         it = stackages.erase(it);
00823       else
00824         ++it;
00825     }
00826   }
00827   // Now go looking for the manifest data
00828   for(std::vector<Stackage*>::const_iterator it = stackages.begin();
00829       it != stackages.end();
00830       ++it)
00831   {
00832     rospack_tinyxml::TiXmlElement* root = get_manifest_root(*it);
00833     for(rospack_tinyxml::TiXmlElement* ele = root->FirstChildElement(MANIFEST_TAG_EXPORT);
00834         ele;
00835         ele = ele->NextSiblingElement(MANIFEST_TAG_EXPORT))
00836     {
00837       for(rospack_tinyxml::TiXmlElement* ele2 = ele->FirstChildElement(name);
00838           ele2;
00839           ele2 = ele2->NextSiblingElement(name))
00840       {
00841         const char *att_str;
00842         if((att_str = ele2->Attribute(attrib.c_str())))
00843         {
00844           std::string expanded_str;
00845           if(!expandExportString(*it, att_str, expanded_str))
00846             return false;
00847           flags.push_back((*it)->name_ + " " + expanded_str);
00848         }
00849       }
00850     }
00851   }
00852   return true;
00853 }
00854 
00855 bool
00856 Rosstackage::depsMsgSrv(const std::string& name, bool direct, 
00857                         std::vector<std::string>& gens)
00858 {
00859   Stackage* stackage = findWithRecrawl(name);
00860   if(!stackage)
00861     return false;
00862   try
00863   {
00864     computeDeps(stackage);
00865     std::vector<Stackage*> deps_vec;
00866     gatherDeps(stackage, direct, POSTORDER, deps_vec);
00867     for(std::vector<Stackage*>::const_iterator it = deps_vec.begin();
00868         it != deps_vec.end();
00869         ++it)
00870     {
00871       fs::path msg_gen = fs::path((*it)->path_) / 
00872               MSG_GEN_GENERATED_DIR / 
00873               MSG_GEN_GENERATED_FILE;
00874       fs::path srv_gen = fs::path((*it)->path_) / 
00875               SRV_GEN_GENERATED_DIR / 
00876               SRV_GEN_GENERATED_FILE;
00877       if(fs::is_regular_file(msg_gen))
00878         gens.push_back(msg_gen.string());
00879       if(fs::is_regular_file(srv_gen))
00880         gens.push_back(srv_gen.string());
00881     }
00882   }
00883   catch(Exception& e)
00884   {
00885     logError(e.what());
00886     return false;
00887   }
00888   return true;
00889 }
00890 
00892 // Rosstackage methods (private)
00894 
00895 void 
00896 Rosstackage::log(const std::string& level,
00897                  const std::string& msg,
00898                  bool append_errno)
00899 {
00900   if(quiet_)
00901     return;
00902   fprintf(stderr, "[%s] %s: %s",
00903           name_.c_str(), level.c_str(), msg.c_str());
00904   if(append_errno)
00905     fprintf(stderr, ": %s", strerror(errno));
00906   fprintf(stderr, "\n");
00907 }
00908 
00909 
00910 Stackage*
00911 Rosstackage::findWithRecrawl(const std::string& name)
00912 {
00913   if(stackages_.count(name))
00914     return stackages_[name];
00915   else
00916   {
00917     // Try to recrawl, in case we loaded from cache
00918     crawl(search_paths_, true);
00919     if(stackages_.count(name))
00920       return stackages_[name];
00921   }
00922 
00923   logError(std::string("stack/package ") + name + " not found");
00924   return NULL;
00925 }
00926 
00927 bool
00928 Rosstackage::depsDetail(const std::string& name, bool direct,
00929                         std::vector<Stackage*>& deps)
00930 {
00931   // No recrawl here, because we're in a recursive function.  Rely on the
00932   // top level to do it.
00933   if(!stackages_.count(name))
00934   {
00935     logError(std::string("no such package ") + name);
00936     return false;
00937   }
00938   Stackage* stackage = stackages_[name];
00939   try
00940   {
00941     computeDeps(stackage);
00942     std::vector<Stackage*> deps_vec;
00943     gatherDeps(stackage, direct, POSTORDER, deps_vec);
00944     for(std::vector<Stackage*>::const_iterator it = deps_vec.begin();
00945         it != deps_vec.end();
00946         ++it)
00947       deps.push_back(*it);
00948   }
00949   catch(Exception& e)
00950   {
00951     logError(e.what());
00952     return false;
00953   }
00954   return true;
00955 }
00956 
00957 void
00958 Rosstackage::depsWhyDetail(Stackage* from,
00959                            Stackage* to,
00960                            std::list<std::list<Stackage*> >& acc_list)
00961 {
00962   computeDeps(from);
00963   for(std::vector<Stackage*>::const_iterator it = from->deps_.begin();
00964       it != from->deps_.end();
00965       ++it)
00966   {
00967     if((*it)->name_ == to->name_)
00968     {
00969       std::list<Stackage*> acc;
00970       acc.push_back(from);
00971       acc.push_back(to);
00972       acc_list.push_back(acc);
00973     }
00974     else
00975     {
00976       std::list<std::list<Stackage*> > l;
00977       depsWhyDetail(*it, to, l);
00978       for(std::list<std::list<Stackage*> >::iterator iit = l.begin();
00979           iit != l.end();
00980           ++iit)
00981       {
00982         iit->push_front(from);
00983         acc_list.push_back(*iit);
00984       }
00985     }
00986   }
00987 }
00988 
00989 bool
00990 Rosstackage::depsOnDetail(const std::string& name, bool direct,
00991                              std::vector<Stackage*>& deps)
00992 {
00993   // No recrawl here, because depends-on always forces a crawl at the
00994   // start.
00995   if(!stackages_.count(name))
00996     logWarn(std::string("no such package ") + name);
00997   try
00998   {
00999     for(std::tr1::unordered_map<std::string, Stackage*>::const_iterator it = stackages_.begin();
01000         it != stackages_.end();
01001         ++it)
01002     {
01003       computeDeps(it->second, true);
01004       std::vector<Stackage*> deps_vec;
01005       gatherDeps(it->second, direct, POSTORDER, deps_vec);
01006       for(std::vector<Stackage*>::const_iterator iit = deps_vec.begin();
01007           iit != deps_vec.end();
01008           ++iit)
01009       {
01010         if((*iit)->name_ == name)
01011         {
01012           deps.push_back(it->second);
01013           break;
01014         }
01015       }
01016     }
01017   }
01018   catch(Exception& e)
01019   {
01020     logError(e.what());
01021     return false;
01022   }
01023   return true;
01024 }
01025 
01026 bool
01027 Rosstackage::profile(const std::vector<std::string>& search_path,
01028                      bool zombie_only,
01029                      int length,
01030                      std::vector<std::string>& dirs)
01031 {
01032   double start = time_since_epoch();
01033   std::vector<DirectoryCrawlRecord*> dcrs;
01034   std::tr1::unordered_set<std::string> dcrs_hash;
01035   for(std::vector<std::string>::const_iterator p = search_path.begin();
01036       p != search_path.end();
01037       ++p)
01038   {
01039     crawlDetail(*p, true, 1, true, dcrs, dcrs_hash);
01040   }
01041   if(!zombie_only)
01042   {
01043     double total = time_since_epoch() - start;
01044     char buf[16];
01045     snprintf(buf, sizeof(buf), "%.6f", total);
01046     dirs.push_back(std::string("Full tree crawl took ") + buf + " seconds.");
01047     dirs.push_back("Directories marked with (*) contain no manifest.  You may");
01048     dirs.push_back("want to delete these directories.");
01049     dirs.push_back("To get just of list of directories without manifests,");
01050     dirs.push_back("re-run the profile with --zombie-only");
01051     dirs.push_back("-------------------------------------------------------------");
01052   }
01053   std::sort(dcrs.begin(), dcrs.end(), cmpDirectoryCrawlRecord);
01054   std::reverse(dcrs.begin(), dcrs.end());
01055   int i=0;
01056   for(std::vector<DirectoryCrawlRecord*>::const_iterator it = dcrs.begin();
01057       it != dcrs.end();
01058       ++it)
01059   {
01060     if(zombie_only)
01061     {
01062       if((*it)->zombie_)
01063       {
01064         if(length < 0 || i < length)
01065           dirs.push_back((*it)->path_);
01066         i++;
01067       }
01068     }
01069     else
01070     {
01071       char buf[16];
01072       snprintf(buf, sizeof(buf), "%.6f", (*it)->crawl_time_);
01073       if(length < 0 || i < length)
01074         dirs.push_back(std::string(buf) + " " + 
01075                        ((*it)->zombie_ ? "* " : "  ") +
01076                        (*it)->path_);
01077       i++;
01078     }
01079     delete *it;
01080   }
01081 
01082   writeCache();
01083   return 0;
01084 }
01085 
01086 void
01087 Rosstackage::addStackage(const std::string& path)
01088 {
01089 #if !defined(BOOST_FILESYSTEM_VERSION) || (BOOST_FILESYSTEM_VERSION == 2)
01090   std::string name = fs::path(path).filename();
01091 #else
01092   // in boostfs3, filename() returns a path, which needs to be stringified
01093   std::string name = fs::path(path).filename().string();
01094 #endif
01095 
01096   if(stackages_.find(name) != stackages_.end())
01097   {
01098     dups_.insert(name);
01099     return;
01100   }
01101   fs::path manifest_path = fs::path(path) / manifest_name_;
01102   stackages_[name] = new Stackage(name, path, manifest_path.string());
01103 }
01104 
01105 void
01106 Rosstackage::crawlDetail(const std::string& path,
01107                          bool force,
01108                          int depth,
01109                          bool collect_profile_data,
01110                          std::vector<DirectoryCrawlRecord*>& profile_data,
01111                          std::tr1::unordered_set<std::string>& profile_hash)
01112 {
01113   if(depth > MAX_CRAWL_DEPTH)
01114     throw Exception("maximum depth exceeded during crawl");
01115 
01116   try
01117   {
01118     if(!fs::is_directory(path))
01119       return;
01120   }
01121   catch(fs::filesystem_error& e)
01122   {
01123     logWarn(std::string("error while looking at ") + path + ": " + e.what());
01124     return;
01125   }
01126 
01127   if(isStackage(path))
01128   {
01129     addStackage(path);
01130     return;
01131   }
01132 
01133   fs::path nosubdirs = fs::path(path) / ROSPACK_NOSUBDIRS;
01134   try
01135   {
01136     if(fs::is_regular_file(nosubdirs))
01137       return;
01138   }
01139   catch(fs::filesystem_error& e)
01140   {
01141     logWarn(std::string("error while looking for ") + nosubdirs.string() + ": " + e.what());
01142   }
01143 
01144   // We've already checked above whether CWD contains the kind of manifest
01145   // we're looking for.  Don't recurse if we encounter a rospack manifest,
01146   // to avoid having rosstack finding stacks inside packages, #3816.
01147   fs::path rospack_manifest = fs::path(path) / ROSPACK_MANIFEST_NAME;
01148   try
01149   {
01150     if(fs::is_regular_file(rospack_manifest))
01151       return;
01152   }
01153   catch(fs::filesystem_error& e)
01154   {
01155     logWarn(std::string("error while looking for ") + rospack_manifest.string() + ": " + e.what());
01156   }
01157 
01158   DirectoryCrawlRecord* dcr = NULL;
01159   if(collect_profile_data)
01160   {
01161     if(profile_hash.find(path) == profile_hash.end())
01162     {
01163       dcr = new DirectoryCrawlRecord(path,
01164                                      time_since_epoch(),
01165                                      stackages_.size());
01166       profile_data.push_back(dcr);
01167       profile_hash.insert(path);
01168     }
01169   }
01170 
01171   try
01172   {
01173     for(fs::directory_iterator dit = fs::directory_iterator(path);
01174         dit != fs::directory_iterator();
01175         ++dit)
01176     {
01177       if(fs::is_directory(dit->path()))
01178       {
01179 #if !defined(BOOST_FILESYSTEM_VERSION) || (BOOST_FILESYSTEM_VERSION == 2)
01180         std::string name = dit->path().filename();
01181 #else
01182         // in boostfs3, filename() returns a path, which needs to be stringified
01183         std::string name = dit->path().filename().string();
01184 #endif
01185         // Ignore directories starting with '.'
01186         if(name.size() == 0 || name[0] == '.')
01187           continue;
01188 
01189         crawlDetail(dit->path().string(), force, depth+1,
01190                     collect_profile_data, profile_data, profile_hash);
01191       }
01192     }
01193   }
01194   catch(fs::filesystem_error& e)
01195   {
01196     logWarn(std::string("error while crawling ") + path + ": " + e.what());
01197   }
01198 
01199   if(collect_profile_data && dcr != NULL)
01200   {
01201     // Measure the elapsed time
01202     dcr->crawl_time_ = time_since_epoch() - dcr->start_time_;
01203     // If the number of packages didn't change while crawling, 
01204     // then this directory is a zombie
01205     if(stackages_.size() == dcr->start_num_pkgs_)
01206       dcr->zombie_ = true;
01207   }
01208 }
01209 
01210 void
01211 Rosstackage::loadManifest(Stackage* stackage)
01212 {
01213   if(stackage->manifest_loaded_)
01214     return;
01215 
01216   if(!stackage->manifest_.LoadFile(stackage->manifest_path_))
01217   {
01218     std::string errmsg = std::string("error parsing manifest of package ") + 
01219             stackage->name_ + " at " + stackage->manifest_path_;
01220     throw Exception(errmsg);
01221   }
01222   stackage->manifest_loaded_ = true;
01223 }
01224 
01225 void
01226 Rosstackage::computeDeps(Stackage* stackage, bool ignore_errors)
01227 {
01228   if(stackage->deps_computed_)
01229     return;
01230 
01231   stackage->deps_computed_ = true;
01232 
01233   rospack_tinyxml::TiXmlElement* root;
01234   try
01235   {
01236     loadManifest(stackage);
01237     root = get_manifest_root(stackage);
01238   }
01239   catch(Exception& e)
01240   {
01241     if(ignore_errors)
01242       return;
01243     else
01244       throw e;
01245   }
01246   rospack_tinyxml::TiXmlNode *dep_node = NULL;
01247   while((dep_node = root->IterateChildren("depend", dep_node)))
01248   {
01249     rospack_tinyxml::TiXmlElement *dep_ele = dep_node->ToElement();
01250     const char* dep_pkgname = dep_ele->Attribute(tag_.c_str());
01251     if(!dep_pkgname)
01252     {
01253       if(!ignore_errors)
01254       {
01255         std::string errmsg = std::string("bad depend syntax (no 'package/stack' attribute) in manifest ") + stackage->name_ + " at " + stackage->manifest_path_;
01256         throw Exception(errmsg);
01257       }
01258     }
01259     else if(dep_pkgname == stackage->name_)
01260     {
01261       if(!ignore_errors)
01262       {
01263         std::string errmsg = std::string("package/stack ") + stackage->name_ + " depends on itself";
01264         throw Exception(errmsg);
01265       }
01266     }
01267     else if(!stackages_.count(dep_pkgname))
01268     {
01269       if(ignore_errors)
01270       {
01271         Stackage* dep =  new Stackage(dep_pkgname, "", "");
01272         stackage->deps_.push_back(dep);
01273       }
01274       else
01275       {
01276         std::string errmsg = std::string("package/stack ") + stackage->name_ + " depends on non-existent package " + dep_pkgname;
01277         throw Exception(errmsg);
01278       }
01279     }
01280     else
01281     {
01282       Stackage* dep = stackages_[dep_pkgname];
01283       stackage->deps_.push_back(dep);
01284       computeDeps(dep, ignore_errors);
01285     }
01286   }
01287 }
01288 
01289 void
01290 Rosstackage::gatherDeps(Stackage* stackage, bool direct, 
01291                         traversal_order_t order,
01292                         std::vector<Stackage*>& deps)
01293 {
01294   std::tr1::unordered_set<Stackage*> deps_hash;
01295   std::vector<std::string> indented_deps;
01296   gatherDepsFull(stackage, direct, order, 0, 
01297                  deps_hash, deps, false, indented_deps);
01298 }
01299 
01300 // Pre-condition: computeDeps(stackage) succeeded
01301 void
01302 Rosstackage::gatherDepsFull(Stackage* stackage, bool direct, 
01303                             traversal_order_t order, int depth, 
01304                             std::tr1::unordered_set<Stackage*>& deps_hash,
01305                             std::vector<Stackage*>& deps,
01306                             bool get_indented_deps,
01307                             std::vector<std::string>& indented_deps)
01308 {
01309   if(direct)
01310   {
01311     for(std::vector<Stackage*>::const_iterator it = stackage->deps_.begin();
01312         it != stackage->deps_.end();
01313         ++it)
01314       deps.push_back(*it);
01315     return;
01316   }
01317 
01318   if(depth > MAX_DEPENDENCY_DEPTH)
01319     throw Exception("maximum dependency depth exceeded (likely circular dependency)");
01320 
01321   for(std::vector<Stackage*>::const_iterator it = stackage->deps_.begin();
01322       it != stackage->deps_.end();
01323       ++it)
01324   {
01325     if(get_indented_deps)
01326     {
01327       std::string indented_dep;
01328       for(int i=0; i<depth; i++)
01329         indented_dep.append("  ");
01330       indented_dep.append((*it)->name_);
01331         indented_deps.push_back(indented_dep);
01332     }
01333 
01334     bool first = (deps_hash.find(*it) == deps_hash.end());
01335     if(first)
01336     {
01337       deps_hash.insert(*it);
01338       // We maintain the vector because the original rospack guaranteed
01339       // ordering in dep reporting.
01340       if(order == PREORDER)
01341         deps.push_back(*it);
01342     }
01343     // We always descend, even if we're encountering this stackage for the
01344     // nth time, so that we'll throw an error on recursive dependencies
01345     // (detected via max stack depth being exceeded).
01346     gatherDepsFull(*it, direct, order, depth+1, deps_hash, deps,
01347                    get_indented_deps, indented_deps);
01348     if(first)
01349     {
01350       if(order == POSTORDER)
01351         deps.push_back(*it);
01352     }
01353   }
01354 }
01355 
01356 std::string
01357 Rosstackage::getCachePath()
01358 {
01359   fs::path cache_path;
01360 
01361   char* ros_home = getenv("ROS_HOME");
01362   if(ros_home)
01363     cache_path = ros_home;
01364   else
01365   {
01366     // Get the user's home directory by looking up the password entry based
01367     // on UID.  If that doesn't work, we fall back on examining $HOME,
01368     // knowing that that can cause trouble when mixed with sudo (#2884).  
01369 #if defined(WIN32)
01370     char* home_drive = getenv("HOMEDRIVE");
01371     char* home_path = getenv("HOMEPATH");
01372     if(home_drive && home_path) 
01373       cache_path = fs::path(home_drive) / fs::path(home_path) / fs::path(DOTROS_NAME);
01374 #else // UNIX
01375     char* home_path;
01376     struct passwd* passwd_ent;
01377     // Look up based on effective UID, just in case we got here by set-uid
01378     if((passwd_ent = getpwuid(geteuid())))
01379       home_path = passwd_ent->pw_dir;
01380     else
01381       home_path = getenv("HOME");
01382     if(home_path)
01383       cache_path = fs::path(home_path) / fs::path(DOTROS_NAME);
01384 #endif
01385   }
01386 
01387   // If it doesn't exist, create the directory that will hold the cache
01388   try
01389   {
01390     if(!fs::is_directory(cache_path))
01391     {
01392       fs::create_directory(cache_path);
01393     }
01394   }
01395   catch(fs::filesystem_error& e)
01396   {
01397     logWarn(std::string("cannot create rospack cache directory ") +
01398             cache_path.string() + ": " + e.what());
01399   }
01400   cache_path /= cache_name_;
01401   return cache_path.string();
01402 }
01403 
01404 bool
01405 Rosstackage::readCache()
01406 {
01407   FILE* cache = validateCache();
01408   if(cache)
01409   {
01410     char linebuf[30000];
01411     for(;;)
01412     {
01413       if (!fgets(linebuf, sizeof(linebuf), cache))
01414         break; // error in read operation
01415       if (linebuf[0] == '#')
01416         continue;
01417       char* newline_pos = strchr(linebuf, '\n');
01418       if(newline_pos)
01419         *newline_pos = 0;
01420       addStackage(linebuf);
01421     }
01422     fclose(cache);
01423     return true;
01424   }
01425   else
01426     return false;
01427 }
01428 
01429 // TODO: replace the contents of the method with some fancy cross-platform
01430 // boost thing.
01431 void
01432 Rosstackage::writeCache()
01433 {
01434   // Write the results of this crawl to the cache file.  At each step, give
01435   // up on error, printing a warning to stderr.
01436   std::string cache_path = getCachePath();
01437   if(!cache_path.size())
01438   {
01439     logWarn("no location available to write cache file. Try setting ROS_HOME or HOME.");
01440   }
01441   else
01442   {
01443     char tmp_cache_dir[PATH_MAX];
01444     char tmp_cache_path[PATH_MAX];
01445     strncpy(tmp_cache_dir, cache_path.c_str(), sizeof(tmp_cache_dir));
01446 #if defined(_MSC_VER)
01447     // No dirname on Windows; use _splitpath_s instead
01448     char drive[_MAX_DRIVE], dir[_MAX_DIR], fname[_MAX_FNAME], ext[_MAX_EXT];
01449     _splitpath_s(tmp_cache_dir, drive, _MAX_DRIVE, dir, _MAX_DIR, fname, _MAX_FNAME,
01450                  ext, _MAX_EXT);
01451     char full_dir[_MAX_DRIVE + _MAX_DIR];
01452     _makepath_s(full_dir, _MAX_DRIVE + _MAX_DIR, drive, dir, NULL, NULL);
01453     snprintf(tmp_cache_path, sizeof(tmp_cache_path), "%s\\.rospack_cache.XXXXXX", full_dir);
01454 #elif defined(__MINGW32__)
01455     char* temp_name = tempnam(dirname(tmp_cache_dir),".rospack_cache.");
01456     snprintf(tmp_cache_path, sizeof(tmp_cache_path), temp_name);
01457     delete temp_name;
01458 #else
01459     snprintf(tmp_cache_path, sizeof(tmp_cache_path), "%s/.rospack_cache.XXXXXX", dirname(tmp_cache_dir));
01460 #endif
01461 #if defined(__MINGW32__)
01462     // There is no equivalent of mkstemp or _mktemp_s on mingw, so we resort to a slightly problematic
01463     // tempnam (above) and mktemp method. This has the miniscule chance of a race condition.
01464     int fd = open(tmp_cache_path, O_RDWR | O_EXCL | _O_CREAT, 0644);
01465     if (fd < 0)
01466     {
01467       logWarn(std::string("unable to create temporary cache file ") +
01468                    tmp_cache_path, true);
01469     }
01470     else
01471     {
01472       FILE *cache = fdopen(fd, "w");
01473 #elif defined(WIN32)
01474     if (_mktemp_s(tmp_cache_path, PATH_MAX) != 0)
01475     {
01476       fprintf(stderr,
01477               "[rospack] Unable to generate temporary cache file name: %u",
01478               GetLastError());
01479     }
01480     else
01481     {
01482       FILE *cache = fopen(tmp_cache_path, "w");
01483 #else
01484     int fd = mkstemp(tmp_cache_path);
01485     if (fd < 0)
01486     {
01487       fprintf(stderr, "[rospack] Unable to create temporary cache file %s: %s\n", 
01488               tmp_cache_path, strerror(errno));
01489     }
01490     else
01491     {
01492       FILE *cache = fdopen(fd, "w");
01493 #endif
01494       if (!cache)
01495       {
01496         fprintf(stderr, "[rospack] Unable open cache file %s: %s\n", 
01497                 tmp_cache_path, strerror(errno));
01498       }
01499       else
01500       {
01501         // TODO: remove writing of ROS_ROOT
01502         char *rr = getenv("ROS_ROOT");
01503         fprintf(cache, "#ROS_ROOT=%s\n", (rr ? rr : ""));
01504 
01505         char *rpp = getenv("ROS_PACKAGE_PATH");
01506         fprintf(cache, "#ROS_PACKAGE_PATH=%s\n", (rpp ? rpp : ""));
01507         for(std::tr1::unordered_map<std::string, Stackage*>::const_iterator it = stackages_.begin();
01508             it != stackages_.end();
01509             ++it)
01510           fprintf(cache, "%s\n", it->second->path_.c_str());
01511         fclose(cache);
01512         if(fs::exists(cache_path))
01513           remove(cache_path.c_str());
01514         if(rename(tmp_cache_path, cache_path.c_str()) < 0)
01515         {
01516           fprintf(stderr, "[rospack] Error: failed to rename cache file %s to %s: %s\n", 
01517                   tmp_cache_path, cache_path.c_str(), strerror(errno));
01518         }
01519       }
01520     }
01521   }
01522 }
01523 
01524 FILE*
01525 Rosstackage::validateCache()
01526 {
01527   std::string cache_path = getCachePath();
01528   // first see if it's new enough
01529   double cache_max_age = DEFAULT_MAX_CACHE_AGE;
01530   const char *user_cache_time_str = getenv("ROS_CACHE_TIMEOUT");
01531   if(user_cache_time_str)
01532     cache_max_age = atof(user_cache_time_str);
01533   if(cache_max_age == 0.0)
01534     return NULL;
01535   struct stat s;
01536   if(stat(cache_path.c_str(), &s) == 0)
01537   {
01538     double dt = difftime(time(NULL), s.st_mtime);
01539     // Negative cache_max_age means it's always new enough.  It's dangerous
01540     // for the user to set this, but rosbash uses it.
01541     if ((cache_max_age > 0.0) && (dt > cache_max_age))
01542       return NULL;
01543   }
01544   // try to open it 
01545   FILE* cache = fopen(cache_path.c_str(), "r");
01546   if(!cache)
01547     return NULL; // it's not readable by us. sad.
01548 
01549   // see if ROS_PACKAGE_PATH matches
01550   char linebuf[30000];
01551   bool ros_root_ok = false;
01552   bool ros_package_path_ok = false;
01553   // TODO: remove ROS_ROOT
01554   const char* ros_root = getenv("ROS_ROOT");
01555   const char* ros_package_path = getenv("ROS_PACKAGE_PATH");
01556   for(;;)
01557   {
01558     if(!fgets(linebuf, sizeof(linebuf), cache))
01559       break;
01560     linebuf[strlen(linebuf)-1] = 0; // get rid of trailing newline
01561     if (linebuf[0] == '#')
01562     {
01563       if (!strncmp("#ROS_ROOT=", linebuf, 10))
01564       {
01565         if(!ros_root)
01566         {
01567           if(!strlen(linebuf+10))
01568             ros_root_ok = true;
01569         }
01570         else if (!strcmp(linebuf+10, ros_root))
01571           ros_root_ok = true;
01572       }
01573       else if(!strncmp("#ROS_PACKAGE_PATH=", linebuf, 18))
01574       {
01575         if(!ros_package_path)
01576         {
01577           if(!strlen(linebuf+18))
01578             ros_package_path_ok = true;
01579         }
01580         else if(!strcmp(linebuf+18, ros_package_path))
01581           ros_package_path_ok = true;
01582       }
01583     }
01584     else
01585       break; // we're out of the header. nothing more matters to this check.
01586   }
01587   if(ros_root_ok && ros_package_path_ok)
01588   {
01589     // seek to the beginning and pass back the stream (instead of closing
01590     // and later reopening, which is a race condition, #1666)
01591     fseek(cache, 0, SEEK_SET);
01592     return cache;
01593   }
01594   else
01595   {
01596     fclose(cache);
01597     return NULL;
01598   }
01599 }
01600 
01601 bool
01602 Rosstackage::expandExportString(Stackage* stackage,
01603                                 const std::string& instring,
01604                                 std::string& outstring)
01605 {
01606   outstring = instring;
01607   for(std::string::size_type i = outstring.find(MANIFEST_PREFIX);
01608       i != std::string::npos;
01609       i = outstring.find(MANIFEST_PREFIX))
01610   {
01611     outstring.replace(i, std::string(MANIFEST_PREFIX).length(), 
01612                       stackage->path_);
01613   }
01614   
01615   // Do backquote substitution.  E.g.,  if we find this string:
01616   //   `pkg-config --cflags gdk-pixbuf-2.0`
01617   // We replace it with the result of executing the command
01618   // contained within the backquotes (reading from its stdout), which
01619   // might be something like:
01620   //   -I/usr/include/gtk-2.0 -I/usr/include/glib-2.0 -I/usr/lib/glib-2.0/include
01621 
01622   // Construct and execute the string
01623   // We do the assignment first to ensure that if backquote expansion (or
01624   // anything else) fails, we'll get a non-zero exit status from pclose().
01625   std::string cmd = std::string("ret=\"") + outstring + "\" && echo $ret";
01626 
01627   // Remove embedded newlines
01628   std::string token("\n");
01629   for (std::string::size_type s = cmd.find(token); 
01630        s != std::string::npos;
01631        s = cmd.find(token, s))
01632     cmd.replace(s,token.length(),std::string(" "));
01633 
01634   FILE* p;
01635   if(!(p = popen(cmd.c_str(), "r")))
01636   {
01637     std::string errmsg = 
01638             std::string("failed to execute backquote expression ") +
01639             cmd + " in " +
01640             stackage->manifest_path_;
01641     logWarn(errmsg, true);
01642     return false;
01643   }
01644   else
01645   {
01646     char buf[8192];
01647     memset(buf,0,sizeof(buf));
01648     // Read the command's output
01649     do
01650     {
01651       clearerr(p);
01652       while(fgets(buf + strlen(buf),sizeof(buf)-strlen(buf)-1,p));
01653     } while(ferror(p) && errno == EINTR);
01654     // Close the subprocess, checking exit status
01655     if(pclose(p) != 0)
01656     {
01657       std::string errmsg = 
01658               std::string("got non-zero exit status from executing backquote expression ") +
01659               cmd + " in " +
01660               stackage->manifest_path_;
01661       return false;
01662     }
01663     else
01664     {
01665       // Strip trailing newline, which was added by our call to echo
01666       buf[strlen(buf)-1] = '\0';
01667       // Replace the backquote expression with the new text
01668       outstring = buf;
01669     }
01670   }
01671 
01672   return true;
01673 }
01674 
01676 // Rospack methods
01678 Rospack::Rospack() :
01679         Rosstackage(ROSPACK_MANIFEST_NAME,
01680                     ROSPACK_CACHE_NAME,
01681                     ROSPACK_NAME,
01682                     MANIFEST_TAG_PACKAGE)
01683 {
01684 }
01685 
01686 Rosstackage::~Rosstackage()
01687 {
01688   for(std::tr1::unordered_map<std::string, Stackage*>::const_iterator it = stackages_.begin();
01689       it != stackages_.end();
01690       ++it)
01691   {
01692     delete it->second;
01693   }
01694 }
01695 
01696 const char* 
01697 Rospack::usage()
01698 {
01699   return "USAGE: rospack <command> [options] [package]\n"
01700           "  Allowed commands:\n"
01701           "    help\n"
01702           "    cflags-only-I     [--deps-only] [package]\n"
01703           "    cflags-only-other [--deps-only] [package]\n"
01704           "    depends           [package] (alias: deps)\n"
01705           "    depends-indent    [package] (alias: deps-indent)\n"
01706           "    depends-manifests [package] (alias: deps-manifests)\n"
01707           "    depends-msgsrv    [package] (alias: deps-msgsrv)\n"
01708           "    depends-on        [package]\n"
01709           "    depends-on1       [package]\n"
01710           "    depends-why --target=<target> [package] (alias: deps-why)\n"
01711           "    depends1          [package] (alias: deps1)\n"
01712           "    export [--deps-only] --lang=<lang> --attrib=<attrib> [package]\n"
01713           "    find [package]\n"
01714           "    langs\n"
01715           "    libs-only-L     [--deps-only] [package]\n"
01716           "    libs-only-l     [--deps-only] [package]\n"
01717           "    libs-only-other [--deps-only] [package]\n"
01718           "    list\n"
01719           "    list-duplicates\n"
01720           "    list-names\n"
01721           "    plugins --attrib=<attrib> [--top=<toppkg>] [package]\n"
01722           "    profile [--length=<length>] [--zombie-only]\n"
01723           "    rosdep  [package] (alias: rosdeps)\n"
01724           "    rosdep0 [package] (alias: rosdeps0)\n"
01725           "    vcs  [package]\n"
01726           "    vcs0 [package]\n"
01727           "  Extra options:\n"
01728           "    -q     Quiets error reports.\n\n"
01729           " If [package] is omitted, the current working directory\n"
01730           " is used (if it contains a manifest.xml).\n\n";
01731 }
01732 
01734 // Rosstack methods
01736 Rosstack::Rosstack() :
01737         Rosstackage(ROSSTACK_MANIFEST_NAME,
01738                     ROSSTACK_CACHE_NAME,
01739                     ROSSTACK_NAME,
01740                     MANIFEST_TAG_STACK)
01741 {
01742 }
01743 
01744 const char* 
01745 Rosstack::usage()
01746 {
01747   return "USAGE: rosstack [options] <command> [stack]\n"
01748           "  Allowed commands:\n"
01749           "    help\n"
01750           "    find [stack]\n"
01751           "    contents [stack]\n"
01752           "    list\n"
01753           "    list-names\n"
01754           "    depends [stack] (alias: deps)\n"
01755           "    depends-manifests [stack] (alias: deps-manifests)\n"
01756           "    depends1 [stack] (alias: deps1)\n"
01757           "    depends-indent [stack] (alias: deps-indent)\n"
01758           "    depends-why --target=<target> [stack] (alias: deps-why)\n"
01759           "    depends-on [stack]\n"
01760           "    depends-on1 [stack]\n"
01761           "    contains [package]\n"
01762           "    contains-path [package]\n"
01763           "    profile [--length=<length>] \n\n"
01764           " If [stack] is omitted, the current working directory\n"
01765           " is used (if it contains a stack.xml).\n\n";
01766 }
01767 
01768 rospack_tinyxml::TiXmlElement*
01769 get_manifest_root(Stackage* stackage)
01770 {
01771   rospack_tinyxml::TiXmlElement* ele = stackage->manifest_.RootElement();
01772   if(!ele)
01773   {
01774     std::string errmsg = std::string("error parsing manifest of package ") + 
01775             stackage->name_ + " at " + stackage->manifest_path_;
01776     throw Exception(errmsg);
01777   }
01778   return ele;
01779 }
01780 
01781 double 
01782 time_since_epoch()
01783 {
01784 #if defined(WIN32)
01785   #if defined(_MSC_VER) || defined(_MSC_EXTENSIONS)
01786     #define DELTA_EPOCH_IN_MICROSECS  11644473600000000Ui64
01787   #else
01788     #define DELTA_EPOCH_IN_MICROSECS  11644473600000000ULL
01789   #endif
01790   FILETIME ft;
01791   unsigned __int64 tmpres = 0;
01792 
01793   GetSystemTimeAsFileTime(&ft);
01794   tmpres |= ft.dwHighDateTime;
01795   tmpres <<= 32;
01796   tmpres |= ft.dwLowDateTime;
01797   tmpres /= 10;
01798   tmpres -= DELTA_EPOCH_IN_MICROSECS;
01799   return static_cast<double>(tmpres) / 1e6;
01800 #else
01801   struct timeval tod;
01802   gettimeofday(&tod, NULL);
01803   return tod.tv_sec + 1e-6 * tod.tv_usec;
01804 #endif
01805 }
01806 
01807 
01808 
01809 } // namespace rospack


rospack
Author(s): Brian Gerkey/gerkey@willowgarage.com, Morgan Quigley/mquigley@cs.stanford.edu
autogenerated on Fri Jan 3 2014 11:51:40