$search
00001 # Software License Agreement (BSD License) 00002 # 00003 # Copyright (c) 2008, Willow Garage, Inc. 00004 # All rights reserved. 00005 # 00006 # Redistribution and use in source and binary forms, with or without 00007 # modification, are permitted provided that the following conditions 00008 # are met: 00009 # 00010 # * Redistributions of source code must retain the above copyright 00011 # notice, this list of conditions and the following disclaimer. 00012 # * Redistributions in binary form must reproduce the above 00013 # copyright notice, this list of conditions and the following 00014 # disclaimer in the documentation and/or other materials provided 00015 # with the distribution. 00016 # * Neither the name of Willow Garage, Inc. nor the names of its 00017 # contributors may be used to endorse or promote products derived 00018 # from this software without specific prior written permission. 00019 # 00020 # THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS 00021 # "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT 00022 # LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS 00023 # FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE 00024 # COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, 00025 # INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, 00026 # BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; 00027 # LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER 00028 # CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT 00029 # LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN 00030 # ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 00031 # POSSIBILITY OF SUCH DAMAGE. 00032 # 00033 # Revision $Id$ 00034 00035 import os 00036 import traceback 00037 import sys 00038 from subprocess import Popen, PIPE 00039 00040 import roslib.packages 00041 import roslib.rosenv 00042 import roslib.manifest 00043 import roslib.rospack 00044 import roslib.stacks 00045 import roslib.stack_manifest 00046 00047 class RosdocContext(object): 00048 00049 def __init__(self, name, docdir, package_filters=None, path_filters=None): 00050 self.name = name 00051 self.package_filters = package_filters 00052 self.path_filters = [] 00053 if path_filters: 00054 for p in path_filters.split(os.pathsep): 00055 if not p: 00056 continue 00057 if not p.endswith(os.sep): 00058 p = p + os.sep 00059 self.path_filters.append(p) 00060 self.docdir = docdir 00061 00062 # these will be initialized in init() 00063 self.rosroot = self.ros_package_path = None 00064 self.packages = {} 00065 self.stacks = {} 00066 self.external_docs = {} 00067 self.manifests = {} 00068 self.stack_manifests = {} 00069 00070 # allow rosmake to be disabled 00071 self.allow_rosmake = True 00072 00073 # - generally suppress output 00074 self.quiet = False 00075 # - for profiling 00076 self.timings = {} 00077 00078 # advanced per-package config 00079 self.rd_configs = {} 00080 00081 self.template_dir = None 00082 00083 def has_builder(self, package, builder): 00084 """ 00085 @return: True if package is configured to use builder. NOTE: 00086 if there is no config, package is assumed to define a doxygen 00087 builder 00088 @rtype: bool 00089 """ 00090 rd_config = self.rd_configs.get(package, None) 00091 if not rd_config: 00092 return builder == 'doxygen' 00093 if type(rd_config) != list: 00094 sys.stderr.write("WARNING: package [%s] has an invalid rosdoc config\n"%(package)) 00095 return False 00096 try: 00097 return len([d for d in rd_config if d['builder'] == builder]) > 0 00098 except KeyError: 00099 sys.stderr.write("config file for [%s] is invalid, missing required 'builder' key\n"%(package)) 00100 return False 00101 except: 00102 sys.stderr.write("config file for [%s] is invalid\n"%(package)) 00103 return False 00104 00105 def should_document(self, package): 00106 """ 00107 @return: True if package should be documented 00108 @rtype: bool 00109 """ 00110 if not package in self.packages: 00111 return False 00112 # package filters override all 00113 if self.package_filters: 00114 return package in self.package_filters 00115 # don't document if not in path filters 00116 if self.path_filters: 00117 package_path = self.packages[package] 00118 if not [p for p in self.path_filters if package_path.startswith(p)]: 00119 return False 00120 # TODO: don't document if not in requested stack 00121 return True 00122 00123 def init(self): 00124 if not self.quiet: 00125 print "initializing rosdoc context:\n\tpackage filters: %s\n\tpath filters: %s"%(self.package_filters, self.path_filters) 00126 00127 self.rosroot = roslib.rosenv.get_ros_root(required=True) 00128 self.ros_package_path = roslib.rosenv.get_ros_package_path(required=False) or '' 00129 00130 rosdoc_dir = roslib.packages.get_pkg_dir('rosdoc') 00131 self.template_dir = os.path.join(rosdoc_dir, 'templates') 00132 00133 # use 'rospack list' to locate all packages and store their paths in a dictionary 00134 rospack_list = roslib.rospack.rospackexec(['list']).split('\n') 00135 rospack_list = [x.split(' ') for x in rospack_list if ' ' in x] 00136 00137 # I'm still debating whether or not to immediately filter 00138 # these. The problem is that a package that is within the 00139 # filter may reference packages outside that filter. I'm not 00140 # sure if this is an issue or not. 00141 packages = self.packages 00142 for package, path in rospack_list: 00143 packages[package] = path 00144 00145 # cache all stack manifests due to issue with empty stacks not being noted by _crawl_deps 00146 stack_manifests = self.stack_manifests 00147 rosstack_list = roslib.rospack.rosstackexec(['list']).split('\n') 00148 rosstack_list = [x.split(' ') for x in rosstack_list if ' ' in x] 00149 for stack, path in rosstack_list: 00150 00151 f = os.path.join(path, roslib.stack_manifest.STACK_FILE) 00152 try: 00153 stack_manifests[stack] = roslib.stack_manifest.parse_file(f) 00154 except: 00155 traceback.print_exc() 00156 print >> sys.stderr, "WARN: stack '%s' does not have a valid stack.xml file, manifest information will not be included in docs"%stack 00157 00158 self.doc_packages = [p for p in packages if self.should_document(p)] 00159 self._crawl_deps() 00160 00161 def _crawl_deps(self): 00162 """ 00163 Crawl manifest.xml dependencies 00164 """ 00165 external_docs = self.external_docs 00166 manifests = self.manifests 00167 rd_configs = self.rd_configs 00168 00169 stacks = self.stacks = {} 00170 00171 # keep track of packages with invalid manifests so we can unregister them 00172 bad = [] 00173 for package, path in self.packages.iteritems(): 00174 00175 # find stacks to document on demand 00176 if self.should_document(package): 00177 if not self.quiet: 00178 print "+package[%s]"%(package) 00179 stack = roslib.stacks.stack_of(package) or '' 00180 if stack and stack not in stacks: 00181 #print "adding stack [%s] to documentation"%stack 00182 try: 00183 p = roslib.stacks.get_stack_dir(stack) 00184 stacks[stack] = p 00185 except: 00186 sys.stderr.write("cannot locate directory of stack [%s]\n"%(stack)) 00187 00188 f = os.path.join(path, roslib.manifest.MANIFEST_FILE) 00189 try: 00190 manifests[package] = m = roslib.manifest.parse_file(f) 00191 00192 if self.should_document(package): 00193 #NOTE: the behavior is undefined if the users uses 00194 #both config and export properties directly 00195 00196 # #1650 for backwards compatibility, we read the old 00197 # 'doxymaker' tag, which is deprecated 00198 # - this is a loop but we only accept one value 00199 for e in m.get_export('doxymaker', 'external'): 00200 external_docs[package] = e 00201 for e in m.get_export('rosdoc', 'external'): 00202 external_docs[package] = e 00203 00204 # load in any external config files 00205 # TODO: check for rosdoc.yaml by default 00206 for e in m.get_export('rosdoc', 'config'): 00207 import yaml 00208 try: 00209 e = e.replace('${prefix}', path) 00210 config_p = os.path.join(path, e) 00211 with open(config_p, 'r') as config_f: 00212 rd_configs[package] = yaml.load(config_f) 00213 except Exception as e: 00214 sys.stderr.write("ERROR: unable to load rosdoc config file [%s]: %s\n"%(config_p, str(e))) 00215 00216 except: 00217 if self.should_document(package): 00218 sys.stderr.write("WARN: Package '%s' does not have a valid manifest.xml file, manifest information will not be included in docs\n"%(package)) 00219 bad.append(package) 00220 00221 for b in bad: 00222 if b in self.packages: 00223 del self.packages[b] 00224 stack_manifests = self.stack_manifests 00225 for stack, path in stacks.iteritems(): 00226 if not self.quiet: 00227 print "+stack[%s]"%(stack) 00228 00229 def compute_relative(src, target): 00230 s1, s2 = [p.split(os.sep) for p in [src, target]] 00231 #filter out empties 00232 s1, s2 = filter(lambda x: x, s1), filter(lambda x: x, s2) 00233 i = 0 00234 while i < min(len(s1), len(s2)): 00235 if s1[i] != s2[i]: 00236 break 00237 i+=1 00238 rel = ['..' for d in s1[i:]] + s2[i:] 00239 return os.sep.join(rel) 00240 00241 def html_path(package, docdir): 00242 return os.path.join(docdir, package, 'html') 00243 00244 00245 ################################################################################ 00246 # TEMPLATE ROUTINES 00247 00248 _TEMPLATES_DIR = 'templates' 00249 00250 def load_tmpl(filename): 00251 filename = os.path.join(roslib.packages.get_pkg_dir('rosdoc'), _TEMPLATES_DIR, filename) 00252 if not os.path.isfile(filename): 00253 sys.stderr.write("Cannot locate template file '%s'\n"%(filename)) 00254 sys.exit(1) 00255 f = open(filename, 'r') 00256 try: 00257 str = f.read() 00258 if not str: 00259 sys.stderr.write("Template file '%s' is empty\n"%(filename)) 00260 sys.exit(1) 00261 return str 00262 finally: 00263 f.close() 00264 00265 def li_package_links(ctx, package, packages, docdir, package_htmldir=None): 00266 """ 00267 @param package: current package 00268 @type package: str 00269 @param packages: list of packages to generate 'li' html links to 00270 @type packages: [str] 00271 """ 00272 # package_htmldir can be overridden by rosdoc config 00273 package_htmldir = package_htmldir or html_path(package, docdir) 00274 00275 # don't link to packages that aren't documentable 00276 documented_packages = [p for p in packages if ctx.should_document(p)] 00277 undocumented_packages = [p for p in packages if not ctx.should_document(p)] 00278 00279 documented = '\n'.join([' <li><a href="%s/index.html">%s</a></li>'%\ 00280 (compute_relative(package_htmldir, html_path(p, docdir)), p) for p in documented_packages]) 00281 undocumented = '\n'.join([' <li>%s</li>'%p for p in undocumented_packages]) 00282 return documented + undocumented + "\n</ul>" 00283 00284 00285 def instantiate_template(tmpl, vars): 00286 for k, v in vars.iteritems(): 00287 try: 00288 tmpl = tmpl.replace(k, str(v).encode('utf-8')) 00289 except: 00290 traceback.print_exc() 00291 return tmpl 00292 00293 00294 ################################################################################ 00295 # ROS package utilities 00296 00297 def generate_package_tree(ctx): 00298 """ 00299 Generate a tree representation of the available packages 00300 """ 00301 remaining_packages = set(ctx.doc_packages) 00302 00303 # step 1: assign stack packages 00304 stacks = roslib.stacks.list_stacks() 00305 # - fill out tree structure for packages in stacks 00306 packagetree = {} 00307 found_packages = set() 00308 for s in stacks: 00309 packagetree[s] = d = {} 00310 packages = roslib.stacks.packages_of(s) 00311 for p in packages: 00312 d[p] = {} 00313 found_packages.add(p) 00314 remaining_packages = set(ctx.doc_packages) - found_packages 00315 00316 # step 2: walk remaining packages 00317 def _gt_visitor(base, d, dirs, files): 00318 if os.path.isfile(os.path.join(d, 'manifest.xml')): 00319 package = os.path.basename(d) 00320 if package in remaining_packages: 00321 visited.append(package) 00322 rel = d[len(base):] 00323 treepath = [t for t in rel.split(os.sep) if t] 00324 node = packagetree 00325 for t in treepath: 00326 if not node.has_key(t): 00327 node[t] = {} 00328 node = node[t] 00329 return True 00330 else: 00331 # ignore 00332 pass 00333 elif os.path.isfile(os.path.join(d, 'rospack_nosubdirs')): 00334 return True 00335 return False 00336 00337 packages = ctx.packages 00338 rosroot = ctx.rosroot 00339 ros_package_path = ctx.ros_package_path 00340 00341 visited = [] 00342 paths = [rosroot] + ros_package_path.split(os.pathsep) 00343 paths = [p for p in paths if p] 00344 for p in paths: 00345 for d, dirs, files in os.walk(p, topdown=True): 00346 if _gt_visitor(p, d, dirs, files): 00347 del dirs[:] #don't descend further 00348 00349 return packagetree 00350