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


rospack
Author(s): Brian Gerkey, Morgan Quigley, Dirk Thomas
autogenerated on Sat Jun 8 2019 18:35:33