_setup_util.py
Go to the documentation of this file.
00001 #!/usr/bin/env python
00002 
00003 # Software License Agreement (BSD License)
00004 #
00005 # Copyright (c) 2012, Willow Garage, Inc.
00006 # All rights reserved.
00007 #
00008 # Redistribution and use in source and binary forms, with or without
00009 # modification, are permitted provided that the following conditions
00010 # are met:
00011 #
00012 #  * Redistributions of source code must retain the above copyright
00013 #    notice, this list of conditions and the following disclaimer.
00014 #  * Redistributions in binary form must reproduce the above
00015 #    copyright notice, this list of conditions and the following
00016 #    disclaimer in the documentation and/or other materials provided
00017 #    with the distribution.
00018 #  * Neither the name of Willow Garage, Inc. nor the names of its
00019 #    contributors may be used to endorse or promote products derived
00020 #    from this software without specific prior written permission.
00021 #
00022 # THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00023 # "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00024 # LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00025 # FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00026 # COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00027 # INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00028 # BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00029 # LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00030 # CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00031 # LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00032 # ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00033 # POSSIBILITY OF SUCH DAMAGE.
00034 
00035 '''This file generates shell code for the setup.SHELL scripts to set environment variables'''
00036 
00037 from __future__ import print_function
00038 import argparse
00039 import copy
00040 import os
00041 import platform
00042 import sys
00043 
00044 CATKIN_MARKER_FILE = '.catkin'
00045 
00046 system = platform.system()
00047 IS_DARWIN = (system == 'Darwin')
00048 IS_WINDOWS = (system == 'Windows')
00049 
00050 # subfolder of workspace prepended to CMAKE_PREFIX_PATH
00051 ENV_VAR_SUBFOLDERS = {
00052     'CMAKE_PREFIX_PATH': '',
00053     'CPATH': 'include',
00054     'LD_LIBRARY_PATH' if not IS_DARWIN else 'DYLD_LIBRARY_PATH': 'lib',
00055     'PATH': 'bin',
00056     'PKG_CONFIG_PATH': 'lib/pkgconfig',
00057     'PYTHONPATH': 'lib/python2.7/dist-packages',
00058 }
00059 
00060 
00061 def rollback_env_variables(environ, env_var_subfolders):
00062     '''
00063     Generate shell code to reset environment variables
00064     by unrolling modifications based on all workspaces in CMAKE_PREFIX_PATH.
00065     This does not cover modifications performed by environment hooks.
00066     '''
00067     lines = []
00068     unmodified_environ = copy.copy(environ)
00069     for key in sorted(env_var_subfolders.keys()):
00070         subfolder = env_var_subfolders[key]
00071         value = _rollback_env_variable(unmodified_environ, key, subfolder)
00072         if value is not None:
00073             environ[key] = value
00074             lines.append(assignment(key, value))
00075     if lines:
00076         lines.insert(0, comment('reset environment variables by unrolling modifications based on all workspaces in CMAKE_PREFIX_PATH'))
00077     return lines
00078 
00079 
00080 def _rollback_env_variable(environ, name, subfolder):
00081     '''
00082     For each catkin workspace in CMAKE_PREFIX_PATH remove the first entry from env[NAME] matching workspace + subfolder.
00083 
00084     :param subfolder: str '' or subfoldername that may start with '/'
00085     :returns: the updated value of the environment variable.
00086     '''
00087     value = environ[name] if name in environ else ''
00088     env_paths = [path for path in value.split(os.pathsep) if path]
00089     value_modified = False
00090     if subfolder:
00091         if subfolder.startswith(os.path.sep) or (os.path.altsep and subfolder.startswith(os.path.altsep)):
00092             subfolder = subfolder[1:]
00093         if subfolder.endswith(os.path.sep) or (os.path.altsep and subfolder.endswith(os.path.altsep)):
00094             subfolder = subfolder[:-1]
00095     for ws_path in _get_workspaces(environ, include_fuerte=True):
00096         path_to_find = os.path.join(ws_path, subfolder) if subfolder else ws_path
00097         path_to_remove = None
00098         for env_path in env_paths:
00099             env_path_clean = env_path[:-1] if env_path and env_path[-1] in [os.path.sep, os.path.altsep] else env_path
00100             if env_path_clean == path_to_find:
00101                 path_to_remove = env_path
00102                 break
00103         if path_to_remove:
00104             env_paths.remove(path_to_remove)
00105             value_modified = True
00106     new_value = os.pathsep.join(env_paths)
00107     return new_value if value_modified else None
00108 
00109 
00110 def _get_workspaces(environ, include_fuerte=False):
00111     '''
00112     Based on CMAKE_PREFIX_PATH return all catkin workspaces.
00113 
00114     :param include_fuerte: The flag if paths starting with '/opt/ros/fuerte' should be considered workspaces, ``bool``
00115     '''
00116     # get all cmake prefix paths
00117     env_name = 'CMAKE_PREFIX_PATH'
00118     value = environ[env_name] if env_name in environ else ''
00119     paths = [path for path in value.split(os.pathsep) if path]
00120     # remove non-workspace paths
00121     workspaces = [path for path in paths if os.path.isfile(os.path.join(path, CATKIN_MARKER_FILE)) or (include_fuerte and path.startswith('/opt/ros/fuerte'))]
00122     return workspaces
00123 
00124 
00125 def prepend_env_variables(environ, env_var_subfolders, workspaces):
00126     '''
00127     Generate shell code to prepend environment variables
00128     for the all workspaces.
00129     '''
00130     lines = []
00131     lines.append(comment('prepend folders of workspaces to environment variables'))
00132 
00133     paths = [path for path in workspaces.split(os.pathsep) if path]
00134 
00135     prefix = _prefix_env_variable(environ, 'CMAKE_PREFIX_PATH', paths, '')
00136     lines.append(prepend(environ, 'CMAKE_PREFIX_PATH', prefix))
00137 
00138     for key in sorted([key for key in env_var_subfolders.keys() if key != 'CMAKE_PREFIX_PATH']):
00139         subfolder = env_var_subfolders[key]
00140         prefix = _prefix_env_variable(environ, key, paths, subfolder)
00141         lines.append(prepend(environ, key, prefix))
00142     return lines
00143 
00144 
00145 def _prefix_env_variable(environ, name, paths, subfolder):
00146     '''
00147     Return the prefix to prepend to the environment variable NAME, adding any path in NEW_PATHS_STR without creating duplicate or empty items.
00148     '''
00149     value = environ[name] if name in environ else ''
00150     environ_paths = [path for path in value.split(os.pathsep) if path]
00151     checked_paths = []
00152     for path in paths:
00153         if subfolder:
00154             path = os.path.join(path, subfolder)
00155         # exclude any path already in env and any path we already added
00156         if path not in environ_paths and path not in checked_paths:
00157             checked_paths.append(path)
00158     prefix_str = os.pathsep.join(checked_paths)
00159     if prefix_str != '' and environ_paths:
00160         prefix_str += os.pathsep
00161     return prefix_str
00162 
00163 
00164 def assignment(key, value):
00165     if not IS_WINDOWS:
00166         return 'export %s="%s"' % (key, value)
00167     else:
00168         return 'set %s=%s' % (key, value)
00169 
00170 
00171 def comment(msg):
00172     if not IS_WINDOWS:
00173         return '# %s' % msg
00174     else:
00175         return 'REM %s' % msg
00176 
00177 
00178 def prepend(environ, key, prefix):
00179     if key not in environ or not environ[key]:
00180         return assignment(key, prefix)
00181     if not IS_WINDOWS:
00182         return 'export %s="%s$%s"' % (key, prefix, key)
00183     else:
00184         return 'set %s=%s%%%s%%' % (key, prefix, key)
00185 
00186 
00187 def find_env_hooks(environ, cmake_prefix_path):
00188     '''
00189     Generate shell code with found environment hooks
00190     for the all workspaces.
00191     '''
00192     lines = []
00193     lines.append(comment('found environment hooks in workspaces'))
00194 
00195     generic_env_hooks = []
00196     generic_env_hooks_workspace = []
00197     specific_env_hooks = []
00198     specific_env_hooks_workspace = []
00199     generic_env_hooks_by_filename = {}
00200     specific_env_hooks_by_filename = {}
00201     generic_env_hook_ext = 'bat' if IS_WINDOWS else 'sh'
00202     specific_env_hook_ext = environ['CATKIN_SHELL'] if not IS_WINDOWS and 'CATKIN_SHELL' in environ and environ['CATKIN_SHELL'] else None
00203     # remove non-workspace paths
00204     workspaces = [path for path in cmake_prefix_path.split(os.pathsep) if path and os.path.isfile(os.path.join(path, CATKIN_MARKER_FILE))]
00205     for workspace in reversed(workspaces):
00206         env_hook_dir = os.path.join(workspace, 'etc', 'catkin', 'profile.d')
00207         if os.path.isdir(env_hook_dir):
00208             for filename in sorted(os.listdir(env_hook_dir)):
00209                 if filename.endswith('.%s' % generic_env_hook_ext):
00210                     # remove previous env hook with same name if present
00211                     if filename in generic_env_hooks_by_filename:
00212                         i = generic_env_hooks.index(generic_env_hooks_by_filename[filename])
00213                         generic_env_hooks.pop(i)
00214                         generic_env_hooks_workspace.pop(i)
00215                     # append env hook
00216                     generic_env_hooks.append(os.path.join(env_hook_dir, filename))
00217                     generic_env_hooks_workspace.append(workspace)
00218                     generic_env_hooks_by_filename[filename] = generic_env_hooks[-1]
00219                 elif specific_env_hook_ext is not None and filename.endswith('.%s' % specific_env_hook_ext):
00220                     # remove previous env hook with same name if present
00221                     if filename in specific_env_hooks_by_filename:
00222                         i = specific_env_hooks.index(specific_env_hooks_by_filename[filename])
00223                         specific_env_hooks.pop(i)
00224                         specific_env_hooks_workspace.pop(i)
00225                     # append env hook
00226                     specific_env_hooks.append(os.path.join(env_hook_dir, filename))
00227                     specific_env_hooks_workspace.append(workspace)
00228                     specific_env_hooks_by_filename[filename] = specific_env_hooks[-1]
00229     env_hooks = generic_env_hooks + specific_env_hooks
00230     env_hooks_workspace = generic_env_hooks_workspace + specific_env_hooks_workspace
00231     count = len(env_hooks)
00232     lines.append(assignment('_CATKIN_ENVIRONMENT_HOOKS_COUNT', count))
00233     for i in range(count):
00234         lines.append(assignment('_CATKIN_ENVIRONMENT_HOOKS_%d' % i, env_hooks[i]))
00235         lines.append(assignment('_CATKIN_ENVIRONMENT_HOOKS_%d_WORKSPACE' % i, env_hooks_workspace[i]))
00236     return lines
00237 
00238 
00239 def _parse_arguments(args=None):
00240     parser = argparse.ArgumentParser(description='Generates code blocks for the setup.SHELL script.')
00241     parser.add_argument('--extend', action='store_true', help='Skip unsetting previous environment variables to extend context')
00242     return parser.parse_known_args(args=args)[0]
00243 
00244 
00245 if __name__ == '__main__':
00246     try:
00247         args = _parse_arguments()
00248     except Exception as e:
00249         print(e, file=sys.stderr)
00250         exit(1)
00251 
00252     # environment at generation time
00253     CMAKE_PREFIX_PATH = '/home/robbie/homer/catkin_ws/devel;/opt/ros/hydro'.split(';')
00254     # prepend current workspace if not already part of CPP
00255     base_path = os.path.dirname(__file__)
00256     if base_path not in CMAKE_PREFIX_PATH:
00257         CMAKE_PREFIX_PATH.insert(0, base_path)
00258     CMAKE_PREFIX_PATH = os.pathsep.join(CMAKE_PREFIX_PATH)
00259 
00260     environ = dict(os.environ)
00261     lines = []
00262     if not args.extend:
00263         lines += rollback_env_variables(environ, ENV_VAR_SUBFOLDERS)
00264     lines += prepend_env_variables(environ, ENV_VAR_SUBFOLDERS, CMAKE_PREFIX_PATH)
00265     lines += find_env_hooks(environ, CMAKE_PREFIX_PATH)
00266     print('\n'.join(lines))
00267     sys.exit(0)


or_libs
Author(s): raphael
autogenerated on Mon Oct 6 2014 02:53:18