rospack.h
Go to the documentation of this file.
00001 /*
00002  * Copyright (C) 2008, Willow Garage, Inc.
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 
00105 #ifndef ROSPACK_ROSPACK_H
00106 #define ROSPACK_ROSPACK_H
00107 
00108 #include <boost/tr1/unordered_set.hpp>
00109 #include <boost/tr1/unordered_map.hpp>
00110 #include <list>
00111 #include <map>
00112 #include <set>
00113 #include <string>
00114 #include <vector>
00115 #include "macros.h"
00116 
00117 //#ifdef ROSPACK_API_BACKCOMPAT_V1
00118 #if 1 // def ROSPACK_API_BACKCOMPAT_V1
00119   #include "rospack/rospack_backcompat.h"
00120 #endif
00121 
00122 
00123 namespace rospack
00124 {
00125 
00126 typedef enum
00127 {
00128   POSTORDER,
00129   PREORDER
00130 } traversal_order_t;
00131 
00132 // Forward declarations
00133 class Stackage;
00134 class DirectoryCrawlRecord;
00135 
00141 class ROSPACK_DECL Rosstackage
00142 {
00143   private:
00144     std::string manifest_name_;
00145     std::string cache_prefix_;
00146     bool crawled_;
00147     std::string name_;
00148     std::string tag_;
00149     bool quiet_;
00150     std::vector<std::string> search_paths_;
00151     std::tr1::unordered_map<std::string, std::vector<std::string> > dups_;
00152     std::tr1::unordered_map<std::string, Stackage*> stackages_;
00153     Stackage* findWithRecrawl(const std::string& name);
00154     void log(const std::string& level, const std::string& msg, bool append_errno);
00155     void clearStackages();
00156     void addStackage(const std::string& path);
00157     void crawlDetail(const std::string& path,
00158                      bool force,
00159                      int depth,
00160                      bool collect_profile_data,
00161                      std::vector<DirectoryCrawlRecord*>& profile_data,
00162                      std::tr1::unordered_set<std::string>& profile_hash);
00163     bool isStackage(const std::string& path);
00164     void loadManifest(Stackage* stackage);
00165     void computeDeps(Stackage* stackage, bool ignore_errors=false, bool ignore_missing=false);
00166     void computeDepsInternal(Stackage* stackage, bool ignore_errors, const std::string& depend_tag, bool ignore_missing=false);
00167     bool isSysPackage(const std::string& pkgname);
00168     void gatherDeps(Stackage* stackage, bool direct,
00169                     traversal_order_t order,
00170                     std::vector<Stackage*>& deps,
00171                     bool no_recursion_on_wet=false);
00172     void gatherDepsFull(Stackage* stackage, bool direct,
00173                         traversal_order_t order, int depth,
00174                         std::tr1::unordered_set<Stackage*>& deps_hash,
00175                         std::vector<Stackage*>& deps,
00176                         bool get_indented_deps,
00177                         std::vector<std::string>& indented_deps,
00178                         bool no_recursion_on_wet=false);
00179     std::string getCachePath();
00180     std::string getCacheHash();
00181     bool readCache();
00182     void writeCache();
00183     FILE* validateCache();
00184     bool expandExportString(Stackage* stackage,
00185                             const std::string& instring,
00186                             std::string& outstring);
00187     void depsWhyDetail(Stackage* from,
00188                        Stackage* to,
00189                        std::list<std::list<Stackage*> >& acc_list);
00190 
00191     void initPython();
00192 
00193   protected:
00202     Rosstackage(const std::string& manifest_name,
00203                 const std::string& cache_prefix,
00204                 const std::string& name,
00205                 const std::string& tag);
00206 
00207   public:
00211     virtual ~Rosstackage();
00212 
00217     virtual const char* usage() { return ""; }
00229     void crawl(std::vector<std::string> search_path, bool force);
00236     bool inStackage(std::string& name);
00243     void setQuiet(bool quiet);
00248     const std::string& getName() {return name_;}
00257     bool getSearchPathFromEnv(std::vector<std::string>& sp);
00264     bool find(const std::string& name, std::string& path);
00271     bool contents(const std::string& name, std::set<std::string>& packages);
00279     bool contains(const std::string& name,
00280                   std::string& stack,
00281                   std::string& path);
00282 
00287     void list(std::set<std::pair<std::string, std::string> >& list);
00293     void listDuplicates(std::vector<std::string>& dups);
00299     void listDuplicatesWithPaths(std::map<std::string, std::vector<std::string> >& dups);
00310     bool deps(const std::string& name, bool direct, std::vector<std::string>& deps);
00321     bool depsOn(const std::string& name, bool direct,
00322                    std::vector<std::string>& deps);
00333     bool depsDetail(const std::string& name, bool direct, std::vector<Stackage*>& deps);
00343     bool depsOnDetail(const std::string& name, bool direct,
00344                       std::vector<Stackage*>& deps, bool ignore_missing=false);
00354     bool depsManifests(const std::string& name, bool direct,
00355                        std::vector<std::string>& manifests);
00369     bool depsMsgSrv(const std::string& name, bool direct,
00370                     std::vector<std::string>& gens);
00392     bool depsIndent(const std::string& name, bool direct,
00393                     std::vector<std::string>& deps);
00410     bool depsWhy(const std::string& from,
00411                  const std::string& to,
00412                  std::string& output);
00424     bool rosdeps(const std::string& name, bool direct,
00425                  std::set<std::string>& rosdeps);
00426     void _rosdeps(Stackage* stackage, std::set<std::string>& rosdeps, const char* tag_name);
00439     bool vcs(const std::string& name, bool direct,
00440              std::vector<std::string>& vcs);
00453     bool cpp_exports(const std::string& name, const std::string& type,
00454                  const std::string& attrib, bool deps_only,
00455                  std::vector<std::pair<std::string, bool> >& flags);
00462     bool reorder_paths(const std::string& paths, std::string& reordered);
00475     bool exports(const std::string& name, const std::string& lang,
00476                  const std::string& attrib, bool deps_only,
00477                  std::vector<std::string>& flags);
00486     bool exports_dry_package(Stackage* stackage, const std::string& lang,
00487                          const std::string& attrib,
00488                          std::vector<std::string>& flags);
00500     bool plugins(const std::string& name, const std::string& attrib,
00501                  const std::string& top,
00502                  std::vector<std::string>& flags);
00528     bool profile(const std::vector<std::string>& search_path,
00529                  bool zombie_only,
00530                  int length,
00531                  std::vector<std::string>& dirs);
00538     void logWarn(const std::string& msg,
00539                  bool append_errno = false);
00546     void logError(const std::string& msg,
00547                   bool append_errno = false);
00548 
00549     /*
00550      * @brief The manifest type.
00551      * @return Either "package" or "stack".
00552      */
00553     virtual std::string get_manifest_type() { return ""; }
00554 };
00555 
00560 class ROSPACK_DECL Rospack : public Rosstackage
00561 {
00562   public:
00566     Rospack();
00571     virtual const char* usage();
00572 
00573     virtual std::string get_manifest_type();
00574 };
00575 
00580 class ROSPACK_DECL Rosstack : public Rosstackage
00581 {
00582   public:
00586     Rosstack();
00591     virtual const char* usage();
00592 
00593     virtual std::string get_manifest_type();
00594 };
00595 
00596 } // namespace rospack
00597 
00598 #endif


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