1# Software License Agreement (BSD License)
2#
3# Copyright (c) 2012, Willow Garage, Inc.
4# All rights reserved.
5#
6# Redistribution and use in source and binary forms, with or without
7# modification, are permitted provided that the following conditions
8# are met:
9#
10#  * Redistributions of source code must retain the above copyright
11#    notice, this list of conditions and the following disclaimer.
12#  * Redistributions in binary form must reproduce the above
13#    copyright notice, this list of conditions and the following
14#    disclaimer in the documentation and/or other materials provided
15#    with the distribution.
16#  * Neither the name of Willow Garage, Inc. nor the names of its
17#    contributors may be used to endorse or promote products derived
18#    from this software without specific prior written permission.
19#
20# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
21# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
22# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
23# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
24# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
25# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
26# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
27# LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
28# CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
29# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
30# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
31# POSSIBILITY OF SUCH DAMAGE.
32
33from __future__ import print_function
34
35import copy
36import multiprocessing
37import os
38import platform
39import re
40try:
41    from shlex import quote
42except ImportError:
43    from pipes import quote
44import stat
45try:
46    from StringIO import StringIO
47except ImportError:
48    from io import StringIO
49import subprocess
50import sys
51
52try:
53    from catkin_pkg.cmake import configure_file, get_metapackage_cmake_template_path
54    from catkin_pkg.packages import find_packages
55    from catkin_pkg.tool_detection import get_previous_tool_used_on_the_space
56    from catkin_pkg.tool_detection import mark_space_as_built_by
57    from catkin_pkg.topological_order import topological_order_packages
58except ImportError as e:
59    sys.exit(
60        'ImportError: "from catkin_pkg.topological_order import '
61        'topological_order" failed: %s\nMake sure that you have installed '
62        '"catkin_pkg", it is up to date and on the PYTHONPATH.' % e
63    )
64
65from catkin.cmake import get_cmake_path
66
67from catkin_pkg.package import InvalidPackage
68from catkin_pkg.terminal_color import ansi, disable_ANSI_colors, fmt, sanitize
69from catkin_pkg.workspaces import ensure_workspace_marker
70
71
72def determine_path_argument(cwd, base_path, argument, default):
73    if argument is None:
74        # if no argument is passed the default is relative to the base_path
75        path = os.path.join(base_path, default)
76    else:
77        # if an argument is passed it is relative to cwd (or absolute)
78        path = os.path.abspath(os.path.join(cwd, argument))
79    return path
80
81
82def split_arguments(args, splitter_name, default=None):
83    if splitter_name not in args:
84        return args, default
85    index = args.index(splitter_name)
86    return args[0:index], args[index + 1:]
87
88
89def extract_cmake_and_make_arguments(args):
90    args, cmake_args, make_args, _ = _extract_cmake_and_make_arguments(args, extract_catkin_make=False)
91    return args, cmake_args, make_args
92
93
94def extract_cmake_and_make_and_catkin_make_arguments(args):
95    return _extract_cmake_and_make_arguments(args, extract_catkin_make=True)
96
97
98def _extract_cmake_and_make_arguments(args, extract_catkin_make):
99    cmake_args = []
100    make_args = []
101    catkin_make_args = []
102
103    arg_types = {
104        '--cmake-args': cmake_args,
105        '--make-args': make_args
106    }
107    if extract_catkin_make:
108        arg_types['--catkin-make-args'] = catkin_make_args
109
110    arg_indexes = {}
111    for k in arg_types.keys():
112        if k in args:
113            arg_indexes[args.index(k)] = k
114
115    for index in reversed(sorted(arg_indexes.keys())):
116        arg_type = arg_indexes[index]
117        args, specific_args = split_arguments(args, arg_type)
118        arg_types[arg_type].extend(specific_args)
119
120    # classify -D* and -G* arguments as cmake specific arguments
121    implicit_cmake_args = [a for a in args if a.startswith('-D') or a.startswith('-G')]
122    args = [a for a in args if a not in implicit_cmake_args]
123
124    return args, implicit_cmake_args + cmake_args, make_args, catkin_make_args
125
126
127def cprint(msg, end=None):
128    print(fmt(msg), end=end)
129
130
131def colorize_line(line):
132    cline = sanitize(line)
133    cline = cline.replace(
134        '-- ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~',
135        '-- @{pf}~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~@|'
136    )
137    if line.startswith('-- ~~'):
138        # -- ~~  -
139        cline = cline.replace('~~ ', '@{pf}~~ @|')
140        cline = cline.replace(' - ', ' - @!@{bf}')
141        cline = cline.replace('(', '@|(')
142        cline = cline.replace('(plain cmake)', '@|(@{rf}plain cmake@|)')
143        cline = cline.replace('(unknown)', '@|(@{yf}unknown@|)')
144    if line.startswith('-- +++'):
145        # -- +++ add_subdirectory(package)
146        cline = cline.replace('+++', '@!@{gf}+++@|')
147        cline = cline.replace("kin package: '", "kin package: '@!@{bf}")
148        cline = cline.replace(')', '@|)')
149        cline = cline.replace("'\n", "@|'\n")
150        cline = cline.replace("cmake package: '", "cmake package: '@!@{bf}")
151        cline = cline.replace("'\n", "@|'\n")
152    if line.startswith('-- ==>'):
153        cline = cline.replace('-- ==>', '-- @!@{bf}==>@|')
154    if line.lower().startswith('warning'):
155        # WARNING
156        cline = ansi('yf') + cline
157    if line.startswith('CMake Warning'):
158        # CMake Warning...
159        cline = cline.replace('CMake Warning', '@{yf}@!CMake Warning@|')
160    if line.startswith('ERROR:'):
161        # ERROR:
162        cline = cline.replace('ERROR:', '@!@{rf}ERROR:@|')
163    if line.startswith('CMake Error'):
164        # CMake Error...
165        cline = cline.replace('CMake Error', '@{rf}@!CMake Error@|')
166    if line.startswith('Call Stack (most recent call first):'):
167        # CMake Call Stack
168        cline = cline.replace('Call Stack (most recent call first):',
169                              '@{cf}@_Call Stack (most recent call first):@|')
170    return fmt(cline)
171
172
173def print_command_banner(cmd, cwd, color):
174    if color:
175        # Prepare for printing
176        cmd_str = sanitize(' '.join(cmd))
177        cwd_str = sanitize(cwd)
178        # Print command notice
179        cprint('@{bf}####')
180        cprint('@{bf}#### Running command: @!"%s"@|@{bf} in @!"%s"' % (cmd_str, cwd_str))
181        cprint('@{bf}####')
182    else:
183        print('####')
184        print('#### Running command: "%s" in "%s"' % (' '.join(cmd), cwd))
185        print('####')
186
187
188def run_command_colorized(cmd, cwd, quiet=False, add_env=None):
189    run_command(cmd, cwd, quiet=quiet, colorize=True, add_env=add_env)
190
191
192def run_command(cmd, cwd, quiet=False, colorize=False, add_env=None):
193    capture = (quiet or colorize)
194    stdout_pipe = subprocess.PIPE if capture else None
195    stderr_pipe = subprocess.STDOUT if capture else None
196    env = None
197    if add_env:
198        env = copy.copy(os.environ)
199        env.update(add_env)
200    try:
201        proc = subprocess.Popen(
202            cmd, cwd=cwd, shell=False,
203            stdout=stdout_pipe, stderr=stderr_pipe,
204            env=env
205        )
206    except OSError as e:
207        raise OSError("Failed command '%s': %s" % (cmd, e))
208    out = StringIO() if quiet else sys.stdout
209    if capture:
210        while True:
211            line = proc.stdout.readline()
212            try:
213                # try decoding in case the output is encoded
214                line = line.decode('utf8', 'replace')
215            except (AttributeError, UnicodeEncodeError):
216                # do nothing for Python 3 when line is already a str
217                # or when the string can't be decoded
218                pass
219
220            # ensure that it is convertable to the target encoding
221            encoding = 'utf8'
222            try:
223                if out.encoding:
224                    encoding = out.encoding
225            except AttributeError:
226                # do nothing for Python 2
227                pass
228            line = line.encode(encoding, 'replace')
229            line = line.decode(encoding, 'replace')
230
231            if proc.returncode is not None or not line:
232                break
233            try:
234                line = colorize_line(line) if colorize else line
235            except Exception as e:
236                import traceback
237                traceback.print_exc()
238                print('<caktin_make> color formatting problem: ' + str(e),
239                      file=sys.stderr)
240            out.write(line)
241    proc.wait()
242    if proc.returncode:
243        if quiet:
244            print(out.getvalue())
245        raise subprocess.CalledProcessError(proc.returncode, cmd)
246    return out.getvalue() if quiet else ''
247
248
249blue_arrow = '@!@{bf}==>@|@!'
250
251
252def _check_build_dir(name, workspace, buildspace):
253    package_build_dir = os.path.join(buildspace, name)
254    if not os.path.exists(package_build_dir):
255        cprint(
256            blue_arrow + " Creating build directory: '" +
257            os.path.relpath(package_build_dir, workspace) + "'@|"
258        )
259        os.makedirs(package_build_dir)
260    return package_build_dir
261
262
263def isolation_print_command(cmd, path=None, add_env=None):
264    cprint(
265        blue_arrow + ' ' + sanitize(cmd) + '@|' +
266        (" @!@{kf}in@| '@!" + sanitize(path) + "@|'" if path else '') +
267        (" @!@{kf}with@| '@!" + ' '.join(['%s=%s' % (k, v) for k, v in add_env.items()]) + "@|'" if add_env else '')
268    )
269
270
271def get_multiarch():
272    if not sys.platform.lower().startswith('linux'):
273        return ''
274    # this function returns the suffix for lib directories on supported systems or an empty string
275    # it uses two step approach to look for multiarch: first run gcc -print-multiarch and if
276    # failed try to run dpkg-architecture
277    p = subprocess.Popen(
278        ['gcc', '-print-multiarch'],
279        stdout=subprocess.PIPE, stderr=subprocess.PIPE)
280    out = p.communicate()[0].decode('utf-8')
281    if p.returncode != 0:
282        out = subprocess.Popen(
283            ['dpkg-architecture', '-qDEB_HOST_MULTIARCH'],
284            stdout=subprocess.PIPE, stderr=subprocess.PIPE).communicate()[0].decode('utf-8')
285
286    # be sure of returning empty string or a valid multiarch tuple format
287    assert(not out.strip() or out.strip().count('-') == 2)
288    return out.strip()
289
290
291def get_python_install_dir():
292    # this function returns the same value as the CMake variable PYTHON_INSTALL_DIR from catkin/cmake/python.cmake
293    python_install_dir = 'lib'
294    python_use_debian_layout = os.path.exists('/etc/debian_version')
295    if os.name != 'nt':
296        python_version_xdoty = str(sys.version_info[0]) + '.' + str(sys.version_info[1])
297        if python_use_debian_layout and sys.version_info[0] == 3:
298            python_version_xdoty = str(sys.version_info[0])
299        python_install_dir = os.path.join(python_install_dir, 'python' + python_version_xdoty)
300
301    python_packages_dir = 'dist-packages' if python_use_debian_layout else 'site-packages'
302    python_install_dir = os.path.join(python_install_dir, python_packages_dir)
303    return python_install_dir
304
305
306def handle_make_arguments(input_make_args, append_default_jobs_flags=True):
307    make_args = list(input_make_args)
308
309    # If no -j/--jobs/-l/--load-average flags are in make_args
310    if not extract_jobs_flags(' '.join(make_args)):
311        # If -j/--jobs/-l/--load-average are in MAKEFLAGS
312        if 'MAKEFLAGS' in os.environ and extract_jobs_flags(os.environ['MAKEFLAGS']):
313            # Do not extend make arguments, let MAKEFLAGS set things
314            pass
315        else:
316            # Else extend the make_arguments to include some jobs flags
317            # If ROS_PARALLEL_JOBS is set use those flags
318            if 'ROS_PARALLEL_JOBS' in os.environ:
319                # ROS_PARALLEL_JOBS is a set of make variables, not just a number
320                ros_parallel_jobs = os.environ['ROS_PARALLEL_JOBS']
321                make_args.extend(ros_parallel_jobs.split())
322            elif append_default_jobs_flags:
323                # Else Use the number of CPU cores
324                try:
325                    jobs = multiprocessing.cpu_count()
326                    make_args.append('-j{0}'.format(jobs))
327                    make_args.append('-l{0}'.format(jobs))
328                except NotImplementedError:
329                    # If the number of cores cannot be determined, do not extend args
330                    pass
331    return make_args
332
333
334def extract_jobs_flags(mflags):
335    regex = r'(?:^|\s)(-?(?:j|l)(?:\s*[0-9]+|\s|$))' + \
336            r'|' + \
337            r'(?:^|\s)((?:--)?(?:jobs|load-average)(?:(?:=|\s+)[0-9]+|(?:\s|$)))'
338    matches = re.findall(regex, mflags) or []
339    matches = [m[0] or m[1] for m in matches]
340    return ' '.join([m.strip() for m in matches]) if matches else None
341
342
343def build_catkin_package(
344    path, package,
345    workspace, buildspace, develspace, installspace,
346    install, force_cmake, quiet, last_env, cmake_args, make_args,
347    destdir=None, use_ninja=False, use_nmake=False, use_gmake=False
348):
349    cprint(
350        "Processing @{cf}catkin@| package: '@!@{bf}" +
351        package.name + "@|'"
352    )
353
354    # Make the build dir
355    build_dir = _check_build_dir(package.name, workspace, buildspace)
356
357    # Check last_env
358    if last_env is not None:
359        cprint(
360            blue_arrow + ' Building with env: ' +
361            "'{0}'".format(sanitize(last_env))
362        )
363
364    # Check for Makefile and maybe call cmake
365    if not use_ninja:
366        makefile_name = 'Makefile'
367    else:
368        makefile_name = 'build.ninja'
369    makefile = os.path.join(build_dir, makefile_name)
370    if not os.path.exists(makefile) or force_cmake:
371        package_dir = os.path.dirname(package.filename)
372        if not os.path.exists(os.path.join(package_dir, 'CMakeLists.txt')):
373            export_tags = [e.tagname for e in package.exports]
374            if 'metapackage' not in export_tags:
375                print(colorize_line('Error: Package "%s" does not have a CMakeLists.txt file' % package.name))
376                sys.exit('Can not build catkin package without CMakeLists.txt file')
377            # generate CMakeLists.txt for metpackages without one
378            print(colorize_line('Warning: metapackage "%s" should have a CMakeLists.txt file' % package.name))
379            cmake_code = configure_file(
380                get_metapackage_cmake_template_path(),
381                {'name': package.name, 'metapackage_arguments': 'DIRECTORY "%s"' % package_dir})
382            cmakelists_txt = os.path.join(build_dir, 'CMakeLists.txt')
383            with open(cmakelists_txt, 'w') as f:
384                f.write(cmake_code)
385            package_dir = build_dir
386
387        # Run cmake
388        cmake_cmd = [
389            'cmake',
390            package_dir,
391            '-DCATKIN_DEVEL_PREFIX=' + develspace,
392            '-DCMAKE_INSTALL_PREFIX=' + installspace
393        ]
394        cmake_cmd.extend(cmake_args)
395        add_env = get_additional_environment(install, destdir, installspace)
396        isolation_print_command(' '.join(cmake_cmd), build_dir, add_env=add_env)
397        if last_env is not None:
398            cmake_cmd = [last_env] + cmake_cmd
399        try:
400            run_command_colorized(cmake_cmd, build_dir, quiet, add_env=add_env)
401        except subprocess.CalledProcessError:
402            if os.path.exists(makefile):
403                # remove Makefile to force CMake invocation next time
404                os.remove(makefile)
405            raise
406    else:
407        print('%s exists, skipping explicit cmake invocation...' % makefile_name)
408        # Check to see if cmake needs to be run via make
409        if use_ninja:
410            make_check_cmake_cmd = ['ninja', 'build.ninja']
411        elif use_nmake:
412            make_check_cmake_cmd = ['nmake', 'cmake_check_build_system']
413        elif use_gmake:
414            make_check_cmake_cmd = ['gmake', 'cmake_check_build_system']
415        else:
416            make_check_cmake_cmd = ['make', 'cmake_check_build_system']
417
418        add_env = get_additional_environment(install, destdir, installspace)
419        isolation_print_command(' '.join(make_check_cmake_cmd), build_dir, add_env=add_env)
420        if last_env is not None:
421            make_check_cmake_cmd = [last_env] + make_check_cmake_cmd
422        run_command_colorized(
423            make_check_cmake_cmd, build_dir, quiet, add_env=add_env
424        )
425
426    # Run make
427    if use_ninja:
428        make_executable = 'ninja'
429    elif use_nmake:
430        make_executable = 'nmake'
431    elif use_gmake:
432        make_executable = 'gmake'
433    else:
434        make_executable = 'make'
435
436    make_cmd = [make_executable]
437    make_cmd.extend(handle_make_arguments(make_args, append_default_jobs_flags=not use_nmake))
438    isolation_print_command(' '.join(make_cmd), build_dir)
439    if last_env is not None:
440        make_cmd = [last_env] + make_cmd
441    run_command(make_cmd, build_dir, quiet)
442
443    # Make install
444    # NMake doesn't have an option to list target so try it anyway
445    if install or use_nmake:
446        if has_make_target(build_dir, 'install', use_ninja=use_ninja, use_nmake=use_nmake, use_gmake=use_gmake):
447            make_install_cmd = [make_executable, 'install']
448            isolation_print_command(' '.join(make_install_cmd), build_dir)
449            if last_env is not None:
450                make_install_cmd = [last_env] + make_install_cmd
451            run_command(make_install_cmd, build_dir, quiet)
452        else:
453            print(fmt(
454                '@{yf}Package has no "@{boldon}install@{boldoff}" target, skipping "%s install" invocation...'
455                % make_executable))
456
457
458def has_make_target(path, target, use_ninja=False, use_nmake=False, use_gmake=False):
459    if use_ninja:
460        output = run_command(['ninja', '-t', 'targets'], path, quiet=True)
461    elif use_nmake:
462        output = run_command(['nmake', '/PNC'], path, quiet=True)
463    elif use_gmake:
464        output = run_command(['gmake', '-pn'], path, quiet=True)
465    else:
466        output = run_command(['make', '-pn'], path, quiet=True)
467    lines = output.splitlines()
468    # strip nanja warnings since they look similar to targets
469    if use_ninja:
470        lines = [l for l in lines if not l.startswith('ninja: warning:')]
471    targets = [m.group(1) for m in [re.match(r'^([a-zA-Z0-9][a-zA-Z0-9_\.]*):', l) for l in lines] if m]
472    return target in targets
473
474
475def get_additional_environment(install, destdir, installspace):
476    add_env = {}
477    if install and destdir:
478        # exclude drive letter if on Windows, returns the same string on Linux since there is no drive specifications
479        _, installspace = os.path.splitdrive(installspace)
480
481        add_env['_CATKIN_SETUP_DIR'] = os.path.join(destdir, installspace[1:])
482    return add_env
483
484
485def write_env_bat(dest_file, variables):
486    env_bat_template = """\
487@echo off
488REM generated from catkin.builder Python module
489
490if "%1"=="" (
491  echo "Usage: env.bat COMMANDS"
492  echo "Calling env.bat without arguments is not supported anymore. Instead spawn a subshell and source a setup file manually."
493  exit 1
494) else (
495  call "{SETUP_DIR}\\{SETUP_FILENAME}.bat"
496  %*
497)
498"""
499    with open(dest_file, 'w') as f:
500        f.write(env_bat_template.format(**variables))
501
502
503def write_setup_bat(dest_file, last_setup_basename, variables):
504    setup_bat_header = """\
505@echo off
506REM generated from catkin.builder Python module
507"""
508    setup_bat_template = """\
509REM Prepend to the environment
510set CMAKE_PREFIX_PATH={cmake_prefix_path};%CMAKE_PREFIX_PATH%
511set LD_LIBRARY_PATH={ld_path};%LD_LIBRARY_PATH%
512set PATH={path};%PATH%
513set PKG_CONFIG_PATH={pkgcfg_path};%PKG_CONFIG_PATH%
514set PYTHONPATH={pythonpath};%PYTHONPATH%
515"""
516    with open(dest_file, 'w') as f:
517        f.write(setup_bat_header)
518        if last_setup_basename is not None:
519            f.write('call "%s.bat"\n\n' % last_setup_basename)
520        f.write(setup_bat_template.format(**variables))
521
522
523def write_env_sh(dest_file, variables):
524    env_sh_template = """\
525#!/usr/bin/env sh
526# generated from catkin.builder Python module
527
528if [ $# -eq 0 ] ; then
529  /bin/echo "Usage: env.sh COMMANDS"
530  /bin/echo "Calling env.sh without arguments is not supported anymore. \
531Instead spawn a subshell and source a setup file manually."
532  exit 1
533fi
534
535# ensure to not use different shell type which was set before
536CATKIN_SHELL=sh
537
538# source {SETUP_FILENAME}.sh from same directory as this file
539. "$(cd "`dirname "$0"`" && pwd)/{SETUP_FILENAME}.sh"
540exec "$@"
541"""
542    with open(os.path.join(dest_file), 'w') as f:
543        f.write(env_sh_template.format(**variables))
544    os.chmod(dest_file, stat.S_IXUSR | stat.S_IWUSR | stat.S_IRUSR)
545
546
547def write_setup_sh(dest_file, last_setup_basename, variables):
548    setup_sh_header = """\
549#!/usr/bin/env sh
550# generated from catkin.builder Python module
551
552# remember type of shell if not already set
553if [ -z "$CATKIN_SHELL" ]; then
554  CATKIN_SHELL=sh
555fi
556"""
557    setup_sh_template = """\
558# detect if running on Darwin platform
559_UNAME=`uname -s`
560IS_DARWIN=0
561if [ "$_UNAME" = "Darwin" ]; then
562  IS_DARWIN=1
563fi
564
565# Prepend to the environment
566export CMAKE_PREFIX_PATH="{cmake_prefix_path}:$CMAKE_PREFIX_PATH"
567if [ $IS_DARWIN -eq 0 ]; then
568  export LD_LIBRARY_PATH="{ld_path}:$LD_LIBRARY_PATH"
569else
570  export DYLD_LIBRARY_PATH="{ld_path}:$DYLD_LIBRARY_PATH"
571fi
572export PATH="{path}:$PATH"
573export PKG_CONFIG_PATH="{pkgcfg_path}:$PKG_CONFIG_PATH"
574export PYTHONPATH="{pythonpath}:$PYTHONPATH"
575"""
576    with open(dest_file, 'w') as f:
577        f.write(setup_sh_header)
578        if last_setup_basename is not None:
579            f.write('. "%s.$CATKIN_SHELL"\n\n' % last_setup_basename)
580        f.write(setup_sh_template.format(**variables))
581
582
583def build_cmake_package(
584    path, package,
585    workspace, buildspace, develspace, installspace,
586    install, force_cmake, quiet, last_env, cmake_args, make_args,
587    destdir=None, use_ninja=False, use_nmake=False, use_gmake=False
588):
589    # Notify the user that we are processing a plain cmake package
590    cprint(
591        "Processing @{cf}plain cmake@| package: '@!@{bf}" + package.name +
592        "@|'"
593    )
594
595    # Make the build dir
596    if install:
597        build_dir_name = '%s%sinstall' % (package.name, os.sep)
598    else:
599        build_dir_name = '%s%sdevel' % (package.name, os.sep)
600    build_dir = _check_build_dir(build_dir_name, workspace, buildspace)
601
602    # Check last_env
603    if last_env is not None:
604        cprint(blue_arrow + ' Building with env: ' +
605               "'{0}'".format(sanitize(last_env)))
606
607    # Check for Makefile and maybe call cmake
608    if not use_ninja:
609        makefile_name = 'Makefile'
610    else:
611        makefile_name = 'build.ninja'
612    makefile = os.path.join(build_dir, makefile_name)
613    install_target = installspace if install else develspace
614    if not os.path.exists(makefile) or force_cmake:
615        # Call cmake
616        cmake_cmd = [
617            'cmake',
618            os.path.dirname(package.filename),
619            '-DCMAKE_INSTALL_PREFIX=' + install_target
620        ]
621        cmake_cmd.extend(cmake_args)
622        isolation_print_command(' '.join(cmake_cmd), build_dir)
623        if last_env is not None:
624            cmake_cmd = [last_env] + cmake_cmd
625        run_command_colorized(cmake_cmd, build_dir, quiet)
626    else:
627        print('%s exists, skipping explicit cmake invocation...' % makefile_name)
628        # Check to see if cmake needs to be run via make
629        if use_ninja:
630            make_check_cmake_cmd = ['ninja', 'build.ninja']
631        elif use_nmake:
632            make_check_cmake_cmd = ['nmake', 'cmake_check_build_system']
633        elif use_gmake:
634            make_check_cmake_cmd = ['gmake', 'cmake_check_build_system']
635        else:
636            make_check_cmake_cmd = ['make', 'cmake_check_build_system']
637
638        isolation_print_command(' '.join(make_check_cmake_cmd), build_dir)
639        if last_env is not None:
640            make_check_cmake_cmd = [last_env] + make_check_cmake_cmd
641        run_command_colorized(
642            make_check_cmake_cmd, build_dir, quiet
643        )
644
645    # Run make
646    if use_ninja:
647        make_executable = 'ninja'
648    elif use_nmake:
649        make_executable = 'nmake'
650    elif use_gmake:
651        make_executable = 'gmake'
652    else:
653        make_executable = 'make'
654    make_cmd = [make_executable]
655    make_cmd.extend(handle_make_arguments(make_args, append_default_jobs_flags=not use_nmake))
656    isolation_print_command(' '.join(make_cmd), build_dir)
657    if last_env is not None:
658        make_cmd = [last_env] + make_cmd
659    if install:
660        run_command(make_cmd, build_dir, quiet)
661    else:
662        run_command(make_cmd, build_dir, quiet, add_env={'DESTDIR': ''})
663
664    # Make install
665    make_install_cmd = [make_executable, 'install']
666    isolation_print_command(' '.join(make_install_cmd), build_dir)
667    if last_env is not None:
668        make_install_cmd = [last_env] + make_install_cmd
669    run_command(make_install_cmd, build_dir, quiet)
670
671    env_script = 'env' + ('.bat' if sys.platform == 'win32' else '.sh')
672    # If an env script already exists, don't overwrite it
673    if install and os.path.exists(prefix_destdir(os.path.join(install_target, env_script), destdir)):
674        return
675    cprint(blue_arrow + ' Generating an ' + env_script)
676    # Generate env script for chaining to catkin packages
677    # except if using --merge which implies that new_env_path equals last_env
678    new_env_path = os.path.join(install_target, env_script)
679    if install:
680        new_env_path = prefix_destdir(new_env_path, destdir)
681    if new_env_path != last_env:
682        variables = {
683            'SETUP_DIR': install_target,
684            'SETUP_FILENAME': 'setup'
685        }
686        if not os.path.exists(os.path.dirname(new_env_path)):
687            os.makedirs(os.path.dirname(new_env_path))
688        env_script_writer = write_env_bat if sys.platform == 'win32' else write_env_sh
689        env_script_writer(dest_file=new_env_path, variables=variables)
690
691    # Generate setup script for chaining to catkin packages
692    # except if using --merge which implies that new_setup_path equals last_setup_env
693    setup_script = 'setup' + ('.bat' if sys.platform == 'win32' else '.sh')
694    new_setup_path = os.path.join(install_target, setup_script)
695    if install:
696        new_setup_path = prefix_destdir(new_setup_path, destdir)
697    last_setup_env = os.path.join(os.path.dirname(last_env), setup_script) if last_env is not None else None
698    if new_setup_path != last_setup_env:
699        subs = {}
700        # CMAKE_PREFIX_PATH uses forward slash on all platforms.
701        subs['cmake_prefix_path'] = install_target.replace(os.sep, '/')
702        subs['ld_path'] = os.path.join(install_target, 'lib')
703        pythonpath = os.path.join(install_target, get_python_install_dir())
704        subs['pythonpath'] = pythonpath
705        subs['pkgcfg_path'] = os.path.join(install_target, 'lib', 'pkgconfig')
706        subs['path'] = os.path.join(install_target, 'bin')
707        arch = get_multiarch()
708        if arch:
709            subs['ld_path'] = os.pathsep.join([subs['ld_path'], os.path.join(install_target, 'lib', arch)])
710            subs['pkgcfg_path'] = os.pathsep.join([subs['pkgcfg_path'], os.path.join(install_target, 'lib', arch, 'pkgconfig')])
711        if not os.path.exists(os.path.dirname(new_setup_path)):
712            os.mkdir(os.path.dirname(new_setup_path))
713        setup_script_writer = write_setup_bat if sys.platform == 'win32' else write_setup_sh
714        last_setup_basename = os.path.splitext(last_setup_env)[0] if last_setup_env is not None else None
715        setup_script_writer(dest_file=new_setup_path, last_setup_basename=last_setup_basename, variables=subs)
716
717        if sys.platform != 'win32':
718            # generate setup.bash|zsh scripts
719            setup_script_template = """\
720#!/usr/bin/env {1}
721# generated from catkin.builder Python module
722
723CATKIN_SHELL={1}
724. "{0}/setup.sh"
725"""
726            for shell in ['bash', 'zsh']:
727                setup_path = os.path.join(install_target, 'setup.%s' % shell)
728                if install:
729                    setup_path = prefix_destdir(setup_path, destdir)
730                with open(setup_path, 'w') as f:
731                    f.write(setup_script_template.format(os.path.dirname(setup_path), shell))
732
733
734def build_package(
735    path, package,
736    workspace, buildspace, develspace, installspace,
737    install, force_cmake, quiet, last_env, cmake_args, make_args, catkin_make_args,
738    destdir=None, use_ninja=False, use_nmake=False, use_gmake=False,
739    number=None, of=None
740):
741    if platform.system() in ['Linux', 'Darwin'] and sys.stdout.isatty():
742        status_msg = '{package_name} [{number} of {total}]'.format(package_name=package.name, number=number, total=of)
743        sys.stdout.write('\x1b]2;' + status_msg + '\x07')
744    cprint('@!@{gf}==>@| ', end='')
745    new_last_env = get_new_env(package, develspace, installspace, install, last_env, destdir)
746    try:
747        build_type = package.get_build_type()
748    except InvalidPackage as e:
749        sys.exit(str(e))
750    if build_type == 'catkin':
751        build_catkin_package(
752            path, package,
753            workspace, buildspace, develspace, installspace,
754            install, force_cmake, quiet, last_env, cmake_args, make_args + catkin_make_args,
755            destdir=destdir, use_ninja=use_ninja, use_nmake=use_nmake, use_gmake=use_gmake
756        )
757        if not os.path.exists(new_last_env):
758            raise RuntimeError(
759                "No env.sh file generated at: '" + new_last_env +
760                "'\n  This sometimes occurs when a non-catkin package is "
761                'interpreted as a catkin package.\n  This can also occur '
762                'when the cmake cache is stale, try --force-cmake.'
763            )
764    elif build_type == 'cmake':
765        build_cmake_package(
766            path, package,
767            workspace, buildspace, develspace, installspace,
768            install, force_cmake, quiet, last_env, cmake_args, make_args,
769            destdir=destdir, use_ninja=use_ninja, use_nmake=use_nmake, use_gmake=use_gmake
770        )
771    else:
772        sys.exit('Can not build package with unknown build_type')
773    if number is not None and of is not None:
774        msg = ' [@{gf}@!' + str(number) + '@| of @!@{gf}' + str(of) + '@|]'
775    else:
776        msg = ''
777    cprint('@{gf}<==@| Finished processing package' + msg + ": '@{bf}@!" +
778           package.name + "@|'")
779    return new_last_env
780
781
782def get_new_env(package, develspace, installspace, install, last_env, destdir=None):
783    env_script = 'env.bat' if sys.platform == 'win32' else 'env.sh'
784    new_env = None
785    try:
786        build_type = package.get_build_type()
787    except InvalidPackage as e:
788        sys.exit(str(e))
789    if build_type in ['catkin', 'cmake']:
790        new_env = os.path.join(
791            installspace if install else develspace,
792            env_script
793        )
794        if install:
795            new_env = prefix_destdir(new_env, destdir)
796    return new_env
797
798
799def prefix_destdir(path, destdir=None):
800    if destdir is not None:
801        # exclude drive letter if on Windows, returns the same string on Linux since there is no drive specifications
802        _, path = os.path.splitdrive(path)
803
804        path = os.path.join(destdir, path[1:])
805    return path
806
807
808def _print_build_error(package, e):
809    e_msg = 'KeyboardInterrupt' if isinstance(e, KeyboardInterrupt) else str(e)
810    cprint("@{rf}@!<==@| Failed to process package '@!@{bf}" + package.name + "@|': \n  " + e_msg)
811
812
813def build_workspace_isolated(
814    workspace='.',
815    sourcespace=None,
816    buildspace=None,
817    develspace=None,
818    installspace=None,
819    merge=False,
820    install=False,
821    force_cmake=False,
822    colorize=True,
823    build_packages=None,
824    ignore_packages=None,
825    quiet=False,
826    cmake_args=None,
827    make_args=None,
828    catkin_make_args=None,
829    continue_from_pkg=False,
830    only_pkg_with_deps=None,
831    destdir=None,
832    use_ninja=False,
833    use_nmake=False,
834    use_gmake=False,
835    override_build_tool_check=False
836):
837    """
838    Run ``cmake``, ``make`` and optionally ``make install`` for all catkin packages in sourcespace_dir.
839
840    It creates several folders
841    in the current working directory. For non-catkin packages it runs
842    ``cmake``, ``make`` and ``make install`` for each, installing it to
843    the devel space or install space if the ``install`` option is specified.
844
845    :param workspace: path to the current workspace, ``str``
846    :param sourcespace: workspace folder containing catkin packages, ``str``
847    :param buildspace: path to build space location, ``str``
848    :param develspace: path to devel space location, ``str``
849    :param installspace: path to install space (CMAKE_INSTALL_PREFIX), ``str``
850    :param merge: if True, build each catkin package into the same
851        devel space (not affecting plain cmake packages), ``bool``
852    :param install: if True, install all packages to the install space,
853        ``bool``
854    :param force_cmake: (optional), if True calls cmake explicitly for each
855        package, ``bool``
856    :param colorize: if True, colorize cmake output and other messages,
857        ``bool``
858    :param build_packages: specific packages to build (all parent packages
859        in the topological order must have been built before), ``str``
860    :param quiet: if True, hides some build output, ``bool``
861    :param cmake_args: additional arguments for cmake, ``[str]``
862    :param make_args: additional arguments for make, ``[str]``
863    :param catkin_make_args: additional arguments for make but only for catkin
864        packages, ``[str]``
865    :param continue_from_pkg: indicates whether or not cmi should continue
866        when a package is reached, ``bool``
867    :param only_pkg_with_deps: only consider the specific packages and their
868        recursive dependencies and ignore all other packages in the workspace,
869        ``[str]``
870    :param destdir: define DESTDIR for cmake/invocation, ``string``
871    :param use_ninja: if True, use ninja instead of make, ``bool``
872    :param use_nmake: if True, use nmake instead of make, ``bool``
873    :param use_gmake: if True, use gmake instead of make, ``bool``
874    :param override_build_tool_check: if True, build even if a space was built
875        by another tool previously.
876    """
877    if not colorize:
878        disable_ANSI_colors()
879
880    # Check workspace existance
881    if not os.path.exists(workspace):
882        sys.exit("Workspace path '{0}' does not exist.".format(workspace))
883    workspace = os.path.abspath(workspace)
884
885    # Check source space existance
886    if sourcespace is None:
887        sourcespace = os.path.join(workspace, 'src')
888    if not os.path.exists(sourcespace):
889        sys.exit('Could not find source space: {0}'.format(sourcespace))
890    print('Base path: ' + str(workspace))
891    print('Source space: ' + str(sourcespace))
892
893    # Check build space
894    if buildspace is None:
895        buildspace = os.path.join(workspace, 'build_isolated')
896    if not os.path.exists(buildspace):
897        os.mkdir(buildspace)
898    print('Build space: ' + str(buildspace))
899
900    # ensure the build space was previously built by catkin_make_isolated
901    previous_tool = get_previous_tool_used_on_the_space(buildspace)
902    if previous_tool is not None and previous_tool != 'catkin_make_isolated':
903        if override_build_tool_check:
904            print(fmt(
905                "@{yf}Warning: build space at '%s' was previously built by '%s', "
906                'but --override-build-tool-check was passed so continuing anyways.'
907                % (buildspace, previous_tool)))
908        else:
909            sys.exit(fmt(
910                "@{rf}The build space at '%s' was previously built by '%s'. "
911                'Please remove the build space or pick a different build space.'
912                % (buildspace, previous_tool)))
913    mark_space_as_built_by(buildspace, 'catkin_make_isolated')
914
915    # Check devel space
916    if develspace is None:
917        develspace = os.path.join(workspace, 'devel_isolated')
918    print('Devel space: ' + str(develspace))
919
920    # ensure the devel space was previously built by catkin_make_isolated
921    previous_tool = get_previous_tool_used_on_the_space(develspace)
922    if previous_tool is not None and previous_tool != 'catkin_make_isolated':
923        if override_build_tool_check:
924            print(fmt(
925                "@{yf}Warning: devel space at '%s' was previously built by '%s', "
926                'but --override-build-tool-check was passed so continuing anyways.'
927                % (develspace, previous_tool)))
928        else:
929            sys.exit(fmt(
930                "@{rf}The devel space at '%s' was previously built by '%s'. "
931                'Please remove the devel space or pick a different devel space.'
932                % (develspace, previous_tool)))
933    mark_space_as_built_by(develspace, 'catkin_make_isolated')
934
935    # Check install space
936    if installspace is None:
937        installspace = os.path.join(workspace, 'install_isolated')
938    print('Install space: ' + str(installspace))
939
940    if cmake_args:
941        print('Additional CMake Arguments: ' + ' '.join(cmake_args))
942    else:
943        cmake_args = []
944
945    if not [arg for arg in cmake_args if arg.startswith('-G')]:
946        if use_ninja:
947            cmake_args += ['-G', 'Ninja']
948        elif use_nmake:
949            cmake_args += ['-G', 'NMake Makefiles']
950        else:
951            # no need to check for use_gmake, as it uses the same generator as make
952            cmake_args += ['-G', 'Unix Makefiles']
953    elif use_ninja or use_nmake:
954        print(colorize_line("Error: either specify a generator using '-G...' or '--use-[ninja|nmake]' but not both"))
955        sys.exit(1)
956
957    if make_args:
958        print('Additional make Arguments: ' + ' '.join(make_args))
959    else:
960        make_args = []
961
962    if catkin_make_args:
963        print('Additional make Arguments for catkin packages: ' + ' '.join(catkin_make_args))
964    else:
965        catkin_make_args = []
966
967    # Find packages
968    packages = find_packages(sourcespace, exclude_subspaces=True)
969    if not packages:
970        print(fmt('@{yf}No packages found in source space: %s@|' % sourcespace))
971
972    # whitelist packages and their dependencies in workspace
973    if only_pkg_with_deps:
974        package_names = [p.name for p in packages.values()]
975        unknown_packages = [name for name in only_pkg_with_deps if name not in package_names]
976        if unknown_packages:
977            sys.exit('Packages not found in the workspace: %s' % ', '.join(unknown_packages))
978
979        whitelist_pkg_names = get_package_names_with_recursive_dependencies(packages, only_pkg_with_deps)
980        print('Whitelisted packages: %s' % ', '.join(sorted(whitelist_pkg_names)))
981        packages = {path: p for path, p in packages.items() if p.name in whitelist_pkg_names}
982
983    # verify that specified package exists in workspace
984    if build_packages:
985        packages_by_name = {p.name: path for path, p in packages.items()}
986        unknown_packages = [p for p in build_packages if p not in packages_by_name]
987        if unknown_packages:
988            sys.exit('Packages not found in the workspace: %s' % ', '.join(unknown_packages))
989
990    # evaluate conditions
991    for package in packages.values():
992        package.evaluate_conditions(os.environ)
993
994    # Report topological ordering
995    ordered_packages = topological_order_packages(packages, blacklisted=ignore_packages)
996    unknown_build_types = []
997    msg = []
998    msg.append('@{pf}~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~' + ('~' * len(str(len(ordered_packages)))))
999    msg.append('@{pf}~~@|  traversing %d packages in topological order:' % len(ordered_packages))
1000    for path, package in ordered_packages:
1001        if path is None:
1002            print(fmt('@{rf}Error: Circular dependency in subset of packages: @!%s@|' % package))
1003            sys.exit('Can not build workspace with circular dependency')
1004
1005        export_tags = [e.tagname for e in package.exports]
1006        if 'build_type' in export_tags:
1007            build_type_tag = [e.content for e in package.exports if e.tagname == 'build_type'][0]
1008        else:
1009            build_type_tag = 'catkin'
1010        if build_type_tag == 'catkin':
1011            msg.append('@{pf}~~@|  - @!@{bf}' + package.name + '@|')
1012        elif build_type_tag == 'cmake':
1013            msg.append(
1014                '@{pf}~~@|  - @!@{bf}' + package.name + '@|' +
1015                ' (@!@{cf}plain cmake@|)'
1016            )
1017        else:
1018            msg.append(
1019                '@{pf}~~@|  - @!@{bf}' + package.name + '@|' +
1020                ' (@{rf}unknown@|)'
1021            )
1022            unknown_build_types.append(package)
1023    msg.append('@{pf}~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~' + ('~' * len(str(len(ordered_packages)))))
1024    for index in range(len(msg)):
1025        msg[index] = fmt(msg[index])
1026    print('\n'.join(msg))
1027
1028    # Error if there are packages with unknown build_types
1029    if unknown_build_types:
1030        print(colorize_line('Error: Packages with unknown build types exist'))
1031        sys.exit('Can not build workspace with packages of unknown build_type')
1032
1033    # Check to see if the workspace has changed
1034    cmake_args_with_spaces = list(cmake_args)
1035    if develspace:
1036        cmake_args_with_spaces.append('-DCATKIN_DEVEL_PREFIX=' + develspace)
1037    if installspace:
1038        cmake_args_with_spaces.append('-DCMAKE_INSTALL_PREFIX=' + installspace)
1039    if (
1040        not force_cmake and
1041        cmake_input_changed(packages, buildspace, cmake_args=cmake_args_with_spaces, filename='catkin_make_isolated')
1042    ):
1043        print('The packages or cmake arguments have changed, forcing cmake invocation')
1044        force_cmake = True
1045
1046    ensure_workspace_marker(workspace)
1047
1048    # Build packages
1049    pkg_develspace = None
1050    last_env = None
1051    for index, path_package in enumerate(ordered_packages):
1052        path, package = path_package
1053        if merge:
1054            pkg_develspace = develspace
1055        else:
1056            pkg_develspace = os.path.join(develspace, package.name)
1057        if not build_packages or package.name in build_packages:
1058            if continue_from_pkg and build_packages and package.name in build_packages:
1059                build_packages = None
1060            try:
1061                print()
1062                last_env = build_package(
1063                    path, package,
1064                    workspace, buildspace, pkg_develspace, installspace,
1065                    install, force_cmake,
1066                    quiet, last_env, cmake_args, make_args, catkin_make_args,
1067                    destdir=destdir, use_ninja=use_ninja, use_nmake=use_nmake, use_gmake=use_gmake,
1068                    number=index + 1, of=len(ordered_packages)
1069                )
1070            except subprocess.CalledProcessError as e:
1071                _print_build_error(package, e)
1072                # Let users know how to reproduce
1073                # First add the cd to the build folder of the package
1074                cmd = 'cd ' + quote(os.path.join(buildspace, package.name)) + ' && '
1075                # Then reproduce the command called
1076                if isinstance(e.cmd, list):
1077                    # quote arguments to allow copy-n-paste of command
1078                    cmd += ' '.join([quote(arg) for arg in e.cmd])
1079                else:
1080                    cmd += e.cmd
1081                print(fmt('\n@{rf}Reproduce this error by running:'))
1082                print(fmt('@{gf}@!==> @|') + cmd + '\n')
1083                sys.exit('Command failed, exiting.')
1084            except Exception as e:
1085                print("Unhandled exception of type '{0}':".format(type(e).__name__))
1086                import traceback
1087                traceback.print_exc()
1088                _print_build_error(package, e)
1089                sys.exit('Command failed, exiting.')
1090        else:
1091            cprint("Skipping package: '@!@{bf}" + package.name + "@|'")
1092            last_env = get_new_env(package, pkg_develspace, installspace, install, last_env, destdir)
1093
1094    # Provide a top level devel space environment setup script
1095    if not os.path.exists(develspace):
1096        os.makedirs(develspace)
1097    if not build_packages:
1098        env_script = 'env'
1099        if sys.platform == 'win32':
1100            env_script += '.bat'
1101            env_script_content = """\
1102@echo off
1103REM generated from catkin.builder Python module
1104
1105call {0} %*
1106"""
1107            setup_script_content = """\
1108@echo off
1109REM generated from catkin.builder Python module
1110
1111call "{0}/setup.{1}"
1112"""
1113        else:
1114            env_script += '.sh'
1115            env_script_content = """\
1116#!/usr/bin/env sh
1117# generated from catkin.builder Python module
1118
1119{0} "$@"
1120"""
1121            setup_script_content = """\
1122#!/usr/bin/env {1}
1123# generated from catkin.builder Python module
1124
1125. "{0}/setup.{1}"
1126"""
1127            setup_sh_content = """\
1128#!/usr/bin/env sh
1129# generated from catkin.builder Python module
1130
1131if [ ! -z "$_CATKIN_SETUP_DIR" ] && [ "$_CATKIN_SETUP_DIR" != "{1}" ]; then
1132  echo "Relocation of this workspace is not supported"
1133  return 1
1134fi
1135
1136_CATKIN_SETUP_DIR= . "{0}/setup.sh"
1137"""
1138
1139        generated_env_sh = os.path.join(develspace, env_script)
1140        generated_setup_util_py = os.path.join(develspace, '_setup_util.py')
1141        if not merge and pkg_develspace:
1142            # generate env script and setup.sh|bash|zsh or setup.bat which relay to last devel space
1143            with open(generated_env_sh, 'w') as f:
1144                f.write(env_script_content.format(os.path.join(pkg_develspace, env_script)))
1145            os.chmod(generated_env_sh, stat.S_IXUSR | stat.S_IWUSR | stat.S_IRUSR)
1146
1147            shells_to_write = ['bat'] if sys.platform == 'win32' else ['bash', 'zsh']
1148            for shell in shells_to_write:
1149                with open(os.path.join(develspace, 'setup.%s' % shell), 'w') as f:
1150                    f.write(setup_script_content.format(pkg_develspace, shell))
1151            if sys.platform != 'win32':
1152                with open(os.path.join(develspace, 'setup.sh'), 'w') as f:
1153                    f.write(setup_sh_content.format(pkg_develspace, develspace))
1154
1155            # remove _setup_util.py file which might have been generated for an empty devel space before
1156            if os.path.exists(generated_setup_util_py):
1157                os.remove(generated_setup_util_py)
1158
1159        elif not pkg_develspace:
1160            # generate env.* and setup.* scripts for an empty devel space
1161            if 'CMAKE_PREFIX_PATH' in os.environ.keys():
1162                variables = {
1163                    'CATKIN_GLOBAL_BIN_DESTINATION': 'bin',
1164                    'CATKIN_LIB_ENVIRONMENT_PATHS': "'lib'",
1165                    'CATKIN_PKGCONFIG_ENVIRONMENT_PATHS': "os.path.join('lib', 'pkgconfig')",
1166                    'CMAKE_PREFIX_PATH_AS_IS': ';'.join(os.environ['CMAKE_PREFIX_PATH'].split(os.pathsep)),
1167                    'PYTHON_EXECUTABLE': sys.executable,
1168                    'PYTHON_INSTALL_DIR': get_python_install_dir(),
1169                }
1170                with open(generated_setup_util_py, 'w') as f:
1171                    f.write(configure_file(
1172                        os.path.join(get_cmake_path(), 'templates', '_setup_util.py.in'),
1173                        variables))
1174                os.chmod(generated_setup_util_py, stat.S_IXUSR | stat.S_IWUSR | stat.S_IRUSR)
1175            else:
1176                sys.exit('Unable to process CMAKE_PREFIX_PATH from environment. Cannot generate environment files.')
1177
1178            variables = {
1179                'SETUP_DIR': develspace,
1180                'SETUP_FILENAME': 'setup',
1181            }
1182            with open(generated_env_sh, 'w') as f:
1183                f.write(configure_file(os.path.join(get_cmake_path(), 'templates', env_script + '.in'), variables))
1184            os.chmod(generated_env_sh, stat.S_IXUSR | stat.S_IWUSR | stat.S_IRUSR)
1185
1186            variables = {
1187                'PYTHON_EXECUTABLE': sys.executable,
1188                'SETUP_DIR': develspace,
1189            }
1190            shells_to_write = ['bat'] if sys.platform == 'win32' else ['sh', 'bash', 'zsh']
1191            for shell in shells_to_write:
1192                with open(os.path.join(develspace, 'setup.%s' % shell), 'w') as f:
1193                    f.write(configure_file(
1194                        os.path.join(get_cmake_path(), 'templates', 'setup.%s.in' % shell),
1195                        variables))
1196
1197
1198def cmake_input_changed(packages, build_path, cmake_args=None, filename='catkin_make'):
1199    # get current input
1200    package_paths = os.pathsep.join(sorted(packages.keys()))
1201    cmake_args = ' '.join(cmake_args) if cmake_args else ''
1202
1203    # file to store current input
1204    changed = False
1205    input_filename = os.path.join(build_path, '%s.cache' % filename)
1206    if not os.path.exists(input_filename):
1207        changed = True
1208    else:
1209        # compare with previously stored input
1210        with open(input_filename, 'r') as f:
1211            previous_package_paths = f.readline().rstrip()
1212            previous_cmake_args = f.readline().rstrip()
1213        if package_paths != previous_package_paths:
1214            changed = True
1215        if cmake_args != previous_cmake_args:
1216            changed = True
1217
1218    # store current input for next invocation
1219    with open(input_filename, 'w') as f:
1220        f.write('%s\n%s' % (package_paths, cmake_args))
1221
1222    return changed
1223
1224
1225def get_package_names_with_recursive_dependencies(packages, pkg_names):
1226    dependencies = set()
1227    check_pkg_names = set(pkg_names)
1228    packages_by_name = {p.name: p for path, p in packages.items()}
1229    while check_pkg_names:
1230        pkg_name = check_pkg_names.pop()
1231        if pkg_name in packages_by_name:
1232            pkg = packages_by_name[pkg_name]
1233            dependencies.add(pkg_name)
1234            deps_to_iterate_over = (
1235                pkg.build_depends +
1236                pkg.buildtool_depends +
1237                pkg.run_depends +
1238                (pkg.test_depends if pkg.package_format > 1 else [])
1239            )
1240            for dep in [dep.name for dep in deps_to_iterate_over if dep.evaluated_condition is not False]:
1241                if dep in packages_by_name and dep not in check_pkg_names and dep not in dependencies:
1242                    check_pkg_names.add(dep)
1243    return dependencies
1244
1245
1246def apply_platform_specific_defaults(args):
1247    # add Windows specific defaults
1248    if sys.platform == 'win32':
1249        # default to use nmake if on Windows and if not using ninja
1250        if not args.use_ninja:
1251            args.use_nmake = True
1252        # use RelWithDebInfo as default build type if on Windows
1253        prefix = '-DCMAKE_BUILD_TYPE='
1254        if not any(a.startswith(prefix) for a in args.cmake_args):
1255            args.cmake_args.append(prefix + 'RelWithDebInfo')
1256