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


rospack
Author(s): Brian Gerkey, Morgan Quigley, Dirk Thomas
autogenerated on Tue Mar 7 2017 03:26:33