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_name_;
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 addStackage(const std::string& path);
00156     void crawlDetail(const std::string& path,
00157                      bool force,
00158                      int depth,
00159                      bool collect_profile_data,
00160                      std::vector<DirectoryCrawlRecord*>& profile_data,
00161                      std::tr1::unordered_set<std::string>& profile_hash);
00162     bool depsOnDetail(const std::string& name, bool direct,
00163                       std::vector<Stackage*>& deps, bool ignore_missing=false);
00164     bool depsDetail(const std::string& name, bool direct,
00165                     std::vector<Stackage*>& deps);
00166     bool isStackage(const std::string& path);
00167     void loadManifest(Stackage* stackage);
00168     void computeDeps(Stackage* stackage, bool ignore_errors=false, bool ignore_missing=false);
00169     void computeDepsInternal(Stackage* stackage, bool ignore_errors, const std::string& depend_tag, bool ignore_missing=false);
00170     bool isSysPackage(const std::string& pkgname);
00171     void gatherDeps(Stackage* stackage, bool direct,
00172                     traversal_order_t order,
00173                     std::vector<Stackage*>& deps,
00174                     bool no_recursion_on_wet=false);
00175     void gatherDepsFull(Stackage* stackage, bool direct,
00176                         traversal_order_t order, int depth,
00177                         std::tr1::unordered_set<Stackage*>& deps_hash,
00178                         std::vector<Stackage*>& deps,
00179                         bool get_indented_deps,
00180                         std::vector<std::string>& indented_deps,
00181                         bool no_recursion_on_wet=false);
00182     std::string getCachePath();
00183     bool readCache();
00184     void writeCache();
00185     FILE* validateCache();
00186     bool expandExportString(Stackage* stackage,
00187                             const std::string& instring,
00188                             std::string& outstring);
00189     void depsWhyDetail(Stackage* from,
00190                        Stackage* to,
00191                        std::list<std::list<Stackage*> >& acc_list);
00192 
00193     void initPython();
00194 
00195   protected:
00204     Rosstackage(const std::string& manifest_name,
00205                 const std::string& cache_name,
00206                 const std::string& name,
00207                 const std::string& tag);
00208 
00209   public:
00213     virtual ~Rosstackage();
00214 
00219     virtual const char* usage() { return ""; }
00231     void crawl(std::vector<std::string> search_path, bool force);
00238     bool inStackage(std::string& name);
00245     void setQuiet(bool quiet);
00250     const std::string& getName() {return name_;}
00259     bool getSearchPathFromEnv(std::vector<std::string>& sp);
00266     bool find(const std::string& name, std::string& path);
00273     bool contents(const std::string& name, std::set<std::string>& packages);
00281     bool contains(const std::string& name,
00282                   std::string& stack,
00283                   std::string& path);
00284 
00289     void list(std::set<std::pair<std::string, std::string> >& list);
00295     void listDuplicates(std::vector<std::string>& dups);
00301     void listDuplicatesWithPaths(std::map<std::string, std::vector<std::string> >& dups);
00312     bool deps(const std::string& name, bool direct, std::vector<std::string>& deps);
00323     bool depsOn(const std::string& name, bool direct,
00324                    std::vector<std::string>& deps);
00336     bool depsManifests(const std::string& name, bool direct,
00337                        std::vector<std::string>& manifests);
00351     bool depsMsgSrv(const std::string& name, bool direct,
00352                     std::vector<std::string>& gens);
00374     bool depsIndent(const std::string& name, bool direct,
00375                     std::vector<std::string>& deps);
00392     bool depsWhy(const std::string& from,
00393                  const std::string& to,
00394                  std::string& output);
00406     bool rosdeps(const std::string& name, bool direct,
00407                  std::set<std::string>& rosdeps);
00408     void _rosdeps(Stackage* stackage, std::set<std::string>& rosdeps, const char* tag_name);
00421     bool vcs(const std::string& name, bool direct,
00422              std::vector<std::string>& vcs);
00435     bool cpp_exports(const std::string& name, const std::string& type,
00436                  const std::string& attrib, bool deps_only,
00437                  std::vector<std::pair<std::string, bool> >& flags);
00444     bool reorder_paths(const std::string& paths, std::string& reordered);
00457     bool exports(const std::string& name, const std::string& lang,
00458                  const std::string& attrib, bool deps_only,
00459                  std::vector<std::string>& flags);
00468     bool exports_dry_package(Stackage* stackage, const std::string& lang,
00469                          const std::string& attrib,
00470                          std::vector<std::string>& flags);
00482     bool plugins(const std::string& name, const std::string& attrib,
00483                  const std::string& top,
00484                  std::vector<std::string>& flags);
00510     bool profile(const std::vector<std::string>& search_path,
00511                  bool zombie_only,
00512                  int length,
00513                  std::vector<std::string>& dirs);
00520     void logWarn(const std::string& msg,
00521                  bool append_errno = false);
00528     void logError(const std::string& msg,
00529                   bool append_errno = false);
00530 };
00531 
00536 class ROSPACK_DECL Rospack : public Rosstackage
00537 {
00538   public:
00542     Rospack();
00547     virtual const char* usage();
00548 };
00549 
00554 class ROSPACK_DECL Rosstack : public Rosstackage
00555 {
00556   public:
00560     Rosstack();
00565     virtual const char* usage();
00566 };
00567 
00568 } // namespace rospack
00569 
00570 #endif


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