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.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 <fcntl.h>  // for O_RDWR, O_EXCL, O_CREAT
00040   // simple workaround - could have issues though. See
00041   //   http://stackoverflow.com/questions/2915672/snprintf-and-visual-studio-2010
00042   // for potentially better solutions. Similar probably applies for some of the others
00043   #define snprintf _snprintf
00044   #define pclose _pclose
00045   #define popen _popen
00046   #define PATH_MAX MAX_PATH
00047   #if defined(__MINGW32__)
00048     #include <libgen.h> // for dirname
00049   #endif
00050   #if defined(_MSC_VER)
00051     #include <io.h> // _mktemp_s
00052   #endif
00053 #else //!defined(WIN32)
00054   #include <sys/types.h>
00055   #include <libgen.h>
00056   #include <pwd.h>
00057   #include <unistd.h>
00058   #include <sys/time.h>
00059 #endif
00060 
00061 #include <algorithm>
00062 #include <climits>
00063 
00064 #include <sys/stat.h>
00065 #include <stdio.h>
00066 #include <stdlib.h>
00067 #include <time.h>
00068 #include <string.h>
00069 #include <errno.h>
00070 
00071 #include <Python.h>
00072 
00073 /* re-define some String functions for recent python (>= 3.0) */
00074 #if PY_VERSION_HEX >= 0x03000000
00075 #define PyString_AsString PyBytes_AsString
00076 #define PyString_FromString PyBytes_FromString
00077 #endif
00078 
00079 // TODO:
00080 //   recrawl on:
00081 //     package not found in cache
00082 //     package found in cache, but no manifest.xml present in filesystem
00083 
00084 namespace fs = boost::filesystem;
00085 
00086 namespace rospack
00087 {
00088 static const char* MANIFEST_TAG_PACKAGE = "package";
00089 static const char* MANIFEST_TAG_STACK = "stack";
00090 static const char* ROSPACK_MANIFEST_NAME = "manifest.xml";
00091 static const char* ROSPACKAGE_MANIFEST_NAME = "package.xml";
00092 static const char* ROSSTACK_MANIFEST_NAME = "stack.xml";
00093 static const char* ROSPACK_CACHE_NAME = "rospack_cache";
00094 static const char* ROSSTACK_CACHE_NAME = "rosstack_cache";
00095 static const char* ROSPACK_NOSUBDIRS = "rospack_nosubdirs";
00096 static const char* CATKIN_IGNORE = "CATKIN_IGNORE";
00097 static const char* DOTROS_NAME = ".ros";
00098 static const char* MSG_GEN_GENERATED_DIR = "msg_gen";
00099 static const char* MSG_GEN_GENERATED_FILE = "generated";
00100 static const char* SRV_GEN_GENERATED_DIR = "srv_gen";
00101 static const char* SRV_GEN_GENERATED_FILE = "generated";
00102 static const char* MANIFEST_TAG_ROSDEP = "rosdep";
00103 static const char* MANIFEST_TAG_VERSIONCONTROL = "versioncontrol";
00104 static const char* MANIFEST_TAG_EXPORT = "export";
00105 static const char* MANIFEST_ATTR_NAME = "name";
00106 static const char* MANIFEST_ATTR_TYPE = "type";
00107 static const char* MANIFEST_ATTR_URL = "url";
00108 static const char* MANIFEST_PREFIX = "${prefix}";
00109 static const int MAX_CRAWL_DEPTH = 1000;
00110 static const int MAX_DEPENDENCY_DEPTH = 1000;
00111 static const double DEFAULT_MAX_CACHE_AGE = 60.0;
00112 
00113 TiXmlElement* get_manifest_root(Stackage* stackage);
00114 double time_since_epoch();
00115 
00116 #ifdef __APPLE__
00117   static const std::string g_ros_os = "osx";
00118 #else
00119   #if defined(WIN32)
00120     static const std::string g_ros_os = "win32";
00121   #else
00122     static const std::string g_ros_os = "linux";
00123   #endif
00124 #endif
00125 
00126 class Exception : public std::runtime_error
00127 {
00128   public:
00129     Exception(const std::string& what)
00130             : std::runtime_error(what)
00131     {}
00132 };
00133 
00134 class Stackage
00135 {
00136   public:
00137     // \brief name of the stackage
00138     std::string name_;
00139     // \brief absolute path to the stackage
00140     std::string path_;
00141     // \brief absolute path to the stackage manifest
00142     std::string manifest_path_;
00143     // \brief filename of the stackage manifest
00144     std::string manifest_name_;
00145     // \brief have we already loaded the manifest?
00146     bool manifest_loaded_;
00147     // \brief TinyXML structure, filled in during parsing
00148     TiXmlDocument manifest_;
00149     std::vector<Stackage*> deps_;
00150     bool deps_computed_;
00151     bool is_wet_package_;
00152     bool is_metapackage_;
00153 
00154     Stackage(const std::string& name,
00155              const std::string& path,
00156              const std::string& manifest_path,
00157              const std::string& manifest_name) :
00158             name_(name),
00159             path_(path),
00160             manifest_path_(manifest_path),
00161             manifest_name_(manifest_name),
00162             manifest_loaded_(false),
00163             deps_computed_(false),
00164             is_metapackage_(false)
00165     {
00166       is_wet_package_ = manifest_name_ == ROSPACKAGE_MANIFEST_NAME;
00167     }
00168 
00169     void update_wet_information()
00170     {
00171       assert(is_wet_package_);
00172       assert(manifest_loaded_);
00173       // get name from package.xml instead of folder name
00174       TiXmlElement* root = get_manifest_root(this);
00175       for(TiXmlElement* el = root->FirstChildElement("name"); el; el = el->NextSiblingElement("name"))
00176       {
00177         name_ = el->GetText();
00178         break;
00179       }
00180       // check if package is a metapackage
00181       for(TiXmlElement* el = root->FirstChildElement("export"); el; el = el->NextSiblingElement("export"))
00182       {
00183         if(el->FirstChildElement("metapackage"))
00184         {
00185           is_metapackage_ = true;
00186           break;
00187         }
00188       }
00189     }
00190 
00191     bool isStack() const
00192     {
00193       return manifest_name_ == MANIFEST_TAG_STACK || (is_wet_package_ && is_metapackage_);
00194     }
00195 
00196     bool isPackage() const
00197     {
00198       return manifest_name_ == MANIFEST_TAG_PACKAGE || (is_wet_package_ && !is_metapackage_);
00199     }
00200 
00201 };
00202 
00203 class DirectoryCrawlRecord
00204 {
00205   public:
00206     std::string path_;
00207     bool zombie_;
00208     double start_time_;
00209     double crawl_time_;
00210     size_t start_num_pkgs_;
00211     DirectoryCrawlRecord(std::string path, 
00212                          double start_time, 
00213                          size_t start_num_pkgs) :
00214             path_(path),
00215             zombie_(false),
00216             start_time_(start_time),
00217             crawl_time_(0.0),
00218             start_num_pkgs_(start_num_pkgs) {}
00219 };
00220 bool cmpDirectoryCrawlRecord(DirectoryCrawlRecord* i,
00221                              DirectoryCrawlRecord* j)
00222 {
00223   return (i->crawl_time_ < j->crawl_time_);
00224 }
00225 
00227 // Rosstackage methods (public/protected)
00229 Rosstackage::Rosstackage(const std::string& manifest_name,
00230                          const std::string& cache_name,
00231                          const std::string& name,
00232                          const std::string& tag) :
00233         manifest_name_(manifest_name),
00234         cache_name_(cache_name),
00235         crawled_(false),
00236         name_(name),
00237         tag_(tag)
00238 {
00239 }
00240 
00241 void 
00242 Rosstackage::logWarn(const std::string& msg,
00243                      bool append_errno)
00244 {
00245   log("Warning", msg, append_errno);
00246 }
00247 void
00248 Rosstackage::logError(const std::string& msg,
00249                       bool append_errno)
00250 {
00251   log("Error", msg, append_errno);
00252 }
00253 
00254 bool
00255 Rosstackage::getSearchPathFromEnv(std::vector<std::string>& sp)
00256 {
00257   char* rr = getenv("ROS_ROOT");
00258   char* rpp = getenv("ROS_PACKAGE_PATH");
00259 
00260   // ROS_ROOT is optional, and will be phased out
00261   if(rr)
00262   {
00263     try 
00264     {
00265       if(fs::is_directory(rr))
00266         sp.push_back(rr);
00267       else
00268         logWarn(std::string("ROS_ROOT=") + rr + " is not a directory");
00269     }
00270     catch(fs::filesystem_error& e)
00271     {
00272       logWarn(std::string("error while looking at ROS_ROOT ") + rr + ": " + e.what());
00273     }
00274   }
00275   if(rpp)
00276   {
00277     // I can't see that boost filesystem has an elegant cross platform
00278     // representation for this anywhere like qt/python have.
00279     #if defined(WIN32)
00280       const char *path_delim = ";";
00281     #else //!defined(WIN32)
00282       const char *path_delim = ":";
00283     #endif
00284 
00285     std::vector<std::string> rpp_strings;
00286     boost::split(rpp_strings, rpp, 
00287                  boost::is_any_of(path_delim),
00288                  boost::token_compress_on);
00289     for(std::vector<std::string>::const_iterator it = rpp_strings.begin();
00290         it != rpp_strings.end();
00291         ++it)
00292     {
00293       sp.push_back(*it);
00294     }
00295   }
00296   return true;
00297 }
00298 
00299 void
00300 Rosstackage::setQuiet(bool quiet)
00301 {
00302   quiet_ = quiet;
00303 }
00304 
00305 bool
00306 Rosstackage::isStackage(const std::string& path)
00307 {
00308   try
00309   {
00310     if(!fs::is_directory(path))
00311       return false;
00312   }
00313   catch(fs::filesystem_error& e)
00314   {
00315     logWarn(std::string("error while looking at ") + path + ": " + e.what());
00316     return false;
00317   }
00318 
00319   try
00320   {
00321     for(fs::directory_iterator dit = fs::directory_iterator(path);
00322         dit != fs::directory_iterator();
00323         ++dit)
00324     {
00325       if(!fs::is_regular_file(dit->path()))
00326         continue;
00327 
00328       if(dit->path().filename() == manifest_name_)
00329         return true;
00330 
00331       // finding a package.xml is acceptable
00332       if(dit->path().filename() == ROSPACKAGE_MANIFEST_NAME)
00333         return true;
00334     }
00335   }
00336   catch(fs::filesystem_error& e)
00337   {
00338     logWarn(std::string("error while crawling ") + path + ": " + e.what());
00339   }
00340   return false;
00341 }
00342 
00343 void
00344 Rosstackage::crawl(std::vector<std::string> search_path,
00345                    bool force)
00346 {
00347   if(!force)
00348   {
00349     if(readCache())
00350     {
00351       // If the cache was valid, then the paths in the cache match the ones
00352       // we've been asked to crawl.  Store them, so that later, methods
00353       // like find() can refer to them when recrawling.
00354       search_paths_.clear();
00355       for(std::vector<std::string>::const_iterator it = search_path.begin();
00356           it != search_path.end();
00357           ++it)
00358         search_paths_.push_back(*it);
00359       return;
00360     }
00361 
00362     if(crawled_)
00363     {
00364       bool same_paths = true;
00365       if(search_paths_.size() != search_path.size())
00366         same_paths = false;
00367       else
00368       {
00369         for(unsigned int i=0; i<search_paths_.size(); i++)
00370         {
00371           if(search_paths_[i] != search_path[i])
00372           {
00373             same_paths = false;
00374             break;
00375           }
00376         }
00377       }
00378 
00379       if(same_paths)
00380         return;
00381     }
00382   }
00383 
00384 
00385   std::tr1::unordered_map<std::string, Stackage*>::const_iterator it = stackages_.begin();
00386   while(it != stackages_.end())
00387   {
00388     delete it->second;
00389     it = stackages_.erase(it);
00390   }
00391   dups_.clear();
00392   search_paths_.clear();
00393   for(std::vector<std::string>::const_iterator it = search_path.begin();
00394       it != search_path.end();
00395       ++it)
00396     search_paths_.push_back(*it);
00397 
00398   std::vector<DirectoryCrawlRecord*> dummy;
00399   std::tr1::unordered_set<std::string> dummy2;
00400   for(std::vector<std::string>::const_iterator p = search_paths_.begin();
00401       p != search_paths_.end();
00402       ++p)
00403     crawlDetail(*p, force, 1, false, dummy, dummy2);
00404   
00405   crawled_ = true;
00406 
00407   writeCache();
00408 }
00409 
00410 bool 
00411 Rosstackage::inStackage(std::string& name)
00412 {
00413   fs::path path;
00414   try
00415   {
00416     // Search upward, as suggested in #3697.  This method is only used when
00417     // a package is not given on the command-line, and so should not have
00418     // performance impact in common usage.
00419     for(fs::path path = fs::current_path();
00420         !path.empty();
00421         path = path.parent_path())
00422     {
00423       if(Rosstackage::isStackage(path.string()))
00424       {
00425 #if !defined(BOOST_FILESYSTEM_VERSION) || (BOOST_FILESYSTEM_VERSION == 2)
00426         name = fs::path(path).filename();
00427 #else
00428         // in boostfs3, filename() returns a path, which needs to be stringified
00429         name = fs::path(path).filename().string();
00430 #endif
00431         return true;
00432       }
00433     }
00434     // Search failed.
00435     return false;
00436   }
00437   catch(fs::filesystem_error& e)
00438   {
00439     // can't determine current directory, or encountered trouble while
00440     // searching upward; too bad
00441     return false;
00442   }
00443 }
00444 
00445 
00446 bool
00447 Rosstackage::find(const std::string& name, std::string& path)
00448 {
00449   Stackage* s = findWithRecrawl(name);
00450   if(s)
00451   {
00452     path = s->path_;
00453     return true;
00454   }
00455   else
00456     return false;
00457 }
00458 
00459 bool
00460 Rosstackage::contents(const std::string& name, 
00461                       std::set<std::string>& packages)
00462 {
00463   Rospack rp2;
00464   std::tr1::unordered_map<std::string, Stackage*>::const_iterator it = stackages_.find(name);
00465   if(it != stackages_.end())
00466   {
00467     std::vector<std::string> search_paths;
00468     search_paths.push_back(it->second->path_);
00469     rp2.crawl(search_paths, true);
00470     std::set<std::pair<std::string, std::string> > names_paths;
00471     rp2.list(names_paths);
00472     for(std::set<std::pair<std::string, std::string> >::const_iterator iit = names_paths.begin();
00473         iit != names_paths.end();
00474         ++iit)
00475       packages.insert(iit->first);
00476     return true;
00477   }
00478   else
00479   {
00480     logError(std::string("stack ") + name + " not found");
00481     return false;
00482   }
00483 }
00484 
00485 bool
00486 Rosstackage::contains(const std::string& name, 
00487                       std::string& stack,
00488                       std::string& path)
00489 {
00490   Rospack rp2;
00491   for(std::tr1::unordered_map<std::string, Stackage*>::const_iterator it = stackages_.begin();
00492       it != stackages_.end();
00493       ++it)
00494   {
00495     std::vector<std::string> search_paths;
00496     search_paths.push_back(it->second->path_);
00497     rp2.crawl(search_paths, true);
00498     std::set<std::pair<std::string, std::string> > names_paths;
00499     rp2.list(names_paths);
00500     for(std::set<std::pair<std::string, std::string> >::const_iterator iit = names_paths.begin();
00501         iit != names_paths.end();
00502         ++iit)
00503     {
00504       if(iit->first == name)
00505       {
00506         stack = it->first;
00507         path = it->second->path_;
00508         return true;
00509       }
00510     }
00511   }
00512 
00513   logError(std::string("stack containing package ") + name + " not found");
00514   return false;
00515 }
00516 
00517 void 
00518 Rosstackage::list(std::set<std::pair<std::string, std::string> >& list)
00519 {
00520   for(std::tr1::unordered_map<std::string, Stackage*>::const_iterator it = stackages_.begin();
00521       it != stackages_.end();
00522       ++it)
00523   {
00524     std::pair<std::string, std::string> item; 
00525     item.first = it->first; 
00526     item.second = it->second->path_; 
00527     list.insert(item); 
00528   }
00529 }
00530 
00531 void 
00532 Rosstackage::listDuplicates(std::vector<std::string>& dups)
00533 {
00534   dups.resize(dups_.size());
00535   int i = 0;
00536   for(std::tr1::unordered_map<std::string, std::vector<std::string> >::const_iterator it = dups_.begin();
00537       it != dups_.end();
00538       ++it)
00539   {
00540     dups[i] = it->first;
00541     i++;
00542   }
00543 }
00544 
00545 void
00546 Rosstackage::listDuplicatesWithPaths(std::map<std::string, std::vector<std::string> >& dups)
00547 {
00548   dups.clear();
00549   for(std::tr1::unordered_map<std::string, std::vector<std::string> >::const_iterator it = dups_.begin();
00550       it != dups_.end();
00551       ++it)
00552   {
00553     dups[it->first].resize(it->second.size());
00554     int j = 0;
00555     for(std::vector<std::string>::const_iterator jt = it->second.begin();
00556         jt != it->second.end();
00557         ++jt)
00558     {
00559       dups[it->first][j] = *jt;
00560       j++;
00561     }
00562   }
00563 }
00564 
00565 bool
00566 Rosstackage::deps(const std::string& name, bool direct,
00567                   std::vector<std::string>& deps)
00568 {
00569   std::vector<Stackage*> stackages;
00570   // Disable errors for the first try
00571   bool old_quiet = quiet_;
00572   setQuiet(true);
00573   if(!depsDetail(name, direct, stackages))
00574   {
00575     // Recrawl
00576     crawl(search_paths_, true);
00577     stackages.clear();
00578     setQuiet(old_quiet);
00579     if(!depsDetail(name, direct, stackages))
00580       return false;
00581   }
00582   setQuiet(old_quiet);
00583   for(std::vector<Stackage*>::const_iterator it = stackages.begin();
00584       it != stackages.end();
00585       ++it)
00586     deps.push_back((*it)->name_);
00587   return true;
00588 }
00589 
00590 bool
00591 Rosstackage::depsOn(const std::string& name, bool direct,
00592                        std::vector<std::string>& deps)
00593 {
00594   std::vector<Stackage*> stackages;
00595   if(!depsOnDetail(name, direct, stackages))
00596     return false;
00597   for(std::vector<Stackage*>::const_iterator it = stackages.begin();
00598       it != stackages.end();
00599       ++it)
00600     deps.push_back((*it)->name_);
00601   return true;
00602 }
00603 
00604 bool
00605 Rosstackage::depsIndent(const std::string& name, bool direct,
00606                         std::vector<std::string>& deps)
00607 {
00608   Stackage* stackage = findWithRecrawl(name);
00609   if(!stackage)
00610     return false;
00611   try
00612   {
00613     computeDeps(stackage);
00614     std::vector<Stackage*> deps_vec;
00615     std::tr1::unordered_set<Stackage*> deps_hash;
00616     std::vector<std::string> indented_deps;
00617     gatherDepsFull(stackage, direct, POSTORDER, 0, deps_hash, deps_vec, true, indented_deps);
00618     for(std::vector<std::string>::const_iterator it = indented_deps.begin();
00619         it != indented_deps.end();
00620         ++it)
00621       deps.push_back(*it);
00622   }
00623   catch(Exception& e)
00624   {
00625     logError(e.what());
00626     return false;
00627   }
00628   return true;
00629 }
00630 
00631 bool
00632 Rosstackage::depsWhy(const std::string& from,
00633                      const std::string& to,
00634                      std::string& output)
00635 {
00636   Stackage* from_s = findWithRecrawl(from);
00637   if(!from_s)
00638     return false;
00639   Stackage* to_s = findWithRecrawl(to);
00640   if(!to_s)
00641     return false;
00642 
00643   std::list<std::list<Stackage*> > acc_list;
00644   try
00645   {
00646     depsWhyDetail(from_s, to_s, acc_list);
00647   }
00648   catch(Exception& e)
00649   {
00650     logError(e.what());
00651     return true;
00652   }
00653   output.append(std::string("Dependency chains from ") + 
00654                 from + " to " + to + ":\n");
00655   for(std::list<std::list<Stackage*> >::const_iterator it = acc_list.begin();
00656       it != acc_list.end();
00657       ++it)
00658   {
00659     output.append("* ");
00660     for(std::list<Stackage*>::const_iterator iit = it->begin();
00661         iit != it->end();
00662         ++iit)
00663     {
00664       if(iit != it->begin())
00665         output.append("-> ");
00666       output.append((*iit)->name_ + " ");
00667     }
00668     output.append("\n");
00669   }
00670   return true;
00671 }
00672 
00673 bool
00674 Rosstackage::depsManifests(const std::string& name, bool direct, 
00675                            std::vector<std::string>& manifests)
00676 {
00677   Stackage* stackage = findWithRecrawl(name);
00678   if(!stackage)
00679     return false;
00680   try
00681   {
00682     computeDeps(stackage);
00683     std::vector<Stackage*> deps_vec;
00684     gatherDeps(stackage, direct, POSTORDER, deps_vec);
00685     for(std::vector<Stackage*>::const_iterator it = deps_vec.begin();
00686         it != deps_vec.end();
00687         ++it)
00688       manifests.push_back((*it)->manifest_path_);
00689   }
00690   catch(Exception& e)
00691   {
00692     logError(e.what());
00693     return false;
00694   }
00695   return true;
00696 }
00697 
00698 bool
00699 Rosstackage::rosdeps(const std::string& name, bool direct, 
00700                      std::set<std::string>& rosdeps)
00701 {
00702   Stackage* stackage = findWithRecrawl(name);
00703   if(!stackage)
00704     return false;
00705   try
00706   {
00707     computeDeps(stackage);
00708     std::vector<Stackage*> deps_vec;
00709     // rosdeps include the current package
00710     deps_vec.push_back(stackage);
00711     if(!direct)
00712       gatherDeps(stackage, direct, POSTORDER, deps_vec);
00713     for(std::vector<Stackage*>::const_iterator it = deps_vec.begin();
00714         it != deps_vec.end();
00715         ++it)
00716     {
00717       if (!stackage->is_wet_package_)
00718       {
00719         _rosdeps(*it, rosdeps, MANIFEST_TAG_ROSDEP);
00720       }
00721       else
00722       {
00723         // package format 1 tags
00724         _rosdeps(*it, rosdeps, "build_depend");
00725         _rosdeps(*it, rosdeps, "buildtool_depend");
00726         _rosdeps(*it, rosdeps, "run_depend");
00727         // package format 2 tags
00728         _rosdeps(*it, rosdeps, "build_export_depend");
00729         _rosdeps(*it, rosdeps, "buildtool_export_depend");
00730         _rosdeps(*it, rosdeps, "exec_depend");
00731         _rosdeps(*it, rosdeps, "depend");
00732         _rosdeps(*it, rosdeps, "doc_depend");
00733         _rosdeps(*it, rosdeps, "test_depend");
00734       }
00735     }
00736   }
00737   catch(Exception& e)
00738   {
00739     logError(e.what());
00740     return false;
00741   }
00742   return true;
00743 }
00744 
00745 void
00746 Rosstackage::_rosdeps(Stackage* stackage, std::set<std::string>& rosdeps, const char* tag_name)
00747 {
00748   TiXmlElement* root = get_manifest_root(stackage);
00749   for(TiXmlElement* ele = root->FirstChildElement(tag_name);
00750       ele;
00751       ele = ele->NextSiblingElement(tag_name))
00752   {
00753     if(!stackage->is_wet_package_)
00754     {
00755       const char *att_str;
00756       if((att_str = ele->Attribute(MANIFEST_ATTR_NAME)))
00757       {
00758         rosdeps.insert(std::string("name: ") + att_str);
00759       }
00760     }
00761     else
00762     {
00763       const char* dep_pkgname = ele->GetText();
00764       if(isSysPackage(dep_pkgname))
00765       {
00766         rosdeps.insert(std::string("name: ") + dep_pkgname);
00767       }
00768     }
00769   }
00770 }
00771 
00772 bool
00773 Rosstackage::vcs(const std::string& name, bool direct, 
00774                  std::vector<std::string>& vcs)
00775 {
00776   Stackage* stackage = findWithRecrawl(name);
00777   if(!stackage)
00778     return false;
00779   try
00780   {
00781     computeDeps(stackage);
00782     std::vector<Stackage*> deps_vec;
00783     // vcs include the current package
00784     deps_vec.push_back(stackage);
00785     if(!direct)
00786       gatherDeps(stackage, direct, POSTORDER, deps_vec);
00787     for(std::vector<Stackage*>::const_iterator it = deps_vec.begin();
00788         it != deps_vec.end();
00789         ++it)
00790     {
00791       TiXmlElement* root = get_manifest_root(*it);
00792       for(TiXmlElement* ele = root->FirstChildElement(MANIFEST_TAG_VERSIONCONTROL);
00793           ele;
00794           ele = ele->NextSiblingElement(MANIFEST_TAG_VERSIONCONTROL))
00795       {
00796         std::string result;
00797         const char *att_str;
00798         if((att_str = ele->Attribute(MANIFEST_ATTR_TYPE)))
00799         {
00800           result.append("type: ");
00801           result.append(att_str);
00802         }
00803         if((att_str = ele->Attribute(MANIFEST_ATTR_URL)))
00804         {
00805           result.append("\turl: ");
00806           result.append(att_str);
00807         }
00808         vcs.push_back(result);
00809       }
00810     }
00811   }
00812   catch(Exception& e)
00813   {
00814     logError(e.what());
00815     return false;
00816   }
00817   return true;
00818 }
00819 
00820 bool 
00821 Rosstackage::cpp_exports(const std::string& name, const std::string& type,
00822                      const std::string& attrib, bool deps_only,
00823                      std::vector<std::pair<std::string, bool> >& flags)
00824 {
00825   Stackage* stackage = findWithRecrawl(name);
00826   if(!stackage)
00827     return false;
00828 
00829   static bool init_py = false;
00830   static PyObject* pName;
00831   static PyObject* pModule;
00832   static PyObject* pDict;
00833   static PyObject* pFunc;
00834 
00835   try
00836   {
00837     computeDeps(stackage);
00838     std::vector<Stackage*> deps_vec;
00839     if(!deps_only)
00840       deps_vec.push_back(stackage);
00841     gatherDeps(stackage, false, PREORDER, deps_vec, true);
00842     for(std::vector<Stackage*>::const_iterator it = deps_vec.begin();
00843         it != deps_vec.end();
00844         ++it)
00845     {
00846       if(!(*it)->is_wet_package_)
00847       {
00848         std::vector<std::string> dry_flags;
00849         if(!exports_dry_package(*it, "cpp", attrib, dry_flags))
00850         {
00851           return false;
00852         }
00853         for(std::vector<std::string>::const_iterator it = dry_flags.begin(); it != dry_flags.end(); ++it)
00854         {
00855           flags.push_back(std::pair<std::string, bool>(*it, false));
00856         }
00857       }
00858       else
00859       {
00860         initPython();
00861         PyGILState_STATE gstate = PyGILState_Ensure();
00862 
00863         if(!init_py)
00864         {
00865           init_py = true;
00866           pName = PyString_FromString("rosdep2.rospack");
00867           pModule = PyImport_Import(pName);
00868           if(!pModule)
00869           {
00870             PyErr_Print();
00871             PyGILState_Release(gstate);
00872             std::string errmsg = "could not find python module 'rosdep2.rospack'. is rosdep up-to-date (at least 0.10.4)?";
00873             throw Exception(errmsg);
00874           }
00875           pDict = PyModule_GetDict(pModule);
00876           pFunc = PyDict_GetItemString(pDict, "call_pkg_config");
00877         }
00878 
00879         if(!PyCallable_Check(pFunc))
00880         {
00881           PyErr_Print();
00882           PyGILState_Release(gstate);
00883           std::string errmsg = "could not find python function 'rosdep2.rospack.call_pkg_config'. is rosdep up-to-date (at least 0.10.7)?";
00884           throw Exception(errmsg);
00885         }
00886 
00887         PyObject* pArgs = PyTuple_New(2);
00888         PyObject* pOpt = PyString_FromString(type.c_str());
00889         PyTuple_SetItem(pArgs, 0, pOpt);
00890         PyObject* pPkg = PyString_FromString((*it)->name_.c_str());
00891         PyTuple_SetItem(pArgs, 1, pPkg);
00892         PyObject* pValue = PyObject_CallObject(pFunc, pArgs);
00893         Py_DECREF(pArgs);
00894 
00895         if(!pValue)
00896         {
00897           PyErr_Print();
00898           PyGILState_Release(gstate);
00899           std::string errmsg = "could not call python function 'rosdep2.rospack.call_pkg_config'";
00900           throw Exception(errmsg);
00901         }
00902         if(pValue == Py_None)
00903         {
00904           Py_DECREF(pValue);
00905           std::string errmsg = "python function 'rosdep2.rospack.call_pkg_config' could not call 'pkg-config " + type + " " + (*it)->name_ + "' without errors";
00906           throw Exception(errmsg);
00907         }
00908 
00909         flags.push_back(std::pair<std::string, bool>(PyString_AsString(pValue), true));
00910         Py_DECREF(pValue);
00911 
00912         // we want to keep the static objects alive for repeated access
00913         // so skip all garbage collection until process ends
00914         //Py_DECREF(pFunc);
00915         //Py_DECREF(pModule);
00916         //Py_DECREF(pName);
00917         //Py_Finalize();
00918 
00919         PyGILState_Release(gstate);
00920       }
00921     }
00922   }
00923   catch(Exception& e)
00924   {
00925     logError(e.what());
00926     return false;
00927   }
00928   return true;
00929 }
00930 
00931 bool
00932 Rosstackage::reorder_paths(const std::string& paths, std::string& reordered)
00933 {
00934   static bool init_py = false;
00935   static PyObject* pName;
00936   static PyObject* pModule;
00937   static PyObject* pFunc;
00938 
00939   initPython();
00940   PyGILState_STATE gstate = PyGILState_Ensure();
00941 
00942   if(!init_py)
00943   {
00944     init_py = true;
00945     pName = PyString_FromString("catkin_pkg.rospack");
00946     pModule = PyImport_Import(pName);
00947     if(!pModule)
00948     {
00949       PyErr_Print();
00950       PyGILState_Release(gstate);
00951       std::string errmsg = "could not find python module 'catkin_pkg.rospack'. is catkin_pkg up-to-date (at least 0.1.8)?";
00952       throw Exception(errmsg);
00953     }
00954     PyObject* pDict = PyModule_GetDict(pModule);
00955     pFunc = PyDict_GetItemString(pDict, "reorder_paths");
00956   }
00957 
00958   if(!PyCallable_Check(pFunc))
00959   {
00960     PyErr_Print();
00961     PyGILState_Release(gstate);
00962     std::string errmsg = "could not find python function 'catkin_pkg.rospack.reorder_paths'. is catkin_pkg up-to-date (at least 0.1.8)?";
00963     throw Exception(errmsg);
00964   }
00965 
00966 
00967   PyObject* pArgs = PyTuple_New(1);
00968   PyTuple_SetItem(pArgs, 0, PyString_FromString(paths.c_str()));
00969   PyObject* pValue = PyObject_CallObject(pFunc, pArgs);
00970   Py_DECREF(pArgs);
00971 
00972   if(!pValue)
00973   {
00974     PyErr_Print();
00975     PyGILState_Release(gstate);
00976     std::string errmsg = "could not call python function 'catkin_pkg.rospack.reorder_paths'";
00977     throw Exception(errmsg);
00978   }
00979 
00980   reordered = PyString_AsString(pValue);
00981   Py_DECREF(pValue);
00982 
00983   // we want to keep the static objects alive for repeated access
00984   // so skip all garbage collection until process ends
00985   //Py_DECREF(pFunc);
00986   //Py_DECREF(pModule);
00987   //Py_DECREF(pName);
00988   //Py_Finalize();
00989 
00990   PyGILState_Release(gstate);
00991 
00992   return true;
00993 }
00994 
00995 bool 
00996 Rosstackage::exports(const std::string& name, const std::string& lang,
00997                      const std::string& attrib, bool deps_only,
00998                      std::vector<std::string>& flags)
00999 {
01000   Stackage* stackage = findWithRecrawl(name);
01001   if(!stackage)
01002     return false;
01003   try
01004   {
01005     computeDeps(stackage);
01006     std::vector<Stackage*> deps_vec;
01007     if(!deps_only)
01008       deps_vec.push_back(stackage);
01009     gatherDeps(stackage, false, PREORDER, deps_vec);
01010     for(std::vector<Stackage*>::const_iterator it = deps_vec.begin();
01011         it != deps_vec.end();
01012         ++it)
01013     {
01014       if (!exports_dry_package(*it, lang, attrib, flags))
01015       {
01016         return false;
01017       }
01018     }
01019   }
01020   catch(Exception& e)
01021   {
01022     logError(e.what());
01023     return false;
01024   }
01025   return true;
01026 }
01027 
01028 bool 
01029 Rosstackage::exports_dry_package(Stackage* stackage, const std::string& lang,
01030                      const std::string& attrib,
01031                      std::vector<std::string>& flags)
01032 {
01033   TiXmlElement* root = get_manifest_root(stackage);
01034   for(TiXmlElement* ele = root->FirstChildElement(MANIFEST_TAG_EXPORT);
01035       ele;
01036       ele = ele->NextSiblingElement(MANIFEST_TAG_EXPORT))
01037   {
01038     bool os_match = false;
01039     const char *best_match = NULL;
01040     for(TiXmlElement* ele2 = ele->FirstChildElement(lang);
01041         ele2;
01042         ele2 = ele2->NextSiblingElement(lang))
01043     {
01044       const char *os_str;
01045       if ((os_str = ele2->Attribute("os")))
01046       {
01047         if(g_ros_os == std::string(os_str))
01048         {
01049           if(os_match)
01050             logWarn(std::string("ignoring duplicate ") + lang + " tag with os=" + os_str + " in export block");
01051           else
01052           {
01053             best_match = ele2->Attribute(attrib.c_str());
01054             os_match = true;
01055           }
01056         }
01057       }
01058       if(!os_match)
01059       {
01060         if(!best_match)
01061           best_match = ele2->Attribute(attrib.c_str());
01062         else
01063           logWarn(std::string("ignoring duplicate ") + lang + " tag in export block");
01064       }
01065 
01066     }
01067     if(best_match)
01068     {
01069       std::string expanded_str;
01070       if(!expandExportString(stackage, best_match, expanded_str))
01071         return false;
01072       flags.push_back(expanded_str);
01073     }
01074   }
01075   // We automatically point to msg_gen and msg_srv directories if
01076   // certain files are present.
01077   // But only if we're looking for cpp/cflags, #3884.
01078   if((lang == "cpp") && (attrib == "cflags"))
01079   {
01080     fs::path msg_gen = fs::path(stackage->path_) / MSG_GEN_GENERATED_DIR;
01081     fs::path srv_gen = fs::path(stackage->path_) / SRV_GEN_GENERATED_DIR;
01082     if(fs::is_regular_file(msg_gen / MSG_GEN_GENERATED_FILE))
01083     {
01084       msg_gen /= fs::path("cpp") / "include";
01085       flags.push_back(std::string("-I" + msg_gen.string()));
01086     }
01087     if(fs::is_regular_file(srv_gen / SRV_GEN_GENERATED_FILE))
01088     {
01089       srv_gen /= fs::path("cpp") / "include";
01090       flags.push_back(std::string("-I" + srv_gen.string()));
01091     }
01092   }
01093   return true;
01094 }
01095 
01096 bool 
01097 Rosstackage::plugins(const std::string& name, const std::string& attrib, 
01098                      const std::string& top,
01099                      std::vector<std::string>& flags)
01100 {
01101   // Find everybody who depends directly on the package in question
01102   std::vector<Stackage*> stackages;
01103   if(!depsOnDetail(name, true, stackages, true))
01104     return false;
01105   // Also look in the package itself
01106   std::tr1::unordered_map<std::string, Stackage*>::const_iterator it = stackages_.find(name);
01107   if(it != stackages_.end())
01108   {
01109     // don't warn here; it was done in depsOnDetail()
01110     stackages.push_back(it->second);
01111   }
01112   // If top was given, filter to include only those package on which top
01113   // depends.
01114   if(top.size())
01115   {
01116     std::vector<Stackage*> top_deps;
01117     if(!depsDetail(top, false, top_deps))
01118       return false;
01119     std::tr1::unordered_set<Stackage*> top_deps_set;
01120     for(std::vector<Stackage*>::iterator it = top_deps.begin();
01121         it != top_deps.end();
01122         ++it)
01123       top_deps_set.insert(*it);
01124     std::vector<Stackage*>::iterator it = stackages.begin();
01125     while(it != stackages.end())
01126     {
01127       if((*it)->name_ != top &&
01128          (top_deps_set.find(*it) == top_deps_set.end()))
01129         it = stackages.erase(it);
01130       else
01131         ++it;
01132     }
01133   }
01134   // Now go looking for the manifest data
01135   for(std::vector<Stackage*>::const_iterator it = stackages.begin();
01136       it != stackages.end();
01137       ++it)
01138   {
01139     TiXmlElement* root = get_manifest_root(*it);
01140     for(TiXmlElement* ele = root->FirstChildElement(MANIFEST_TAG_EXPORT);
01141         ele;
01142         ele = ele->NextSiblingElement(MANIFEST_TAG_EXPORT))
01143     {
01144       for(TiXmlElement* ele2 = ele->FirstChildElement(name);
01145           ele2;
01146           ele2 = ele2->NextSiblingElement(name))
01147       {
01148         const char *att_str;
01149         if((att_str = ele2->Attribute(attrib.c_str())))
01150         {
01151           std::string expanded_str;
01152           if(!expandExportString(*it, att_str, expanded_str))
01153             return false;
01154           flags.push_back((*it)->name_ + " " + expanded_str);
01155         }
01156       }
01157     }
01158   }
01159   return true;
01160 }
01161 
01162 bool
01163 Rosstackage::depsMsgSrv(const std::string& name, bool direct, 
01164                         std::vector<std::string>& gens)
01165 {
01166   Stackage* stackage = findWithRecrawl(name);
01167   if(!stackage)
01168     return false;
01169   try
01170   {
01171     computeDeps(stackage);
01172     std::vector<Stackage*> deps_vec;
01173     gatherDeps(stackage, direct, POSTORDER, deps_vec);
01174     for(std::vector<Stackage*>::const_iterator it = deps_vec.begin();
01175         it != deps_vec.end();
01176         ++it)
01177     {
01178       fs::path msg_gen = fs::path((*it)->path_) / 
01179               MSG_GEN_GENERATED_DIR / 
01180               MSG_GEN_GENERATED_FILE;
01181       fs::path srv_gen = fs::path((*it)->path_) / 
01182               SRV_GEN_GENERATED_DIR / 
01183               SRV_GEN_GENERATED_FILE;
01184       if(fs::is_regular_file(msg_gen))
01185         gens.push_back(msg_gen.string());
01186       if(fs::is_regular_file(srv_gen))
01187         gens.push_back(srv_gen.string());
01188     }
01189   }
01190   catch(Exception& e)
01191   {
01192     logError(e.what());
01193     return false;
01194   }
01195   return true;
01196 }
01197 
01199 // Rosstackage methods (private)
01201 
01202 void 
01203 Rosstackage::log(const std::string& level,
01204                  const std::string& msg,
01205                  bool append_errno)
01206 {
01207   if(quiet_)
01208     return;
01209   fprintf(stderr, "[%s] %s: %s",
01210           name_.c_str(), level.c_str(), msg.c_str());
01211   if(append_errno)
01212     fprintf(stderr, ": %s", strerror(errno));
01213   fprintf(stderr, "\n");
01214 }
01215 
01216 
01217 Stackage*
01218 Rosstackage::findWithRecrawl(const std::string& name)
01219 {
01220   if(stackages_.count(name))
01221     return stackages_[name];
01222   else
01223   {
01224     // Try to recrawl, in case we loaded from cache
01225     crawl(search_paths_, true);
01226     if(stackages_.count(name))
01227       return stackages_[name];
01228   }
01229 
01230   logError(std::string("stack/package ") + name + " not found");
01231   return NULL;
01232 }
01233 
01234 bool
01235 Rosstackage::depsDetail(const std::string& name, bool direct,
01236                         std::vector<Stackage*>& deps)
01237 {
01238   // No recrawl here, because we're in a recursive function.  Rely on the
01239   // top level to do it.
01240   if(!stackages_.count(name))
01241   {
01242     logError(std::string("no such package ") + name);
01243     return false;
01244   }
01245   Stackage* stackage = stackages_[name];
01246   try
01247   {
01248     computeDeps(stackage);
01249     std::vector<Stackage*> deps_vec;
01250     gatherDeps(stackage, direct, POSTORDER, deps_vec);
01251     for(std::vector<Stackage*>::const_iterator it = deps_vec.begin();
01252         it != deps_vec.end();
01253         ++it)
01254       deps.push_back(*it);
01255   }
01256   catch(Exception& e)
01257   {
01258     logError(e.what());
01259     return false;
01260   }
01261   return true;
01262 }
01263 
01264 void
01265 Rosstackage::depsWhyDetail(Stackage* from,
01266                            Stackage* to,
01267                            std::list<std::list<Stackage*> >& acc_list)
01268 {
01269   computeDeps(from);
01270   for(std::vector<Stackage*>::const_iterator it = from->deps_.begin();
01271       it != from->deps_.end();
01272       ++it)
01273   {
01274     if((*it)->name_ == to->name_)
01275     {
01276       std::list<Stackage*> acc;
01277       acc.push_back(from);
01278       acc.push_back(to);
01279       acc_list.push_back(acc);
01280     }
01281     else
01282     {
01283       std::list<std::list<Stackage*> > l;
01284       depsWhyDetail(*it, to, l);
01285       for(std::list<std::list<Stackage*> >::iterator iit = l.begin();
01286           iit != l.end();
01287           ++iit)
01288       {
01289         iit->push_front(from);
01290         acc_list.push_back(*iit);
01291       }
01292     }
01293   }
01294 }
01295 
01296 bool
01297 Rosstackage::depsOnDetail(const std::string& name, bool direct,
01298                           std::vector<Stackage*>& deps, bool ignore_missing)
01299 {
01300   // No recrawl here, because depends-on always forces a crawl at the
01301   // start.
01302   if(!stackages_.count(name))
01303     logWarn(std::string("no such package ") + name);
01304   try
01305   {
01306     for(std::tr1::unordered_map<std::string, Stackage*>::const_iterator it = stackages_.begin();
01307         it != stackages_.end();
01308         ++it)
01309     {
01310       computeDeps(it->second, true, ignore_missing);
01311       std::vector<Stackage*> deps_vec;
01312       gatherDeps(it->second, direct, POSTORDER, deps_vec);
01313       for(std::vector<Stackage*>::const_iterator iit = deps_vec.begin();
01314           iit != deps_vec.end();
01315           ++iit)
01316       {
01317         if((*iit)->name_ == name)
01318         {
01319           deps.push_back(it->second);
01320           break;
01321         }
01322       }
01323     }
01324   }
01325   catch(Exception& e)
01326   {
01327     logError(e.what());
01328     return false;
01329   }
01330   return true;
01331 }
01332 
01333 bool
01334 Rosstackage::profile(const std::vector<std::string>& search_path,
01335                      bool zombie_only,
01336                      int length,
01337                      std::vector<std::string>& dirs)
01338 {
01339   double start = time_since_epoch();
01340   std::vector<DirectoryCrawlRecord*> dcrs;
01341   std::tr1::unordered_set<std::string> dcrs_hash;
01342   for(std::vector<std::string>::const_iterator p = search_path.begin();
01343       p != search_path.end();
01344       ++p)
01345   {
01346     crawlDetail(*p, true, 1, true, dcrs, dcrs_hash);
01347   }
01348   if(!zombie_only)
01349   {
01350     double total = time_since_epoch() - start;
01351     char buf[16];
01352     snprintf(buf, sizeof(buf), "%.6f", total);
01353     dirs.push_back(std::string("Full tree crawl took ") + buf + " seconds.");
01354     dirs.push_back("Directories marked with (*) contain no manifest.  You may");
01355     dirs.push_back("want to delete these directories.");
01356     dirs.push_back("To get just of list of directories without manifests,");
01357     dirs.push_back("re-run the profile with --zombie-only");
01358     dirs.push_back("-------------------------------------------------------------");
01359   }
01360   std::sort(dcrs.begin(), dcrs.end(), cmpDirectoryCrawlRecord);
01361   std::reverse(dcrs.begin(), dcrs.end());
01362   int i=0;
01363   for(std::vector<DirectoryCrawlRecord*>::const_iterator it = dcrs.begin();
01364       it != dcrs.end();
01365       ++it)
01366   {
01367     if(zombie_only)
01368     {
01369       if((*it)->zombie_)
01370       {
01371         if(length < 0 || i < length)
01372           dirs.push_back((*it)->path_);
01373         i++;
01374       }
01375     }
01376     else
01377     {
01378       char buf[16];
01379       snprintf(buf, sizeof(buf), "%.6f", (*it)->crawl_time_);
01380       if(length < 0 || i < length)
01381         dirs.push_back(std::string(buf) + " " + 
01382                        ((*it)->zombie_ ? "* " : "  ") +
01383                        (*it)->path_);
01384       i++;
01385     }
01386     delete *it;
01387   }
01388 
01389   writeCache();
01390   return 0;
01391 }
01392 
01393 void
01394 Rosstackage::addStackage(const std::string& path)
01395 {
01396 #if !defined(BOOST_FILESYSTEM_VERSION) || (BOOST_FILESYSTEM_VERSION == 2)
01397   std::string name = fs::path(path).filename();
01398 #else
01399   // in boostfs3, filename() returns a path, which needs to be stringified
01400   std::string name = fs::path(path).filename().string();
01401 #endif
01402 
01403   Stackage* stackage = 0;
01404   fs::path dry_manifest_path = fs::path(path) / manifest_name_;
01405   fs::path wet_manifest_path = fs::path(path) / ROSPACKAGE_MANIFEST_NAME;
01406   if(fs::is_regular_file(dry_manifest_path))
01407   {
01408     stackage = new Stackage(name, path, dry_manifest_path.string(), manifest_name_);
01409   }
01410   else if(fs::is_regular_file(wet_manifest_path))
01411   {
01412     stackage = new Stackage(name, path, wet_manifest_path.string(), ROSPACKAGE_MANIFEST_NAME);
01413     loadManifest(stackage);
01414     stackage->update_wet_information();
01415   }
01416   else
01417   {
01418     return;
01419   }
01420 
01421   // skip the stackage if it is not of correct type
01422   if((manifest_name_ == ROSSTACK_MANIFEST_NAME && stackage->isPackage()) ||
01423      (manifest_name_ == ROSPACK_MANIFEST_NAME && stackage->isStack()))
01424   {
01425     return;
01426   }
01427 
01428   if(stackages_.find(stackage->name_) != stackages_.end())
01429   {
01430     if (dups_.find(stackage->name_) == dups_.end())
01431     {
01432       std::vector<std::string> dups;
01433       dups.push_back(stackages_[stackage->name_]->path_);
01434       dups_[stackage->name_] = dups;
01435     }
01436     dups_[stackage->name_].push_back(stackage->path_);
01437     return;
01438   }
01439 
01440   stackages_[stackage->name_] = stackage;
01441 }
01442 
01443 void
01444 Rosstackage::crawlDetail(const std::string& path,
01445                          bool force,
01446                          int depth,
01447                          bool collect_profile_data,
01448                          std::vector<DirectoryCrawlRecord*>& profile_data,
01449                          std::tr1::unordered_set<std::string>& profile_hash)
01450 {
01451   if(depth > MAX_CRAWL_DEPTH)
01452     throw Exception("maximum depth exceeded during crawl");
01453 
01454   try
01455   {
01456     if(!fs::is_directory(path))
01457       return;
01458   }
01459   catch(fs::filesystem_error& e)
01460   {
01461     logWarn(std::string("error while looking at ") + path + ": " + e.what());
01462     return;
01463   }
01464 
01465   fs::path catkin_ignore = fs::path(path) / CATKIN_IGNORE;
01466   try
01467   {
01468     if(fs::is_regular_file(catkin_ignore))
01469       return;
01470   }
01471   catch(fs::filesystem_error& e)
01472   {
01473     logWarn(std::string("error while looking for ") + catkin_ignore.string() + ": " + e.what());
01474   }
01475 
01476   if(isStackage(path))
01477   {
01478     addStackage(path);
01479     return;
01480   }
01481 
01482   fs::path nosubdirs = fs::path(path) / ROSPACK_NOSUBDIRS;
01483   try
01484   {
01485     if(fs::is_regular_file(nosubdirs))
01486       return;
01487   }
01488   catch(fs::filesystem_error& e)
01489   {
01490     logWarn(std::string("error while looking for ") + nosubdirs.string() + ": " + e.what());
01491   }
01492 
01493   // We've already checked above whether CWD contains the kind of manifest
01494   // we're looking for.  Don't recurse if we encounter a rospack manifest,
01495   // to avoid having rosstack finding stacks inside packages, #3816.
01496   fs::path rospack_manifest = fs::path(path) / ROSPACK_MANIFEST_NAME;
01497   try
01498   {
01499     if(fs::is_regular_file(rospack_manifest))
01500       return;
01501   }
01502   catch(fs::filesystem_error& e)
01503   {
01504     logWarn(std::string("error while looking for ") + rospack_manifest.string() + ": " + e.what());
01505   }
01506 
01507   DirectoryCrawlRecord* dcr = NULL;
01508   if(collect_profile_data)
01509   {
01510     if(profile_hash.find(path) == profile_hash.end())
01511     {
01512       dcr = new DirectoryCrawlRecord(path,
01513                                      time_since_epoch(),
01514                                      stackages_.size());
01515       profile_data.push_back(dcr);
01516       profile_hash.insert(path);
01517     }
01518   }
01519 
01520   try
01521   {
01522     for(fs::directory_iterator dit = fs::directory_iterator(path);
01523         dit != fs::directory_iterator();
01524         ++dit)
01525     {
01526       if(fs::is_directory(dit->path()))
01527       {
01528 #if !defined(BOOST_FILESYSTEM_VERSION) || (BOOST_FILESYSTEM_VERSION == 2)
01529         std::string name = dit->path().filename();
01530 #else
01531         // in boostfs3, filename() returns a path, which needs to be stringified
01532         std::string name = dit->path().filename().string();
01533 #endif
01534         // Ignore directories starting with '.'
01535         if(name.size() == 0 || name[0] == '.')
01536           continue;
01537 
01538         crawlDetail(dit->path().string(), force, depth+1,
01539                     collect_profile_data, profile_data, profile_hash);
01540       }
01541     }
01542   }
01543   catch(fs::filesystem_error& e)
01544   {
01545     logWarn(std::string("error while crawling ") + path + ": " + e.what());
01546   }
01547 
01548   if(collect_profile_data && dcr != NULL)
01549   {
01550     // Measure the elapsed time
01551     dcr->crawl_time_ = time_since_epoch() - dcr->start_time_;
01552     // If the number of packages didn't change while crawling, 
01553     // then this directory is a zombie
01554     if(stackages_.size() == dcr->start_num_pkgs_)
01555       dcr->zombie_ = true;
01556   }
01557 }
01558 
01559 void
01560 Rosstackage::loadManifest(Stackage* stackage)
01561 {
01562   if(stackage->manifest_loaded_)
01563     return;
01564 
01565   if(!stackage->manifest_.LoadFile(stackage->manifest_path_))
01566   {
01567     std::string errmsg = std::string("error parsing manifest of package ") + 
01568             stackage->name_ + " at " + stackage->manifest_path_;
01569     throw Exception(errmsg);
01570   }
01571   stackage->manifest_loaded_ = true;
01572 }
01573 
01574 void
01575 Rosstackage::computeDeps(Stackage* stackage, bool ignore_errors, bool ignore_missing)
01576 {
01577   if(stackage->deps_computed_)
01578     return;
01579 
01580   stackage->deps_computed_ = true;
01581 
01582   try
01583   {
01584     loadManifest(stackage);
01585     get_manifest_root(stackage);
01586   }
01587   catch(Exception& e)
01588   {
01589     if(ignore_errors)
01590       return;
01591     else
01592       throw e;
01593   }
01594   if (!stackage->is_wet_package_)
01595   {
01596     computeDepsInternal(stackage, ignore_errors, "depend", ignore_missing);
01597   }
01598   else
01599   {
01600     // package format 1 tags
01601     computeDepsInternal(stackage, ignore_errors, "run_depend", ignore_missing);
01602     // package format 2 tags
01603     computeDepsInternal(stackage, ignore_errors, "exec_depend", ignore_missing);
01604     computeDepsInternal(stackage, ignore_errors, "depend", ignore_missing);
01605   }
01606 }
01607 
01608 void
01609 Rosstackage::computeDepsInternal(Stackage* stackage, bool ignore_errors, const std::string& depend_tag, bool ignore_missing)
01610 {
01611   TiXmlElement* root;
01612   root = get_manifest_root(stackage);
01613 
01614   TiXmlNode *dep_node = NULL;
01615   const char* dep_pkgname;
01616   while((dep_node = root->IterateChildren(depend_tag, dep_node)))
01617   {
01618     TiXmlElement *dep_ele = dep_node->ToElement();
01619     if (!stackage->is_wet_package_)
01620     {
01621       dep_pkgname = dep_ele->Attribute(tag_.c_str());
01622     }
01623     else
01624     {
01625       dep_pkgname = dep_ele->GetText();
01626     }
01627     if(!dep_pkgname)
01628     {
01629       if(!ignore_errors)
01630       {
01631         std::string errmsg = std::string("bad depend syntax (no 'package/stack' attribute) in manifest ") + stackage->name_ + " at " + stackage->manifest_path_;
01632         throw Exception(errmsg);
01633       }
01634     }
01635     else if(dep_pkgname == stackage->name_)
01636     {
01637       if(!ignore_errors)
01638       {
01639         std::string errmsg = std::string("package/stack ") + stackage->name_ + " depends on itself";
01640         throw Exception(errmsg);
01641       }
01642     }
01643     else if(!stackages_.count(dep_pkgname))
01644     {
01645       if (stackage->is_wet_package_ && (ignore_missing || isSysPackage(dep_pkgname)))
01646       {
01647         continue;
01648       }
01649       if(ignore_errors)
01650       {
01651         Stackage* dep =  new Stackage(dep_pkgname, "", "", "");
01652         stackage->deps_.push_back(dep);
01653       }
01654       else
01655       {
01656         std::string errmsg = std::string("package/stack '") + stackage->name_ + "' depends on non-existent package '" + dep_pkgname + "' and rosdep claims that it is not a system dependency. Check the ROS_PACKAGE_PATH or try calling 'rosdep update'";
01657         throw Exception(errmsg);
01658       }
01659     }
01660     else
01661     {
01662       Stackage* dep = stackages_[dep_pkgname];
01663       if (std::find(stackage->deps_.begin(), stackage->deps_.end(), dep) == stackage->deps_.end())
01664       {
01665         stackage->deps_.push_back(dep);
01666         computeDeps(dep, ignore_errors, ignore_missing);
01667       }
01668     }
01669   }
01670 }
01671 
01672 void
01673 Rosstackage::initPython()
01674 {
01675   static bool initialized = false;
01676   if(!initialized)
01677   {
01678     initialized = true;
01679     Py_InitializeEx(0);
01680   }
01681 }
01682 
01683 bool
01684 Rosstackage::isSysPackage(const std::string& pkgname)
01685 {
01686   static std::map<std::string, bool> cache;
01687   if(cache.find(pkgname) != cache.end())
01688   {
01689     return cache.find(pkgname)->second;
01690   }
01691 
01692   initPython();  
01693   PyGILState_STATE gstate = PyGILState_Ensure();
01694 
01695   static PyObject* pModule = 0;
01696   static PyObject* pDict = 0;
01697   if(!pModule)
01698   {
01699     PyObject* pName = PyString_FromString("rosdep2.rospack");
01700     pModule = PyImport_Import(pName);
01701     Py_DECREF(pName);
01702     if(!pModule)
01703     {
01704       PyErr_Print();
01705       PyGILState_Release(gstate);
01706       std::string errmsg = "could not find python module 'rosdep2.rospack'. is rosdep up-to-date (at least 0.10.4)?";
01707       throw Exception(errmsg);
01708     }
01709     pDict = PyModule_GetDict(pModule);
01710   }
01711 
01712   static PyObject* pView = 0;
01713   if(!pView)
01714   {
01715     PyObject* pFunc = PyDict_GetItemString(pDict, "init_rospack_interface");
01716     if(!PyCallable_Check(pFunc))
01717     {
01718       PyErr_Print();
01719       PyGILState_Release(gstate);
01720       std::string errmsg = "could not find python function 'rosdep2.rospack.init_rospack_interface'. is rosdep up-to-date (at least 0.10.4)?";
01721       throw Exception(errmsg);
01722     }
01723     pView = PyObject_CallObject(pFunc, NULL);
01724     if(!pView)
01725     {
01726       PyErr_Print();
01727       PyGILState_Release(gstate);
01728       std::string errmsg = "could not call python function 'rosdep2.rospack.init_rospack_interface'";
01729       throw Exception(errmsg);
01730     }
01731   }
01732   static bool rospack_view_not_empty = false;
01733   if(!rospack_view_not_empty)
01734   {
01735     PyObject* pFunc = PyDict_GetItemString(pDict, "is_view_empty");
01736     if(!PyCallable_Check(pFunc))
01737     {
01738       PyErr_Print();
01739       PyGILState_Release(gstate);
01740       std::string errmsg = "could not find python function 'rosdep2.rospack.is_view_empty'. is rosdep up-to-date (at least 0.10.8)?";
01741       throw Exception(errmsg);
01742     }
01743     PyObject* pArgs = PyTuple_New(1);
01744     PyTuple_SetItem(pArgs, 0, pView);
01745     PyObject* pValue = PyObject_CallObject(pFunc, pArgs);
01746     Py_INCREF(pView); // in order to keep the view when garbaging pArgs
01747     Py_DECREF(pArgs);
01748     if(PyObject_IsTrue(pValue))
01749     {
01750       PyErr_Print();
01751       PyGILState_Release(gstate);
01752       std::string errmsg = "the rosdep view is empty: call 'sudo rosdep init' and 'rosdep update'";
01753       throw Exception(errmsg);
01754     }
01755     rospack_view_not_empty = true;
01756   }
01757 
01758   PyObject* pFunc = PyDict_GetItemString(pDict, "is_system_dependency");
01759   if(!PyCallable_Check(pFunc))
01760   {
01761     PyErr_Print();
01762     PyGILState_Release(gstate);
01763     std::string errmsg = "could not call python function 'rosdep2.rospack.is_system_dependency'. is rosdep up-to-date (at least 0.10.4)?";
01764     throw Exception(errmsg);
01765   }
01766 
01767   PyObject* pArgs = PyTuple_New(2);
01768   PyTuple_SetItem(pArgs, 0, pView);
01769   PyObject* pDep = PyString_FromString(pkgname.c_str());
01770   PyTuple_SetItem(pArgs, 1, pDep);
01771   PyObject* pValue = PyObject_CallObject(pFunc, pArgs);
01772   Py_INCREF(pView); // in order to keep the view when garbaging pArgs
01773   Py_DECREF(pArgs);
01774 
01775   bool value = PyObject_IsTrue(pValue);
01776   Py_DECREF(pValue);
01777 
01778   // we want to keep the static objects alive for repeated access
01779   // so skip all garbage collection until process ends
01780   //Py_DECREF(pView);
01781   //Py_DECREF(pDict);
01782   //Py_DECREF(pModule);
01783   //Py_Finalize();
01784 
01785   PyGILState_Release(gstate);
01786 
01787   cache[pkgname] = value;
01788 
01789   return value;
01790 }
01791 
01792 void
01793 Rosstackage::gatherDeps(Stackage* stackage, bool direct, 
01794                         traversal_order_t order,
01795                         std::vector<Stackage*>& deps,
01796                         bool no_recursion_on_wet)
01797 {
01798   std::tr1::unordered_set<Stackage*> deps_hash;
01799   std::vector<std::string> indented_deps;
01800   gatherDepsFull(stackage, direct, order, 0, 
01801                  deps_hash, deps, false, indented_deps, no_recursion_on_wet);
01802 }
01803 
01804 void
01805 _gatherDepsFull(Stackage* stackage, bool direct,
01806                             traversal_order_t order, int depth,
01807                             std::tr1::unordered_set<Stackage*>& deps_hash,
01808                             std::vector<Stackage*>& deps,
01809                             bool get_indented_deps,
01810                             std::vector<std::string>& indented_deps,
01811                             bool no_recursion_on_wet,
01812                             std::vector<std::string>& dep_chain)
01813 {
01814   if(stackage->is_wet_package_ && no_recursion_on_wet)
01815   {
01816     return;
01817   }
01818 
01819   if(direct && (stackage->is_wet_package_ || !no_recursion_on_wet))
01820   {
01821     for(std::vector<Stackage*>::const_iterator it = stackage->deps_.begin();
01822         it != stackage->deps_.end();
01823         ++it)
01824       deps.push_back(*it);
01825     return;
01826   }
01827 
01828   if(depth > MAX_DEPENDENCY_DEPTH) {
01829     std::string cycle;
01830     for(std::vector<std::string>::const_iterator it = dep_chain.begin();
01831         it != dep_chain.end();
01832         ++it)
01833     {
01834       std::vector<std::string>::const_iterator begin = dep_chain.begin();
01835       std::vector<std::string>::const_iterator cycle_begin = std::find(begin, it, *it);
01836       if(cycle_begin != it) {
01837         cycle = ": ";
01838         for(std::vector<std::string>::const_iterator jt = cycle_begin; jt != it; ++jt) {
01839           if(jt != cycle_begin) cycle += ", ";
01840           cycle += *jt;
01841         }
01842         break;
01843       }
01844     }
01845     throw Exception(std::string("maximum dependency depth exceeded (likely circular dependency") + cycle + ")");
01846   }
01847 
01848   for(std::vector<Stackage*>::const_iterator it = stackage->deps_.begin();
01849       it != stackage->deps_.end();
01850       ++it)
01851   {
01852     if(get_indented_deps)
01853     {
01854       std::string indented_dep;
01855       for(int i=0; i<depth; i++)
01856         indented_dep.append("  ");
01857       indented_dep.append((*it)->name_);
01858         indented_deps.push_back(indented_dep);
01859     }
01860 
01861     bool first = (deps_hash.find(*it) == deps_hash.end());
01862     if(first)
01863     {
01864       deps_hash.insert(*it);
01865       // We maintain the vector because the original rospack guaranteed
01866       // ordering in dep reporting.
01867       if(order == PREORDER)
01868         deps.push_back(*it);
01869     }
01870     if(!(*it)->is_wet_package_ || !no_recursion_on_wet)
01871     {
01872       // We always descend, even if we're encountering this stackage for the
01873       // nth time, so that we'll throw an error on recursive dependencies
01874       // (detected via max stack depth being exceeded).
01875       dep_chain.push_back((*it)->name_);
01876       _gatherDepsFull(*it, direct, order, depth+1, deps_hash, deps,
01877                      get_indented_deps, indented_deps,
01878                      no_recursion_on_wet, dep_chain);
01879       dep_chain.pop_back();
01880     }
01881     if(first)
01882     {
01883       if(order == POSTORDER)
01884         deps.push_back(*it);
01885     }
01886   }
01887 }
01888 
01889 // Pre-condition: computeDeps(stackage) succeeded
01890 void
01891 Rosstackage::gatherDepsFull(Stackage* stackage, bool direct,
01892                             traversal_order_t order, int depth,
01893                             std::tr1::unordered_set<Stackage*>& deps_hash,
01894                             std::vector<Stackage*>& deps,
01895                             bool get_indented_deps,
01896                             std::vector<std::string>& indented_deps,
01897                             bool no_recursion_on_wet)
01898 {
01899   std::vector<std::string> dep_chain;
01900   dep_chain.push_back(stackage->name_);
01901   _gatherDepsFull(stackage, direct,
01902       order, depth,
01903       deps_hash,
01904       deps,
01905       get_indented_deps,
01906       indented_deps,
01907       no_recursion_on_wet,
01908       dep_chain);
01909 }
01910 
01911 std::string
01912 Rosstackage::getCachePath()
01913 {
01914   fs::path cache_path;
01915 
01916   char* ros_home = getenv("ROS_HOME");
01917   if(ros_home)
01918     cache_path = ros_home;
01919   else
01920   {
01921     // Get the user's home directory by looking up the password entry based
01922     // on UID.  If that doesn't work, we fall back on examining $HOME,
01923     // knowing that that can cause trouble when mixed with sudo (#2884).  
01924 #if defined(WIN32)
01925     char* home_drive = getenv("HOMEDRIVE");
01926     char* home_path = getenv("HOMEPATH");
01927     if(home_drive && home_path) 
01928       cache_path = fs::path(home_drive) / fs::path(home_path) / fs::path(DOTROS_NAME);
01929 #else // UNIX
01930     char* home_path;
01931     struct passwd* passwd_ent;
01932     // Look up based on effective UID, just in case we got here by set-uid
01933     if((passwd_ent = getpwuid(geteuid())))
01934       home_path = passwd_ent->pw_dir;
01935     else
01936       home_path = getenv("HOME");
01937     if(home_path)
01938       cache_path = fs::path(home_path) / fs::path(DOTROS_NAME);
01939 #endif
01940   }
01941 
01942   // If it doesn't exist, create the directory that will hold the cache
01943   try
01944   {
01945     if(!fs::is_directory(cache_path))
01946     {
01947       fs::create_directory(cache_path);
01948     }
01949   }
01950   catch(fs::filesystem_error& e)
01951   {
01952     logWarn(std::string("cannot create rospack cache directory ") +
01953             cache_path.string() + ": " + e.what());
01954   }
01955   cache_path /= cache_name_;
01956   return cache_path.string();
01957 }
01958 
01959 bool
01960 Rosstackage::readCache()
01961 {
01962   FILE* cache = validateCache();
01963   if(cache)
01964   {
01965     char linebuf[30000];
01966     for(;;)
01967     {
01968       if (!fgets(linebuf, sizeof(linebuf), cache))
01969         break; // error in read operation
01970       if (linebuf[0] == '#')
01971         continue;
01972       char* newline_pos = strchr(linebuf, '\n');
01973       if(newline_pos)
01974         *newline_pos = 0;
01975       addStackage(linebuf);
01976     }
01977     fclose(cache);
01978     return true;
01979   }
01980   else
01981     return false;
01982 }
01983 
01984 // TODO: replace the contents of the method with some fancy cross-platform
01985 // boost thing.
01986 void
01987 Rosstackage::writeCache()
01988 {
01989   // Write the results of this crawl to the cache file.  At each step, give
01990   // up on error, printing a warning to stderr.
01991   std::string cache_path = getCachePath();
01992   if(!cache_path.size())
01993   {
01994     logWarn("no location available to write cache file. Try setting ROS_HOME or HOME.");
01995   }
01996   else
01997   {
01998     char tmp_cache_dir[PATH_MAX];
01999     char tmp_cache_path[PATH_MAX];
02000     strncpy(tmp_cache_dir, cache_path.c_str(), sizeof(tmp_cache_dir));
02001 #if defined(_MSC_VER)
02002     // No dirname on Windows; use _splitpath_s instead
02003     char drive[_MAX_DRIVE], dir[_MAX_DIR], fname[_MAX_FNAME], ext[_MAX_EXT];
02004     _splitpath_s(tmp_cache_dir, drive, _MAX_DRIVE, dir, _MAX_DIR, fname, _MAX_FNAME,
02005                  ext, _MAX_EXT);
02006     char full_dir[_MAX_DRIVE + _MAX_DIR];
02007     _makepath_s(full_dir, _MAX_DRIVE + _MAX_DIR, drive, dir, NULL, NULL);
02008     snprintf(tmp_cache_path, sizeof(tmp_cache_path), "%s\\.rospack_cache.XXXXXX", full_dir);
02009 #elif defined(__MINGW32__)
02010     char* temp_name = tempnam(dirname(tmp_cache_dir),".rospack_cache.");
02011     snprintf(tmp_cache_path, sizeof(tmp_cache_path), temp_name);
02012     delete temp_name;
02013 #else
02014     snprintf(tmp_cache_path, sizeof(tmp_cache_path), "%s/.rospack_cache.XXXXXX", dirname(tmp_cache_dir));
02015 #endif
02016 #if defined(__MINGW32__)
02017     // There is no equivalent of mkstemp or _mktemp_s on mingw, so we resort to a slightly problematic
02018     // tempnam (above) and mktemp method. This has the miniscule chance of a race condition.
02019     int fd = open(tmp_cache_path, O_RDWR | O_EXCL | _O_CREAT, 0644);
02020     if (fd < 0)
02021     {
02022       logWarn(std::string("unable to create temporary cache file ") +
02023                    tmp_cache_path, true);
02024     }
02025     else
02026     {
02027       FILE *cache = fdopen(fd, "w");
02028 #elif defined(WIN32)
02029     if (_mktemp_s(tmp_cache_path, PATH_MAX) != 0)
02030     {
02031       fprintf(stderr,
02032               "[rospack] Unable to generate temporary cache file name: %u",
02033               GetLastError());
02034     }
02035     else
02036     {
02037       FILE *cache = fopen(tmp_cache_path, "w");
02038 #else
02039     int fd = mkstemp(tmp_cache_path);
02040     if (fd < 0)
02041     {
02042       fprintf(stderr, "[rospack] Unable to create temporary cache file %s: %s\n", 
02043               tmp_cache_path, strerror(errno));
02044     }
02045     else
02046     {
02047       FILE *cache = fdopen(fd, "w");
02048 #endif
02049       if (!cache)
02050       {
02051         fprintf(stderr, "[rospack] Unable open cache file %s: %s\n", 
02052                 tmp_cache_path, strerror(errno));
02053       }
02054       else
02055       {
02056         // TODO: remove writing of ROS_ROOT
02057         char *rr = getenv("ROS_ROOT");
02058         fprintf(cache, "#ROS_ROOT=%s\n", (rr ? rr : ""));
02059 
02060         char *rpp = getenv("ROS_PACKAGE_PATH");
02061         fprintf(cache, "#ROS_PACKAGE_PATH=%s\n", (rpp ? rpp : ""));
02062         for(std::tr1::unordered_map<std::string, Stackage*>::const_iterator it = stackages_.begin();
02063             it != stackages_.end();
02064             ++it)
02065           fprintf(cache, "%s\n", it->second->path_.c_str());
02066         fclose(cache);
02067         if(fs::exists(cache_path))
02068           remove(cache_path.c_str());
02069         if(rename(tmp_cache_path, cache_path.c_str()) < 0)
02070         {
02071           fprintf(stderr, "[rospack] Error: failed to rename cache file %s to %s: %s\n", 
02072                   tmp_cache_path, cache_path.c_str(), strerror(errno));
02073         }
02074       }
02075     }
02076   }
02077 }
02078 
02079 FILE*
02080 Rosstackage::validateCache()
02081 {
02082   std::string cache_path = getCachePath();
02083   // first see if it's new enough
02084   double cache_max_age = DEFAULT_MAX_CACHE_AGE;
02085   const char *user_cache_time_str = getenv("ROS_CACHE_TIMEOUT");
02086   if(user_cache_time_str)
02087     cache_max_age = atof(user_cache_time_str);
02088   if(cache_max_age == 0.0)
02089     return NULL;
02090   struct stat s;
02091   if(stat(cache_path.c_str(), &s) == 0)
02092   {
02093     double dt = difftime(time(NULL), s.st_mtime);
02094     // Negative cache_max_age means it's always new enough.  It's dangerous
02095     // for the user to set this, but rosbash uses it.
02096     if ((cache_max_age > 0.0) && (dt > cache_max_age))
02097       return NULL;
02098   }
02099   // try to open it 
02100   FILE* cache = fopen(cache_path.c_str(), "r");
02101   if(!cache)
02102     return NULL; // it's not readable by us. sad.
02103 
02104   // see if ROS_PACKAGE_PATH matches
02105   char linebuf[30000];
02106   bool ros_root_ok = false;
02107   bool ros_package_path_ok = false;
02108   // TODO: remove ROS_ROOT
02109   const char* ros_root = getenv("ROS_ROOT");
02110   const char* ros_package_path = getenv("ROS_PACKAGE_PATH");
02111   for(;;)
02112   {
02113     if(!fgets(linebuf, sizeof(linebuf), cache))
02114       break;
02115     linebuf[strlen(linebuf)-1] = 0; // get rid of trailing newline
02116     if (linebuf[0] == '#')
02117     {
02118       if (!strncmp("#ROS_ROOT=", linebuf, 10))
02119       {
02120         if(!ros_root)
02121         {
02122           if(!strlen(linebuf+10))
02123             ros_root_ok = true;
02124         }
02125         else if (!strcmp(linebuf+10, ros_root))
02126           ros_root_ok = true;
02127       }
02128       else if(!strncmp("#ROS_PACKAGE_PATH=", linebuf, 18))
02129       {
02130         if(!ros_package_path)
02131         {
02132           if(!strlen(linebuf+18))
02133             ros_package_path_ok = true;
02134         }
02135         else if(!strcmp(linebuf+18, ros_package_path))
02136           ros_package_path_ok = true;
02137       }
02138     }
02139     else
02140       break; // we're out of the header. nothing more matters to this check.
02141   }
02142   if(ros_root_ok && ros_package_path_ok)
02143   {
02144     // seek to the beginning and pass back the stream (instead of closing
02145     // and later reopening, which is a race condition, #1666)
02146     fseek(cache, 0, SEEK_SET);
02147     return cache;
02148   }
02149   else
02150   {
02151     fclose(cache);
02152     return NULL;
02153   }
02154 }
02155 
02156 bool
02157 Rosstackage::expandExportString(Stackage* stackage,
02158                                 const std::string& instring,
02159                                 std::string& outstring)
02160 {
02161   outstring = instring;
02162   for(std::string::size_type i = outstring.find(MANIFEST_PREFIX);
02163       i != std::string::npos;
02164       i = outstring.find(MANIFEST_PREFIX))
02165   {
02166     outstring.replace(i, std::string(MANIFEST_PREFIX).length(), 
02167                       stackage->path_);
02168   }
02169 
02170   if (outstring.find_first_of("$`") == std::string::npos)
02171   {
02172     return true;
02173   }
02174 
02175   // Do backquote substitution.  E.g.,  if we find this string:
02176   //   `pkg-config --cflags gdk-pixbuf-2.0`
02177   // We replace it with the result of executing the command
02178   // contained within the backquotes (reading from its stdout), which
02179   // might be something like:
02180   //   -I/usr/include/gtk-2.0 -I/usr/include/glib-2.0 -I/usr/lib/glib-2.0/include
02181 
02182   // Construct and execute the string
02183   // We do the assignment first to ensure that if backquote expansion (or
02184   // anything else) fails, we'll get a non-zero exit status from pclose().
02185   std::string cmd = std::string("ret=\"") + outstring + "\" && echo $ret";
02186 
02187   // Remove embedded newlines
02188   std::string token("\n");
02189   for (std::string::size_type s = cmd.find(token); 
02190        s != std::string::npos;
02191        s = cmd.find(token, s))
02192     cmd.replace(s,token.length(),std::string(" "));
02193 
02194   FILE* p;
02195   if(!(p = popen(cmd.c_str(), "r")))
02196   {
02197     std::string errmsg = 
02198             std::string("failed to execute backquote expression ") +
02199             cmd + " in " +
02200             stackage->manifest_path_;
02201     logWarn(errmsg, true);
02202     return false;
02203   }
02204   else
02205   {
02206     char buf[8192];
02207     memset(buf,0,sizeof(buf));
02208     // Read the command's output
02209     do
02210     {
02211       clearerr(p);
02212       while(fgets(buf + strlen(buf),sizeof(buf)-strlen(buf)-1,p));
02213     } while(ferror(p) && errno == EINTR);
02214     // Close the subprocess, checking exit status
02215     if(pclose(p) != 0)
02216     {
02217       std::string errmsg = 
02218               std::string("got non-zero exit status from executing backquote expression ") +
02219               cmd + " in " +
02220               stackage->manifest_path_;
02221       return false;
02222     }
02223     else
02224     {
02225       // Strip trailing newline, which was added by our call to echo
02226       buf[strlen(buf)-1] = '\0';
02227       // Replace the backquote expression with the new text
02228       outstring = buf;
02229     }
02230   }
02231 
02232   return true;
02233 }
02234 
02236 // Rospack methods
02238 Rospack::Rospack() :
02239         Rosstackage(ROSPACK_MANIFEST_NAME,
02240                     ROSPACK_CACHE_NAME,
02241                     ROSPACK_NAME,
02242                     MANIFEST_TAG_PACKAGE)
02243 {
02244 }
02245 
02246 Rosstackage::~Rosstackage()
02247 {
02248   for(std::tr1::unordered_map<std::string, Stackage*>::const_iterator it = stackages_.begin();
02249       it != stackages_.end();
02250       ++it)
02251   {
02252     delete it->second;
02253   }
02254 }
02255 
02256 const char* 
02257 Rospack::usage()
02258 {
02259   return "USAGE: rospack <command> [options] [package]\n"
02260           "  Allowed commands:\n"
02261           "    help\n"
02262           "    cflags-only-I     [--deps-only] [package]\n"
02263           "    cflags-only-other [--deps-only] [package]\n"
02264           "    depends           [package] (alias: deps)\n"
02265           "    depends-indent    [package] (alias: deps-indent)\n"
02266           "    depends-manifests [package] (alias: deps-manifests)\n"
02267           "    depends-msgsrv    [package] (alias: deps-msgsrv)\n"
02268           "    depends-on        [package]\n"
02269           "    depends-on1       [package]\n"
02270           "    depends-why --target=<target> [package] (alias: deps-why)\n"
02271           "    depends1          [package] (alias: deps1)\n"
02272           "    export [--deps-only] --lang=<lang> --attrib=<attrib> [package]\n"
02273           "    find [package]\n"
02274           "    langs\n"
02275           "    libs-only-L     [--deps-only] [package]\n"
02276           "    libs-only-l     [--deps-only] [package]\n"
02277           "    libs-only-other [--deps-only] [package]\n"
02278           "    list\n"
02279           "    list-duplicates\n"
02280           "    list-names\n"
02281           "    plugins --attrib=<attrib> [--top=<toppkg>] [package]\n"
02282           "    profile [--length=<length>] [--zombie-only]\n"
02283           "    rosdep  [package] (alias: rosdeps)\n"
02284           "    rosdep0 [package] (alias: rosdeps0)\n"
02285           "    vcs  [package]\n"
02286           "    vcs0 [package]\n"
02287           "  Extra options:\n"
02288           "    -q     Quiets error reports.\n\n"
02289           " If [package] is omitted, the current working directory\n"
02290           " is used (if it contains a manifest.xml).\n\n";
02291 }
02292 
02294 // Rosstack methods
02296 Rosstack::Rosstack() :
02297         Rosstackage(ROSSTACK_MANIFEST_NAME,
02298                     ROSSTACK_CACHE_NAME,
02299                     ROSSTACK_NAME,
02300                     MANIFEST_TAG_STACK)
02301 {
02302 }
02303 
02304 const char* 
02305 Rosstack::usage()
02306 {
02307   return "USAGE: rosstack [options] <command> [stack]\n"
02308           "  Allowed commands:\n"
02309           "    help\n"
02310           "    find [stack]\n"
02311           "    contents [stack]\n"
02312           "    list\n"
02313           "    list-names\n"
02314           "    depends [stack] (alias: deps)\n"
02315           "    depends-manifests [stack] (alias: deps-manifests)\n"
02316           "    depends1 [stack] (alias: deps1)\n"
02317           "    depends-indent [stack] (alias: deps-indent)\n"
02318           "    depends-why --target=<target> [stack] (alias: deps-why)\n"
02319           "    depends-on [stack]\n"
02320           "    depends-on1 [stack]\n"
02321           "    contains [package]\n"
02322           "    contains-path [package]\n"
02323           "    profile [--length=<length>] \n\n"
02324           " If [stack] is omitted, the current working directory\n"
02325           " is used (if it contains a stack.xml).\n\n";
02326 }
02327 
02328 TiXmlElement*
02329 get_manifest_root(Stackage* stackage)
02330 {
02331   TiXmlElement* ele = stackage->manifest_.RootElement();
02332   if(!ele)
02333   {
02334     std::string errmsg = std::string("error parsing manifest of package ") + 
02335             stackage->name_ + " at " + stackage->manifest_path_;
02336     throw Exception(errmsg);
02337   }
02338   return ele;
02339 }
02340 
02341 double 
02342 time_since_epoch()
02343 {
02344 #if defined(WIN32)
02345   #if defined(_MSC_VER) || defined(_MSC_EXTENSIONS)
02346     #define DELTA_EPOCH_IN_MICROSECS  11644473600000000Ui64
02347   #else
02348     #define DELTA_EPOCH_IN_MICROSECS  11644473600000000ULL
02349   #endif
02350   FILETIME ft;
02351   unsigned __int64 tmpres = 0;
02352 
02353   GetSystemTimeAsFileTime(&ft);
02354   tmpres |= ft.dwHighDateTime;
02355   tmpres <<= 32;
02356   tmpres |= ft.dwLowDateTime;
02357   tmpres /= 10;
02358   tmpres -= DELTA_EPOCH_IN_MICROSECS;
02359   return static_cast<double>(tmpres) / 1e6;
02360 #else
02361   struct timeval tod;
02362   gettimeofday(&tod, NULL);
02363   return tod.tv_sec + 1e-6 * tod.tv_usec;
02364 #endif
02365 }
02366 
02367 
02368 
02369 } // namespace rospack


rospack
Author(s): Brian Gerkey, Morgan Quigley, Dirk Thomas
autogenerated on Mon Oct 6 2014 07:09:09