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 <string>
00111 #include <vector>
00112 #include <set>
00113 #include <list>
00114 
00115 //#ifdef ROSPACK_API_BACKCOMPAT_V1
00116 #if 1 // def ROSPACK_API_BACKCOMPAT_V1
00117   #include "rospack/rospack_backcompat.h"
00118 #endif
00119 
00120 
00121 namespace rospack
00122 {
00123 
00124 typedef enum
00125 {
00126   POSTORDER,
00127   PREORDER
00128 } traversal_order_t;
00129 
00130 // Forward declarations
00131 class Stackage;
00132 class DirectoryCrawlRecord;
00133 
00139 class Rosstackage
00140 {
00141   private:
00142     std::string manifest_name_;
00143     std::string cache_name_;
00144     bool crawled_;
00145     std::string name_;
00146     std::string tag_;
00147     bool quiet_;
00148     std::vector<std::string> search_paths_;
00149     std::tr1::unordered_set<std::string> dups_;
00150     std::tr1::unordered_map<std::string, Stackage*> stackages_;
00151     Stackage* findWithRecrawl(const std::string& name);
00152     void log(const std::string& level, const std::string& msg, bool append_errno);
00153     void addStackage(const std::string& path);
00154     void crawlDetail(const std::string& path,
00155                      bool force,
00156                      int depth,
00157                      bool collect_profile_data,
00158                      std::vector<DirectoryCrawlRecord*>& profile_data,
00159                      std::tr1::unordered_set<std::string>& profile_hash);
00160     bool depsOnDetail(const std::string& name, bool direct,
00161                          std::vector<Stackage*>& deps);
00162     bool depsDetail(const std::string& name, bool direct,
00163                     std::vector<Stackage*>& deps);
00164     bool isStackage(const std::string& path);
00165     void loadManifest(Stackage* stackage);
00166     void computeDeps(Stackage* stackage, bool ignore_errors=false);
00167     void gatherDeps(Stackage* stackage, bool direct,
00168                     traversal_order_t order,
00169                     std::vector<Stackage*>& deps);
00170     void gatherDepsFull(Stackage* stackage, bool direct,
00171                         traversal_order_t order, int depth,
00172                         std::tr1::unordered_set<Stackage*>& deps_hash,
00173                         std::vector<Stackage*>& deps,
00174                         bool get_indented_deps,
00175                         std::vector<std::string>& indented_deps);
00176     std::string getCachePath();
00177     bool readCache();
00178     void writeCache();
00179     FILE* validateCache();
00180     bool expandExportString(Stackage* stackage,
00181                             const std::string& instring,
00182                             std::string& outstring);
00183     void depsWhyDetail(Stackage* from,
00184                        Stackage* to,
00185                        std::list<std::list<Stackage*> >& acc_list);
00186 
00187   protected:
00196     Rosstackage(const std::string& manifest_name,
00197                 const std::string& cache_name,
00198                 const std::string& name,
00199                 const std::string& tag);
00200 
00201   public:
00205     virtual ~Rosstackage();
00206 
00211     virtual const char* usage() { return ""; }
00223     void crawl(std::vector<std::string> search_path, bool force);
00230     bool inStackage(std::string& name);
00237     void setQuiet(bool quiet);
00242     const std::string& getName() {return name_;}
00251     bool getSearchPathFromEnv(std::vector<std::string>& sp);
00258     bool find(const std::string& name, std::string& path);
00265     bool contents(const std::string& name, std::set<std::string>& packages);
00273     bool contains(const std::string& name,
00274                   std::string& stack,
00275                   std::string& path);
00276 
00281     void list(std::set<std::pair<std::string, std::string> >& list);
00287     void listDuplicates(std::vector<std::string>& dups);
00298     bool deps(const std::string& name, bool direct, std::vector<std::string>& deps);
00309     bool depsOn(const std::string& name, bool direct,
00310                    std::vector<std::string>& deps);
00322     bool depsManifests(const std::string& name, bool direct,
00323                        std::vector<std::string>& manifests);
00337     bool depsMsgSrv(const std::string& name, bool direct,
00338                     std::vector<std::string>& gens);
00360     bool depsIndent(const std::string& name, bool direct,
00361                     std::vector<std::string>& deps);
00378     bool depsWhy(const std::string& from,
00379                  const std::string& to,
00380                  std::string& output);
00392     bool rosdeps(const std::string& name, bool direct,
00393                  std::set<std::string>& rosdeps);
00406     bool vcs(const std::string& name, bool direct,
00407              std::vector<std::string>& vcs);
00420     bool exports(const std::string& name, const std::string& lang,
00421                  const std::string& attrib, bool deps_only,
00422                  std::vector<std::string>& flags);
00434     bool plugins(const std::string& name, const std::string& attrib,
00435                  const std::string& top,
00436                  std::vector<std::string>& flags);
00462     bool profile(const std::vector<std::string>& search_path,
00463                  bool zombie_only,
00464                  int length,
00465                  std::vector<std::string>& dirs);
00472     void logWarn(const std::string& msg,
00473                  bool append_errno = false);
00480     void logError(const std::string& msg,
00481                   bool append_errno = false);
00482 };
00483 
00488 class Rospack : public Rosstackage
00489 {
00490   public:
00494     Rospack();
00499     virtual const char* usage();
00500 };
00501 
00506 class Rosstack : public Rosstackage
00507 {
00508   public:
00512     Rosstack();
00517     virtual const char* usage();
00518 };
00519 
00520 } // namespace rospack
00521 
00522 #endif


rospack
Author(s): Brian Gerkey/gerkey@willowgarage.com, Morgan Quigley/mquigley@cs.stanford.edu
autogenerated on Fri Jan 3 2014 11:51:40