Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.
Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.
Path: blob/master/Tools/ardupilotwaf/ardupilotwaf.py
Views: 1798
# encoding: utf-812from __future__ import print_function3from waflib import Build, ConfigSet, Configure, Context, Errors, Logs, Options, Utils, Task4from waflib.Configure import conf5from waflib.Scripting import run_command6from waflib.TaskGen import before_method, after_method, feature7import os.path, os8from pathlib import Path9from collections import OrderedDict10import subprocess1112import ap_persistent1314SOURCE_EXTS = [15'*.S',16'*.c',17'*.cpp',18]1920COMMON_VEHICLE_DEPENDENT_CAN_LIBRARIES = [21'AP_CANManager',22'AP_KDECAN',23'AP_PiccoloCAN',24'AP_PiccoloCAN/piccolo_protocol',25]2627COMMON_VEHICLE_DEPENDENT_LIBRARIES = [28'AP_Airspeed',29'AP_AccelCal',30'AP_ADC',31'AP_AHRS',32'AP_Airspeed',33'AP_Baro',34'AP_BattMonitor',35'AP_BoardConfig',36'AP_Camera',37'AP_Common',38'AP_Compass',39'AP_Declination',40'AP_GPS',41'AP_GSOF',42'AP_HAL',43'AP_HAL_Empty',44'AP_InertialSensor',45'AP_Math',46'AP_Mission',47'AP_DAL',48'AP_NavEKF',49'AP_NavEKF2',50'AP_NavEKF3',51'AP_Notify',52'AP_OpticalFlow',53'AP_Param',54'AP_Rally',55'AP_RangeFinder',56'AP_Scheduler',57'AP_SerialManager',58'AP_Terrain',59'AP_Vehicle',60'AP_InternalError',61'AP_Logger',62'Filter',63'GCS_MAVLink',64'RC_Channel',65'SRV_Channel',66'StorageManager',67'AP_Tuning',68'AP_RPM',69'AP_RSSI',70'AP_Mount',71'AP_Module',72'AP_Button',73'AP_ICEngine',74'AP_Networking',75'AP_Frsky_Telem',76'AP_IBus_Telem',77'AP_FlashStorage',78'AP_Relay',79'AP_ServoRelayEvents',80'AP_Volz_Protocol',81'AP_SBusOut',82'AP_IOMCU',83'AP_Parachute',84'AP_RAMTRON',85'AP_RCProtocol',86'AP_Radio',87'AP_TempCalibration',88'AP_VisualOdom',89'AP_BLHeli',90'AP_ROMFS',91'AP_Proximity',92'AP_Gripper',93'AP_RTC',94'AC_Sprayer',95'AC_Fence',96'AC_Avoidance',97'AP_LandingGear',98'AP_RobotisServo',99'AP_NMEA_Output',100'AP_OSD',101'AP_Filesystem',102'AP_ADSB',103'AP_ADSB/sagetech-sdk',104'AC_PID',105'AP_SerialLED',106'AP_EFI',107'AP_Hott_Telem',108'AP_ESC_Telem',109'AP_Servo_Telem',110'AP_Stats',111'AP_GyroFFT',112'AP_RCTelemetry',113'AP_Generator',114'AP_MSP',115'AP_OLC',116'AP_WheelEncoder',117'AP_ExternalAHRS',118'AP_VideoTX',119'AP_FETtecOneWire',120'AP_TemperatureSensor',121'AP_Torqeedo',122'AP_CustomRotations',123'AP_AIS',124'AP_OpenDroneID',125'AP_CheckFirmware',126'AP_ExternalControl',127'AP_JSON',128'AP_Beacon',129'AP_Arming',130'AP_RCMapper',131'AP_MultiHeap',132]133134def get_legacy_defines(sketch_name, bld):135# If we are building heli, we adjust the build directory define so that136# we do not need to actually split heli and copter directories137if bld.cmd == 'heli' or 'heli' in bld.targets:138return [139'APM_BUILD_DIRECTORY=APM_BUILD_Heli',140'AP_BUILD_TARGET_NAME="' + sketch_name + '"',141]142143return [144'APM_BUILD_DIRECTORY=APM_BUILD_' + sketch_name,145'AP_BUILD_TARGET_NAME="' + sketch_name + '"',146]147148def set_double_precision_flags(flags):149# set up flags for double precision files:150# * remove all single precision constant flags151# * set define to allow double precision math in AP headers152153flags = flags[:] # copy the list to avoid affecting other builds154155# remove GCC and clang single precision constant flags156for opt in ('-fsingle-precision-constant', '-cl-single-precision-constant'):157while True: # might have multiple copies from different sources158try:159flags.remove(opt)160except ValueError:161break162flags.append("-DALLOW_DOUBLE_MATH_FUNCTIONS")163164return flags165166IGNORED_AP_LIBRARIES = [167'doc',168'AP_Scripting', # this gets explicitly included when it is needed and should otherwise never be globbed in169'AP_DDS',170]171172173def ap_autoconfigure(execute_method):174"""175Decorator that enables context commands to run *configure* as needed.176"""177def execute(self):178"""179Wraps :py:func:`waflib.Context.Context.execute` on the context class180"""181if 'tools/' in self.targets:182raise Errors.WafError('\"tools\" name has been replaced with \"tool\" for build please use that!')183if not Configure.autoconfig:184return execute_method(self)185186# Disable autoconfig so waf's version doesn't run (and don't end up on loop of bad configure)187Configure.autoconfig = False188189if self.variant == '':190raise Errors.WafError('The project is badly configured: run "waf configure" again!')191192env = ConfigSet.ConfigSet()193do_config = False194195try:196p = os.path.join(Context.out_dir, Build.CACHE_DIR, self.variant + Build.CACHE_SUFFIX)197env.load(p)198except EnvironmentError:199raise Errors.WafError('The project is not configured for board {0}: run "waf configure --board {0} [...]" first!'.format(self.variant))200201lock_env = ConfigSet.ConfigSet()202203try:204lock_env.load(os.path.join(Context.top_dir, Options.lockfile))205except EnvironmentError:206Logs.warn('Configuring the project')207do_config = True208else:209if lock_env.run_dir != Context.run_dir:210do_config = True211else:212h = 0213214for f in env.CONFIGURE_FILES:215try:216h = Utils.h_list((h, Utils.readf(f, 'rb')))217except EnvironmentError:218do_config = True219break220else:221do_config = h != env.CONFIGURE_HASH222223if do_config:224cmd = lock_env.config_cmd or 'configure'225tmp = Options.options.__dict__226227if env.OPTIONS and sorted(env.OPTIONS.keys()) == sorted(tmp.keys()):228Options.options.__dict__ = env.OPTIONS229else:230raise Errors.WafError('The project configure options have changed: run "waf configure" again!')231232try:233run_command(cmd)234finally:235Options.options.__dict__ = tmp236237run_command(self.cmd)238else:239return execute_method(self)240241return execute242243def ap_configure_post_recurse():244post_recurse_orig = Configure.ConfigurationContext.post_recurse245246def post_recurse(self, node):247post_recurse_orig(self, node)248249self.all_envs[self.variant].CONFIGURE_FILES = self.files250self.all_envs[self.variant].CONFIGURE_HASH = self.hash251252return post_recurse253254@conf255def ap_get_all_libraries(bld):256if bld.env.BOOTLOADER:257# we don't need the full set of libraries for the bootloader build258return ['AP_HAL']259libraries = []260for lib_node in bld.srcnode.ant_glob('libraries/*', dir=True, src=False):261name = lib_node.name262if name in IGNORED_AP_LIBRARIES:263continue264if name.startswith('AP_HAL'):265continue266if name == 'SITL':267continue268libraries.append(name)269libraries.extend(['AP_HAL', 'AP_HAL_Empty'])270libraries.append('AP_PiccoloCAN/piccolo_protocol')271return libraries272273@conf274def ap_common_vehicle_libraries(bld):275libraries = COMMON_VEHICLE_DEPENDENT_LIBRARIES276277if bld.env.with_can or bld.env.HAL_NUM_CAN_IFACES:278libraries.extend(COMMON_VEHICLE_DEPENDENT_CAN_LIBRARIES)279280return libraries281282_grouped_programs = {}283284285class upload_fw_blueos(Task.Task):286def run(self):287# this is rarely used, so we import requests here to avoid the overhead288import requests289binary_path = self.inputs[0].abspath()290# check if .apj file exists for chibios builds291if Path(binary_path + ".apj").exists():292binary_path = binary_path + ".apj"293bld = self.generator.bld294board = bld.bldnode.name.capitalize()295print(f"Uploading {binary_path} to BlueOS at {bld.options.upload_blueos} for board {board}")296url = f'{bld.options.upload_blueos}/ardupilot-manager/v1.0/install_firmware_from_file?board_name={board}'297files = {298'binary': open(binary_path, 'rb')299}300response = requests.post(url, files=files, verify=False)301if response.status_code != 200:302raise Errors.WafError(f"Failed to upload firmware to BlueOS: {response.status_code}: {response.text}")303print("Upload complete")304305def keyword(self):306return "Uploading to BlueOS"307308class check_elf_symbols(Task.Task):309color='CYAN'310always_run = True311def keyword(self):312return "checking symbols"313314def run(self):315'''316check for disallowed symbols in elf file, such as C++ exceptions317'''318elfpath = self.inputs[0].abspath()319320if not self.env.CHECK_SYMBOLS:321# checking symbols disabled on this build322return323324if not self.env.vehicle_binary or self.env.SIM_ENABLED:325# we only want to check symbols for vehicle binaries, allowing examples326# to use C++ exceptions. We also allow them in simulator builds327return328329# we use string find on these symbols, so this catches all types of throw330# calls this should catch all uses of exceptions unless the compiler331# manages to inline them332blacklist = ['std::__throw',333'operator new[](unsigned int)',334'operator new[](unsigned long)',335'operator new(unsigned int)',336'operator new(unsigned long)']337338nmout = subprocess.getoutput("%s -C %s" % (self.env.get_flat('NM'), elfpath))339for b in blacklist:340if nmout.find(b) != -1:341raise Errors.WafError("Disallowed symbol in %s: %s" % (elfpath, b))342343344@feature('post_link')345@after_method('process_source')346def post_link(self):347'''348setup tasks to run after link stage349'''350self.link_task.always_run = True351352link_output = self.link_task.outputs[0]353354check_elf_task = self.create_task('check_elf_symbols', src=link_output)355check_elf_task.set_run_after(self.link_task)356if self.bld.options.upload_blueos and self.env["BOARD_CLASS"] == "LINUX":357_upload_task = self.create_task('upload_fw_blueos', src=link_output)358_upload_task.set_run_after(self.link_task)359360@conf361def ap_program(bld,362program_groups='bin',363program_dir=None,364use_legacy_defines=True,365program_name=None,366vehicle_binary=True,367**kw):368if 'target' in kw:369bld.fatal('Do not pass target for program')370if 'defines' not in kw:371kw['defines'] = []372if 'source' not in kw:373kw['source'] = bld.path.ant_glob(SOURCE_EXTS)374375if not program_name:376program_name = bld.path.name377378if use_legacy_defines:379kw['defines'].extend(get_legacy_defines(bld.path.name, bld))380381kw['features'] = kw.get('features', []) + bld.env.AP_PROGRAM_FEATURES + ['post_link']382383program_groups = Utils.to_list(program_groups)384385if not program_dir:386program_dir = program_groups[0]387388name = os.path.join(program_dir, program_name)389390tg_constructor = bld.program391if bld.env.AP_PROGRAM_AS_STLIB:392tg_constructor = bld.stlib393else:394if bld.env.STATIC_LINKING:395kw['features'].append('static_linking')396397398tg = tg_constructor(399target='#%s' % name,400name=name,401program_name=program_name,402program_dir=program_dir,403**kw404)405406tg.env.vehicle_binary = vehicle_binary407408if 'use' in kw and bld.env.STATIC_LINKING:409# ensure we link against vehicle library410tg.env.STLIB += [kw['use']]411412for group in program_groups:413_grouped_programs.setdefault(group, {}).update({tg.name : tg})414415return tg416417418@conf419def ap_example(bld, **kw):420kw['program_groups'] = 'examples'421ap_program(bld, use_legacy_defines=False, vehicle_binary=False, **kw)422423def unique_list(items):424'''remove duplicate elements from a list while maintaining ordering'''425return list(OrderedDict.fromkeys(items))426427@conf428def ap_stlib(bld, **kw):429if 'name' not in kw:430bld.fatal('Missing name for ap_stlib')431if 'ap_vehicle' not in kw:432bld.fatal('Missing ap_vehicle for ap_stlib')433if 'ap_libraries' not in kw:434bld.fatal('Missing ap_libraries for ap_stlib')435436kw['ap_libraries'] = unique_list(kw['ap_libraries'] + bld.env.AP_LIBRARIES)437for l in kw['ap_libraries']:438bld.ap_library(l, kw['ap_vehicle'])439440if 'dynamic_source' not in kw:441kw['dynamic_source'] = 'modules/DroneCAN/libcanard/dsdlc_generated/src/**.c'442443kw['features'] = kw.get('features', []) + ['cxx', 'cxxstlib']444kw['target'] = kw['name']445kw['source'] = []446447bld.stlib(**kw)448449_created_program_dirs = set()450@feature('cxxstlib', 'cxxprogram')451@before_method('process_rule')452def ap_create_program_dir(self):453if not hasattr(self, 'program_dir'):454return455if self.program_dir in _created_program_dirs:456return457self.bld.bldnode.make_node(self.program_dir).mkdir()458_created_program_dirs.add(self.program_dir)459460@feature('cxxstlib')461@before_method('process_rule')462def ap_stlib_target(self):463if self.target.startswith('#'):464self.target = self.target[1:]465self.target = '#%s' % os.path.join('lib', self.target)466467@conf468def ap_find_tests(bld, use=[], DOUBLE_PRECISION_SOURCES=[]):469if not bld.env.HAS_GTEST:470return471472features = []473if bld.cmd == 'check':474features.append('test')475476use = Utils.to_list(use)477use.append('GTEST')478479includes = [bld.srcnode.abspath() + '/tests/']480481for f in bld.path.ant_glob(incl='*.cpp'):482t = ap_program(483bld,484features=features,485includes=includes,486source=[f],487use=use,488program_name=f.change_ext('').name,489program_groups='tests',490use_legacy_defines=False,491vehicle_binary=False,492cxxflags=['-Wno-undef'],493)494filename = os.path.basename(f.abspath())495if filename in DOUBLE_PRECISION_SOURCES:496t.env.CXXFLAGS = set_double_precision_flags(t.env.CXXFLAGS)497498_versions = []499500@conf501def ap_version_append_str(ctx, k, v):502ctx.env['AP_VERSION_ITEMS'] += [(k, '"{}"'.format(os.environ.get(k, v)))]503504@conf505def ap_version_append_int(ctx, k, v):506ctx.env['AP_VERSION_ITEMS'] += [(k, '{}'.format(os.environ.get(k, v)))]507508@conf509def write_version_header(ctx, tgt):510with open(tgt, 'w') as f:511print(512'''// auto-generated header, do not edit513514#pragma once515516#ifndef FORCE_VERSION_H_INCLUDE517#error ap_version.h should never be included directly. You probably want to include AP_Common/AP_FWVersion.h518#endif519''', file=f)520521for k, v in ctx.env['AP_VERSION_ITEMS']:522print('#define {} {}'.format(k, v), file=f)523524@conf525def ap_find_benchmarks(bld, use=[]):526if not bld.env.HAS_GBENCHMARK:527return528529includes = [bld.srcnode.abspath() + '/benchmarks/']530to_remove = '-Werror=suggest-override'531if to_remove in bld.env.CXXFLAGS:532need_remove = True533else:534need_remove = False535if need_remove:536while to_remove in bld.env.CXXFLAGS:537bld.env.CXXFLAGS.remove(to_remove)538539for f in bld.path.ant_glob(incl='*.cpp'):540ap_program(541bld,542features=['gbenchmark'],543includes=includes,544source=[f],545use=use,546vehicle_binary=False,547program_name=f.change_ext('').name,548program_groups='benchmarks',549use_legacy_defines=False,550)551552def test_summary(bld):553from io import BytesIO554import sys555556if not hasattr(bld, 'utest_results'):557Logs.info('check: no test run')558return559560fails = []561562for filename, exit_code, out, err in bld.utest_results:563Logs.pprint('GREEN' if exit_code == 0 else 'YELLOW',564' %s' % filename,565'returned %d' % exit_code)566567if exit_code != 0:568fails.append(filename)569elif not bld.options.check_verbose:570continue571572if len(out):573buf = BytesIO(out)574for line in buf:575print(" OUT: %s" % line.decode(), end='', file=sys.stderr)576print()577578if len(err):579buf = BytesIO(err)580for line in buf:581print(" ERR: %s" % line.decode(), end='', file=sys.stderr)582print()583584if not fails:585Logs.info('check: All %u tests passed!' % len(bld.utest_results))586return587588Logs.error('check: %u of %u tests failed' %589(len(fails), len(bld.utest_results)))590591for filename in fails:592Logs.error(' %s' % filename)593594bld.fatal('check: some tests failed')595596_build_commands = {}597598def _process_build_command(bld):599if bld.cmd not in _build_commands:600return601602params = _build_commands[bld.cmd]603604targets = params['targets']605if targets:606if bld.targets:607bld.targets += ',' + targets608else:609bld.targets = targets610611program_group_list = Utils.to_list(params['program_group_list'])612bld.options.program_group.extend(program_group_list)613614def build_command(name,615targets=None,616program_group_list=[],617doc='build shortcut'):618_build_commands[name] = dict(619targets=targets,620program_group_list=program_group_list,621)622623class context_class(Build.BuildContext):624cmd = name625context_class.__doc__ = doc626627def _select_programs_from_group(bld):628groups = bld.options.program_group629if not groups:630if bld.targets:631groups = []632else:633groups = ['bin']634635possible_groups = list(_grouped_programs.keys())636possible_groups.remove('bin') # Remove `bin` so as not to duplicate all items in bin637if 'all' in groups:638groups = possible_groups639640for group in groups:641if group not in _grouped_programs:642bld.fatal(f'Group {group} not found, possible groups: {possible_groups}')643644target_names = _grouped_programs[group].keys()645646for name in target_names:647if bld.targets:648bld.targets += ',' + name649else:650bld.targets = name651652def options(opt):653opt.ap_groups = {654'configure': opt.add_option_group('Ardupilot configure options'),655'linux': opt.add_option_group('Linux boards configure options'),656'build': opt.add_option_group('Ardupilot build options'),657'check': opt.add_option_group('Ardupilot check options'),658'clean': opt.add_option_group('Ardupilot clean options'),659}660661g = opt.ap_groups['build']662663g.add_option('--program-group',664action='append',665default=[],666help='''Select all programs that go in <PROGRAM_GROUP>/ for the build.667Example: `waf --program-group examples` builds all examples. The668special group "all" selects all programs.669''')670671g.add_option('--upload',672action='store_true',673help='''Upload applicable targets to a connected device. Not all674platforms may support this. Example: `waf copter --upload` means "build675arducopter and upload it to my board".676''')677678g.add_option('--upload-port',679action='store',680dest='upload_port',681default=None,682help='''Specify the port to be used with the --upload option. For example a port of /dev/ttyS10 indicates that serial port 10 shuld be used.683''')684685g.add_option('--upload-blueos',686action='store',687dest='upload_blueos',688default=None,689help='''Automatically upload to a BlueOS device. The argument is the url for the device. http://blueos.local for example.690''')691692g.add_option('--upload-force',693action='store_true',694help='''Override board type check and continue loading. Same as using uploader.py --force.695''')696697g.add_option('--define',698action='append',699help='Add C++ define to build.')700701g = opt.ap_groups['check']702703g.add_option('--check-verbose',704action='store_true',705help='Output all test programs.')706707g = opt.ap_groups['clean']708709g.add_option('--clean-all-sigs',710action='store_true',711help='''Clean signatures for all tasks. By default, tasks that scan for712implicit dependencies (like the compilation tasks) keep the dependency713information across clean commands, so that that information is changed714only when really necessary. Also, some tasks that don't really produce715files persist their signature. This option avoids that behavior when716cleaning the build.717''')718719g.add_option('--asan',720action='store_true',721help='''Build using the macOS clang Address Sanitizer. In order to run with722Address Sanitizer support llvm-symbolizer is required to be on the PATH.723This option is only supported on macOS versions of clang.724''')725726g.add_option('--ubsan',727action='store_true',728help='''Build using the gcc undefined behaviour sanitizer''')729730g.add_option('--ubsan-abort',731action='store_true',732help='''Build using the gcc undefined behaviour sanitizer and abort on error''')733734def build(bld):735bld.add_pre_fun(_process_build_command)736bld.add_pre_fun(_select_programs_from_group)737738739