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/chibios.py
Views: 1798
# encoding: utf-812"""3Waf tool for ChibiOS build4"""56from waflib import Errors, Logs, Task, Utils, Context7from waflib.TaskGen import after_method, before_method, feature89import os10import shutil11import sys12import re13import pickle14import struct15import base6416import subprocess1718_dynamic_env_data = {}19def _load_dynamic_env_data(bld):20bldnode = bld.bldnode.make_node('modules/ChibiOS')21include_dirs_node = bldnode.find_node('include_dirs')22if include_dirs_node is None:23_dynamic_env_data['include_dirs'] = []24return25tmp_str = include_dirs_node.read()26tmp_str = tmp_str.replace(';\n','')27tmp_str = tmp_str.replace('-I','') #remove existing -I flags28# split, coping with separator29idirs = re.split('; ', tmp_str)3031# create unique list, coping with relative paths32idirs2 = []33for d in idirs:34if d.startswith('../'):35# relative paths from the make build are relative to BUILDROOT36d = os.path.join(bld.env.BUILDROOT, d)37d = os.path.normpath(d)38if d not in idirs2:39idirs2.append(d)40_dynamic_env_data['include_dirs'] = idirs24142@feature('ch_ap_library', 'ch_ap_program')43@before_method('process_source')44def ch_dynamic_env(self):45# The generated files from configuration possibly don't exist if it's just46# a list command (TODO: figure out a better way to address that).47if self.bld.cmd == 'list':48return4950if not _dynamic_env_data:51_load_dynamic_env_data(self.bld)52self.use += ' ch'53self.env.append_value('INCLUDES', _dynamic_env_data['include_dirs'])545556class upload_fw(Task.Task):57color='BLUE'58always_run = True59def run(self):60import platform61upload_tools = self.env.get_flat('UPLOAD_TOOLS')62upload_port = self.generator.bld.options.upload_port63src = self.inputs[0]64# Refer Tools/scripts/macos_remote_upload.sh for details65if 'AP_OVERRIDE_UPLOAD_CMD' in os.environ:66cmd = "{} '{}'".format(os.environ['AP_OVERRIDE_UPLOAD_CMD'], src.abspath())67elif "microsoft-standard-WSL2" in platform.release():68if not self.wsl2_prereq_checks():69return70print("If this takes takes too long here, try power-cycling your hardware\n")71cmd = "{} -u '{}/uploader.py' '{}'".format('python.exe', upload_tools, src.abspath())72else:73cmd = "{} '{}/uploader.py' '{}'".format(self.env.get_flat('PYTHON'), upload_tools, src.abspath())74if upload_port is not None:75cmd += " '--port' '%s'" % upload_port76if self.generator.bld.options.upload_force:77cmd += " '--force'"78return self.exec_command(cmd)7980def wsl2_prereq_checks(self):81# As of July 2022 WSL2 does not support native USB support. The workaround from Microsoft82# using 'usbipd' does not work due to the following workflow:83#84# 1) connect USB device to Windows computer running WSL285# 2) device boots into app86# 3) use 'usbipd' from Windows Cmd/PowerShell to determine busid, this is very hard to automate on Windows87# 4) use 'usbipd' from Windows Cmd/PowerShell to attach, this is very hard to automate on Windows88# -- device is now viewable via 'lsusb' but you need sudo to read from it.89# either run 'chmod666 /dev/ttyACM*' or use udev to automate chmod on device connect90# 5) uploader.py detects device, sends reboot command which disconnects the USB port and reboots into91# bootloader (different USB device)92# 6) manually repeat steps 3 & 493# 7) doing steps 3 and 4 will most likely take several seconds and in many cases the bootloader has94# moved on into the app95#96# Solution: simply call "python.exe" instead of 'python' which magically calls it from the windows97# system using the same absolute path back into the WSL2's user's directory98# Requirements: Windows must have Python3.9.x (NTO 3.10.x) installed and a few packages.99import subprocess100try:101where_python = subprocess.check_output('where.exe python.exe', shell=True, text=True)102except subprocess.CalledProcessError:103#if where.exe can't find the file it returns a non-zero result which throws this exception104where_python = ""105if "python.exe" not in where_python:106print(self.get_full_wsl2_error_msg("Windows python.exe not found"))107return False108return True109110def get_full_wsl2_error_msg(self, error_msg):111return ("""112****************************************113****************************************114WSL2 firmware uploads use the host's Windows Python.exe so it has access to the COM ports.115116%s117Please download Windows Installer 3.9.x (not 3.10) from https://www.python.org/downloads/118and make sure to add it to your path during the installation. Once installed, run this119command in Powershell or Command Prompt to install some packages:120121pip.exe install empy==3.3.4 pyserial122****************************************123****************************************124""" % error_msg)125126def exec_command(self, cmd, **kw):127kw['stdout'] = sys.stdout128return super(upload_fw, self).exec_command(cmd, **kw)129130def keyword(self):131return "Uploading"132133class set_default_parameters(Task.Task):134color='CYAN'135always_run = True136def keyword(self):137return "apj_tool"138def run(self):139rel_default_parameters = self.env.get_flat('DEFAULT_PARAMETERS').replace("'", "")140abs_default_parameters = os.path.join(self.env.SRCROOT, rel_default_parameters)141apj_tool = self.env.APJ_TOOL142sys.path.append(os.path.dirname(apj_tool))143from apj_tool import embedded_defaults144defaults = embedded_defaults(self.inputs[0].abspath())145if defaults.find():146defaults.set_file(abs_default_parameters)147defaults.save()148149150class generate_bin(Task.Task):151color='CYAN'152# run_str="${OBJCOPY} -O binary ${SRC} ${TGT}"153always_run = True154EXTF_MEMORY_START = 0x90000000155EXTF_MEMORY_END = 0x90FFFFFF156INTF_MEMORY_START = 0x08000000157INTF_MEMORY_END = 0x08FFFFFF158def keyword(self):159return "Generating"160def run(self):161if self.env.HAS_EXTERNAL_FLASH_SECTIONS:162ret = self.split_sections()163if (ret < 0):164return ret165return ret166else:167cmd = [self.env.get_flat('OBJCOPY'), '-O', 'binary', self.inputs[0].relpath(), self.outputs[0].relpath()]168self.exec_command(cmd)169170'''list sections and split into two binaries based on section's location in internal, external or in ram'''171def split_sections(self):172# get a list of sections173cmd = "'{}' -A -x {}".format(self.env.get_flat('SIZE'), self.inputs[0].relpath())174out = self.generator.bld.cmd_and_log(cmd, quiet=Context.BOTH, cwd=self.env.get_flat('BUILDROOT'))175extf_sections = []176intf_sections = []177is_text_in_extf = False178found_text_section = False179ramsections = []180for line in out.splitlines():181section_line = line.split()182if (len(section_line) < 3):183continue184try:185if int(section_line[2], 0) == 0:186continue187else:188addr = int(section_line[2], 0)189except ValueError:190continue191if (addr >= self.EXTF_MEMORY_START) and (addr <= self.EXTF_MEMORY_END):192extf_sections.append("--only-section=%s" % section_line[0])193if section_line[0] == '.text':194is_text_in_extf = True195found_text_section = True196elif (addr >= self.INTF_MEMORY_START) and (addr <= self.INTF_MEMORY_END):197intf_sections.append("--only-section=%s" % section_line[0])198if section_line[0] == '.text':199is_text_in_extf = False200found_text_section = True201else: # most likely RAM data, we place it in the same bin as text202ramsections.append(section_line[0])203204if found_text_section:205for section in ramsections:206if is_text_in_extf:207extf_sections.append("--only-section=%s" % section)208else:209intf_sections.append("--only-section=%s" % section)210else:211Logs.error("Couldn't find .text section")212# create intf binary213if len(intf_sections):214cmd = "'{}' {} -O binary {} {}".format(self.env.get_flat('OBJCOPY'),215' '.join(intf_sections), self.inputs[0].relpath(), self.outputs[0].relpath())216else:217cmd = "cp /dev/null {}".format(self.outputs[0].relpath())218ret = self.exec_command(cmd)219if (ret < 0):220return ret221# create extf binary222cmd = "'{}' {} -O binary {} {}".format(self.env.get_flat('OBJCOPY'),223' '.join(extf_sections), self.inputs[0].relpath(), self.outputs[1].relpath())224return self.exec_command(cmd)225226def __str__(self):227return self.outputs[0].path_from(self.generator.bld.bldnode)228229def to_unsigned(i):230'''convert a possibly signed integer to unsigned'''231if i < 0:232i += 2**32233return i234235def sign_firmware(image, private_keyfile):236'''sign firmware with private key'''237try:238import monocypher239except ImportError:240Logs.error("Please install monocypher with: python3 -m pip install pymonocypher==3.1.3.2")241return None242243if monocypher.__version__ != "3.1.3.2":244Logs.error("must use monocypher 3.1.3.2, please run: python3 -m pip install pymonocypher==3.1.3.2")245return None246247try:248key = open(private_keyfile, 'r').read()249except Exception as ex:250Logs.error("Failed to open %s" % private_keyfile)251return None252keytype = "PRIVATE_KEYV1:"253if not key.startswith(keytype):254Logs.error("Bad private key file %s" % private_keyfile)255return None256key = base64.b64decode(key[len(keytype):])257sig = monocypher.signature_sign(key, image)258sig_len = len(sig)259sig_version = 30437260return struct.pack("<IQ64s", sig_len+8, sig_version, sig)261262263class set_app_descriptor(Task.Task):264'''setup app descriptor in bin file'''265color='BLUE'266always_run = True267def keyword(self):268return "app_descriptor"269def run(self):270if self.generator.bld.env.AP_SIGNED_FIRMWARE:271descriptor = b'\x41\xa3\xe5\xf2\x65\x69\x92\x07'272else:273descriptor = b'\x40\xa2\xe4\xf1\x64\x68\x91\x06'274275elf_file = self.inputs[0].abspath()276bin_file = self.inputs[1].abspath()277img = open(bin_file, 'rb').read()278offset = img.find(descriptor)279if offset == -1:280Logs.info("No APP_DESCRIPTOR found")281return282offset += len(descriptor)283# next 8 bytes is 64 bit CRC. We set first 4 bytes to284# CRC32 of image before descriptor and 2nd 4 bytes285# to CRC32 of image after descriptor. This is very efficient286# for bootloader to calculate287# after CRC comes image length and 32 bit git hash288upload_tools = self.env.get_flat('UPLOAD_TOOLS')289sys.path.append(upload_tools)290from uploader import crc32291if self.generator.bld.env.AP_SIGNED_FIRMWARE:292desc_len = 92293else:294desc_len = 16295img1 = bytearray(img[:offset])296img2 = bytearray(img[offset+desc_len:])297crc1 = to_unsigned(crc32(img1))298crc2 = to_unsigned(crc32(img2))299githash = to_unsigned(int('0x' + os.environ.get('GIT_VERSION', self.generator.bld.git_head_hash(short=True)),16))300if self.generator.bld.env.AP_SIGNED_FIRMWARE:301sig = bytearray([0 for i in range(76)])302if self.generator.bld.env.PRIVATE_KEY:303sig_signed = sign_firmware(img1+img2, self.generator.bld.env.PRIVATE_KEY)304if sig_signed:305Logs.info("Signed firmware")306sig = sig_signed307else:308self.generator.bld.fatal("Signing failed")309desc = struct.pack('<IIII76s', crc1, crc2, len(img), githash, sig)310else:311desc = struct.pack('<IIII', crc1, crc2, len(img), githash)312img = img[:offset] + desc + img[offset+desc_len:]313Logs.info("Applying APP_DESCRIPTOR %08x%08x" % (crc1, crc2))314open(bin_file, 'wb').write(img)315316elf_img = open(elf_file,'rb').read()317zero_descriptor = descriptor + struct.pack("<IIII",0,0,0,0)318elf_ofs = elf_img.find(zero_descriptor)319if elf_ofs == -1:320Logs.info("No APP_DESCRIPTOR found in elf file")321return322elf_ofs += len(descriptor)323elf_img = elf_img[:elf_ofs] + desc + elf_img[elf_ofs+desc_len:]324Logs.info("Applying APP_DESCRIPTOR %08x%08x to elf" % (crc1, crc2))325open(elf_file, 'wb').write(elf_img)326327328class generate_apj(Task.Task):329'''generate an apj firmware file'''330color='CYAN'331always_run = True332def keyword(self):333return "apj_gen"334def run(self):335import json, time, base64, zlib336intf_img = open(self.inputs[0].abspath(),'rb').read()337if self.env.HAS_EXTERNAL_FLASH_SECTIONS:338extf_img = open(self.inputs[1].abspath(),'rb').read()339else:340extf_img = b""341d = {342"board_id": int(self.env.APJ_BOARD_ID),343"magic": "APJFWv1",344"description": "Firmware for a %s board" % self.env.APJ_BOARD_TYPE,345"image": base64.b64encode(zlib.compress(intf_img,9)).decode('utf-8'),346"extf_image": base64.b64encode(zlib.compress(extf_img,9)).decode('utf-8'),347"summary": self.env.BOARD,348"version": "0.1",349"image_size": len(intf_img),350"extf_image_size": len(extf_img),351"flash_total": int(self.env.FLASH_TOTAL),352"image_maxsize": int(self.env.FLASH_TOTAL),353"flash_free": int(self.env.FLASH_TOTAL) - len(intf_img),354"extflash_total": int(self.env.EXT_FLASH_SIZE_MB * 1024 * 1024),355"extflash_free": int(self.env.EXT_FLASH_SIZE_MB * 1024 * 1024) - len(extf_img),356"git_identity": self.generator.bld.git_head_hash(short=True),357"board_revision": 0,358"USBID": self.env.USBID359}360if self.env.MANUFACTURER:361d["manufacturer"] = self.env.MANUFACTURER362if self.env.BRAND_NAME:363d["brand_name"] = self.env.BRAND_NAME364if self.env.build_dates:365# we omit build_time when we don't have build_dates so that apj366# file is idential for same git hash and compiler367d["build_time"] = int(time.time())368apj_file = self.outputs[0].abspath()369f = open(apj_file, "w")370f.write(json.dumps(d, indent=4))371f.close()372373class build_abin(Task.Task):374'''build an abin file for skyviper firmware upload via web UI'''375color='CYAN'376run_str='${TOOLS_SCRIPTS}/make_abin.sh ${SRC} ${TGT}'377always_run = True378def keyword(self):379return "Generating"380def __str__(self):381return self.outputs[0].path_from(self.generator.bld.bldnode)382383class build_normalized_bins(Task.Task):384'''Move external flash binaries to regular location if regular bin is zero length'''385color='CYAN'386always_run = True387def run(self):388if self.env.HAS_EXTERNAL_FLASH_SECTIONS and os.path.getsize(self.inputs[0].abspath()) == 0:389os.remove(self.inputs[0].abspath())390shutil.move(self.inputs[1].abspath(), self.inputs[0].abspath())391392def keyword(self):393return "bin cleanup"394395class build_intel_hex(Task.Task):396'''build an intel hex file for upload with DFU'''397color='CYAN'398run_str='${TOOLS_SCRIPTS}/make_intel_hex.py ${SRC} ${FLASH_RESERVE_START_KB}'399always_run = True400def keyword(self):401return "Generating"402def __str__(self):403return self.outputs[0].path_from(self.generator.bld.bldnode)404405@feature('ch_ap_program')406@after_method('process_source')407def chibios_firmware(self):408self.link_task.always_run = True409410link_output = self.link_task.outputs[0]411hex_task = None412413if self.bld.env.HAS_EXTERNAL_FLASH_SECTIONS:414bin_target = [self.bld.bldnode.find_or_declare('bin/' + link_output.change_ext('.bin').name),415self.bld.bldnode.find_or_declare('bin/' + link_output.change_ext('_extf.bin').name)]416else:417bin_target = [self.bld.bldnode.find_or_declare('bin/' + link_output.change_ext('.bin').name)]418apj_target = self.bld.bldnode.find_or_declare('bin/' + link_output.change_ext('.apj').name)419420generate_bin_task = self.create_task('generate_bin', src=link_output, tgt=bin_target)421generate_bin_task.set_run_after(self.link_task)422423generate_apj_task = self.create_task('generate_apj', src=bin_target, tgt=apj_target)424generate_apj_task.set_run_after(generate_bin_task)425426if self.env.BUILD_ABIN:427abin_target = self.bld.bldnode.find_or_declare('bin/' + link_output.change_ext('.abin').name)428abin_task = self.create_task('build_abin', src=bin_target, tgt=abin_target)429abin_task.set_run_after(generate_apj_task)430431cleanup_task = self.create_task('build_normalized_bins', src=bin_target)432cleanup_task.set_run_after(generate_apj_task)433434bootloader_bin = self.bld.srcnode.make_node("Tools/bootloaders/%s_bl.bin" % self.env.BOARD)435if self.bld.env.HAVE_INTEL_HEX:436if os.path.exists(bootloader_bin.abspath()):437if int(self.bld.env.FLASH_RESERVE_START_KB) > 0:438hex_target = self.bld.bldnode.find_or_declare('bin/' + link_output.change_ext('_with_bl.hex').name)439else:440hex_target = self.bld.bldnode.find_or_declare('bin/' + link_output.change_ext('.hex').name)441hex_task = self.create_task('build_intel_hex', src=[bin_target[0], bootloader_bin], tgt=hex_target)442hex_task.set_run_after(cleanup_task)443else:444print("Not embedding bootloader; %s does not exist" % bootloader_bin)445446if self.env.DEFAULT_PARAMETERS:447default_params_task = self.create_task('set_default_parameters',448src=link_output)449default_params_task.set_run_after(self.link_task)450generate_bin_task.set_run_after(default_params_task)451452# we need to setup the app descriptor so the bootloader can validate the firmware453if not self.bld.env.BOOTLOADER:454app_descriptor_task = self.create_task('set_app_descriptor', src=[link_output,bin_target[0]])455app_descriptor_task.set_run_after(generate_bin_task)456generate_apj_task.set_run_after(app_descriptor_task)457if hex_task is not None:458hex_task.set_run_after(app_descriptor_task)459else:460generate_apj_task.set_run_after(generate_bin_task)461if hex_task is not None:462hex_task.set_run_after(generate_bin_task)463464if self.bld.options.upload:465_upload_task = self.create_task('upload_fw', src=apj_target)466_upload_task.set_run_after(generate_apj_task)467468if self.bld.options.upload_blueos:469_upload_task = self.create_task('upload_fw_blueos', src=link_output)470_upload_task.set_run_after(generate_apj_task)471472def setup_canmgr_build(cfg):473'''enable CANManager build. By doing this here we can auto-enable CAN in474the build based on the presence of CAN pins in hwdef.dat except for AP_Periph builds'''475env = cfg.env476env.AP_LIBRARIES += [477'AP_DroneCAN',478'modules/DroneCAN/libcanard/*.c',479]480env.INCLUDES += [481cfg.srcnode.find_dir('modules/DroneCAN/libcanard').abspath(),482]483env.CFLAGS += ['-DHAL_CAN_IFACES=2']484485if not env.AP_PERIPH:486env.DEFINES += [487'DRONECAN_CXX_WRAPPERS=1',488'USE_USER_HELPERS=1',489'CANARD_ENABLE_DEADLINE=1',490'CANARD_MULTI_IFACE=1',491'CANARD_ALLOCATE_SEM=1'492]493494cfg.get_board().with_can = True495496def setup_canperiph_build(cfg):497'''enable CAN build for peripherals'''498env = cfg.env499env.DEFINES += [500'CANARD_ENABLE_DEADLINE=1',501]502503cfg.get_board().with_can = True504505def load_env_vars(env):506'''optionally load extra environment variables from env.py in the build directory'''507print("Checking for env.py")508env_py = os.path.join(env.BUILDROOT, 'env.py')509if not os.path.exists(env_py):510print("No env.py found")511return512e = pickle.load(open(env_py, 'rb'))513for k in e.keys():514v = e[k]515if k == 'ROMFS_FILES':516env.ROMFS_FILES += v517continue518if k in env:519if isinstance(env[k], dict):520a = v.split('=')521env[k][a[0]] = '='.join(a[1:])522print("env updated %s=%s" % (k, v))523elif isinstance(env[k], list):524env[k].append(v)525print("env appended %s=%s" % (k, v))526else:527env[k] = v528print("env added %s=%s" % (k, v))529else:530env[k] = v531print("env set %s=%s" % (k, v))532if env.DEBUG or env.DEBUG_SYMBOLS:533env.CHIBIOS_BUILD_FLAGS += ' ENABLE_DEBUG_SYMBOLS=yes'534if env.ENABLE_ASSERTS:535env.CHIBIOS_BUILD_FLAGS += ' ENABLE_ASSERTS=yes'536if env.ENABLE_MALLOC_GUARD:537env.CHIBIOS_BUILD_FLAGS += ' ENABLE_MALLOC_GUARD=yes'538if env.ENABLE_STATS:539env.CHIBIOS_BUILD_FLAGS += ' ENABLE_STATS=yes'540if env.ENABLE_DFU_BOOT and env.BOOTLOADER:541env.CHIBIOS_BUILD_FLAGS += ' USE_ASXOPT=-DCRT0_ENTRY_HOOK=TRUE'542if env.AP_BOARD_START_TIME:543env.CHIBIOS_BUILD_FLAGS += ' AP_BOARD_START_TIME=0x%x' % env.AP_BOARD_START_TIME544545546def setup_optimization(env):547'''setup optimization flags for build'''548if env.DEBUG:549OPTIMIZE = "-Og"550elif env.OPTIMIZE:551OPTIMIZE = env.OPTIMIZE552else:553OPTIMIZE = "-Os"554env.CFLAGS += [ OPTIMIZE ]555env.CXXFLAGS += [ OPTIMIZE ]556env.CHIBIOS_BUILD_FLAGS += ' USE_COPT=%s' % OPTIMIZE557558def configure(cfg):559cfg.find_program('make', var='MAKE')560#cfg.objcopy = cfg.find_program('%s-%s'%(cfg.env.TOOLCHAIN,'objcopy'), var='OBJCOPY', mandatory=True)561cfg.find_program('arm-none-eabi-objcopy', var='OBJCOPY')562env = cfg.env563bldnode = cfg.bldnode.make_node(cfg.variant)564def srcpath(path):565return cfg.srcnode.make_node(path).abspath()566567def bldpath(path):568return bldnode.make_node(path).abspath()569env.AP_PROGRAM_FEATURES += ['ch_ap_program']570571kw = env.AP_LIBRARIES_OBJECTS_KW572kw['features'] = Utils.to_list(kw.get('features', [])) + ['ch_ap_library']573574env.CH_ROOT = srcpath('modules/ChibiOS')575env.CC_ROOT = srcpath('modules/CrashDebug/CrashCatcher')576env.AP_HAL_ROOT = srcpath('libraries/AP_HAL_ChibiOS')577env.BUILDDIR = bldpath('modules/ChibiOS')578env.BUILDROOT = bldpath('')579env.SRCROOT = srcpath('')580env.PT_DIR = srcpath('Tools/ardupilotwaf/chibios/image')581env.MKFW_TOOLS = srcpath('Tools/ardupilotwaf')582env.UPLOAD_TOOLS = srcpath('Tools/scripts')583env.CHIBIOS_SCRIPTS = srcpath('libraries/AP_HAL_ChibiOS/hwdef/scripts')584env.TOOLS_SCRIPTS = srcpath('Tools/scripts')585env.APJ_TOOL = srcpath('Tools/scripts/apj_tool.py')586env.SERIAL_PORT = srcpath('/dev/serial/by-id/*_STLink*')587588# relative paths to pass to make, relative to directory that make is run from589env.CH_ROOT_REL = os.path.relpath(env.CH_ROOT, env.BUILDROOT)590env.CC_ROOT_REL = os.path.relpath(env.CC_ROOT, env.BUILDROOT)591env.AP_HAL_REL = os.path.relpath(env.AP_HAL_ROOT, env.BUILDROOT)592env.BUILDDIR_REL = os.path.relpath(env.BUILDDIR, env.BUILDROOT)593594mk_custom = srcpath('libraries/AP_HAL_ChibiOS/hwdef/%s/chibios_board.mk' % env.BOARD)595mk_common = srcpath('libraries/AP_HAL_ChibiOS/hwdef/common/chibios_board.mk')596# see if there is a board specific make file597if os.path.exists(mk_custom):598env.BOARD_MK = mk_custom599else:600env.BOARD_MK = mk_common601602if cfg.options.default_parameters:603cfg.msg('Default parameters', cfg.options.default_parameters, color='YELLOW')604env.DEFAULT_PARAMETERS = cfg.options.default_parameters605606try:607ret = generate_hwdef_h(env)608except Exception:609cfg.fatal("Failed to process hwdef.dat")610if ret != 0:611cfg.fatal("Failed to process hwdef.dat ret=%d" % ret)612load_env_vars(cfg.env)613if env.HAL_NUM_CAN_IFACES and not env.AP_PERIPH:614setup_canmgr_build(cfg)615if env.HAL_NUM_CAN_IFACES and env.AP_PERIPH and not env.BOOTLOADER:616setup_canperiph_build(cfg)617if env.HAL_NUM_CAN_IFACES and env.AP_PERIPH and int(env.HAL_NUM_CAN_IFACES)>1 and not env.BOOTLOADER:618env.DEFINES += [ 'CANARD_MULTI_IFACE=1' ]619setup_optimization(cfg.env)620621def generate_hwdef_h(env):622'''run chibios_hwdef.py'''623import subprocess624if env.BOOTLOADER:625if len(env.HWDEF) == 0:626env.HWDEF = os.path.join(env.SRCROOT, 'libraries/AP_HAL_ChibiOS/hwdef/%s/hwdef-bl.dat' % env.BOARD)627else:628# update to using hwdef-bl.dat629env.HWDEF = env.HWDEF.replace('hwdef.dat', 'hwdef-bl.dat')630env.BOOTLOADER_OPTION="--bootloader"631else:632if len(env.HWDEF) == 0:633env.HWDEF = os.path.join(env.SRCROOT, 'libraries/AP_HAL_ChibiOS/hwdef/%s/hwdef.dat' % env.BOARD)634env.BOOTLOADER_OPTION=""635636if env.AP_SIGNED_FIRMWARE:637print(env.BOOTLOADER_OPTION)638env.BOOTLOADER_OPTION += " --signed-fw"639print(env.BOOTLOADER_OPTION)640hwdef_script = os.path.join(env.SRCROOT, 'libraries/AP_HAL_ChibiOS/hwdef/scripts/chibios_hwdef.py')641hwdef_out = env.BUILDROOT642if not os.path.exists(hwdef_out):643os.mkdir(hwdef_out)644python = sys.executable645cmd = "{0} '{1}' -D '{2}' --params '{3}' '{4}'".format(python, hwdef_script, hwdef_out, env.DEFAULT_PARAMETERS, env.HWDEF)646if env.HWDEF_EXTRA:647cmd += " '{0}'".format(env.HWDEF_EXTRA)648if env.BOOTLOADER_OPTION:649cmd += " " + env.BOOTLOADER_OPTION650return subprocess.call(cmd, shell=True)651652def pre_build(bld):653'''pre-build hook to change dynamic sources'''654load_env_vars(bld.env)655if bld.env.HAL_NUM_CAN_IFACES:656bld.get_board().with_can = True657hwdef_h = os.path.join(bld.env.BUILDROOT, 'hwdef.h')658if not os.path.exists(hwdef_h):659print("Generating hwdef.h")660try:661ret = generate_hwdef_h(bld.env)662except Exception:663bld.fatal("Failed to process hwdef.dat")664if ret != 0:665bld.fatal("Failed to process hwdef.dat ret=%d" % ret)666setup_optimization(bld.env)667668def build(bld):669670671hwdef_rule="%s '%s/hwdef/scripts/chibios_hwdef.py' -D '%s' --params '%s' '%s'" % (672bld.env.get_flat('PYTHON'),673bld.env.AP_HAL_ROOT,674bld.env.BUILDROOT,675bld.env.default_parameters,676bld.env.HWDEF)677if bld.env.HWDEF_EXTRA:678hwdef_rule += " " + bld.env.HWDEF_EXTRA679if bld.env.BOOTLOADER_OPTION:680hwdef_rule += " " + bld.env.BOOTLOADER_OPTION681bld(682# build hwdef.h from hwdef.dat. This is needed after a waf clean683source=bld.path.ant_glob(bld.env.HWDEF),684rule=hwdef_rule,685group='dynamic_sources',686target=[bld.bldnode.find_or_declare('hwdef.h'),687bld.bldnode.find_or_declare('ldscript.ld'),688bld.bldnode.find_or_declare('hw.dat')]689)690691bld(692# create the file modules/ChibiOS/include_dirs693rule="touch Makefile && BUILDDIR=${BUILDDIR_REL} BUILDROOT=${BUILDROOT} CRASHCATCHER=${CC_ROOT_REL} CHIBIOS=${CH_ROOT_REL} AP_HAL=${AP_HAL_REL} ${CHIBIOS_BUILD_FLAGS} ${CHIBIOS_BOARD_NAME} ${MAKE} pass -f '${BOARD_MK}'",694group='dynamic_sources',695target=bld.bldnode.find_or_declare('modules/ChibiOS/include_dirs')696)697698bld(699# create the file modules/ChibiOS/include_dirs700rule="echo // BUILD_FLAGS: ${BUILDDIR_REL} ${BUILDROOT} ${CC_ROOT_REL} ${CH_ROOT_REL} ${AP_HAL_REL} ${CHIBIOS_BUILD_FLAGS} ${CHIBIOS_BOARD_NAME} ${HAL_MAX_STACK_FRAME_SIZE} > chibios_flags.h",701group='dynamic_sources',702target=bld.bldnode.find_or_declare('chibios_flags.h')703)704705common_src = [bld.bldnode.find_or_declare('hwdef.h'),706bld.bldnode.find_or_declare('hw.dat'),707bld.bldnode.find_or_declare('ldscript.ld'),708bld.bldnode.find_or_declare('common.ld'),709bld.bldnode.find_or_declare('modules/ChibiOS/include_dirs')]710common_src += bld.path.ant_glob('libraries/AP_HAL_ChibiOS/hwdef/common/*.[ch]')711common_src += bld.path.ant_glob('libraries/AP_HAL_ChibiOS/hwdef/common/*.mk')712common_src += bld.path.ant_glob('modules/ChibiOS/os/hal/**/*.[ch]')713common_src += bld.path.ant_glob('modules/ChibiOS/os/hal/**/*.mk')714if bld.env.ROMFS_FILES:715common_src += [bld.bldnode.find_or_declare('ap_romfs_embedded.h')]716717if bld.env.ENABLE_CRASHDUMP:718ch_task = bld(719# build libch.a from ChibiOS sources and hwdef.h720rule="BUILDDIR='${BUILDDIR_REL}' BUILDROOT='${BUILDROOT}' CRASHCATCHER='${CC_ROOT_REL}' CHIBIOS='${CH_ROOT_REL}' AP_HAL=${AP_HAL_REL} ${CHIBIOS_BUILD_FLAGS} ${CHIBIOS_BOARD_NAME} ${HAL_MAX_STACK_FRAME_SIZE} '${MAKE}' -j%u lib -f '${BOARD_MK}'" % bld.options.jobs,721group='dynamic_sources',722source=common_src,723target=[bld.bldnode.find_or_declare('modules/ChibiOS/libch.a'), bld.bldnode.find_or_declare('modules/ChibiOS/libcc.a')]724)725else:726ch_task = bld(727# build libch.a from ChibiOS sources and hwdef.h728rule="BUILDDIR='${BUILDDIR_REL}' BUILDROOT='${BUILDROOT}' CHIBIOS='${CH_ROOT_REL}' AP_HAL=${AP_HAL_REL} ${CHIBIOS_BUILD_FLAGS} ${CHIBIOS_BOARD_NAME} ${HAL_MAX_STACK_FRAME_SIZE} '${MAKE}' -j%u lib -f '${BOARD_MK}'" % bld.options.jobs,729group='dynamic_sources',730source=common_src,731target=bld.bldnode.find_or_declare('modules/ChibiOS/libch.a')732)733ch_task.name = "ChibiOS_lib"734DSP_LIBS = {735'cortex-m4' : 'libarm_cortexM4lf_math.a',736'cortex-m7' : 'libarm_cortexM7lfdp_math.a',737}738if bld.env.CORTEX in DSP_LIBS:739libname = DSP_LIBS[bld.env.CORTEX]740# we need to copy the library on cygwin as it doesn't handle linking outside build tree741shutil.copyfile(os.path.join(bld.env.SRCROOT,'libraries/AP_GyroFFT/CMSIS_5/lib',libname),742os.path.join(bld.env.BUILDROOT,'modules/ChibiOS/libDSP.a'))743bld.env.LIB += ['DSP']744bld.env.LIB += ['ch']745bld.env.LIBPATH += ['modules/ChibiOS/']746if bld.env.ENABLE_CRASHDUMP:747bld.env.LINKFLAGS += ['-Wl,-whole-archive', 'modules/ChibiOS/libcc.a', '-Wl,-no-whole-archive']748# list of functions that will be wrapped to move them out of libc into our749# own code750wraplist = ['sscanf', 'fprintf', 'snprintf', 'vsnprintf', 'vasprintf', 'asprintf', 'vprintf', 'scanf', 'printf']751752# list of functions that we will give a link error for if they are753# used. This is to prevent accidential use of these functions754blacklist = ['_sbrk', '_sbrk_r', '_malloc_r', '_calloc_r', '_free_r', 'ftell',755'fopen', 'fflush', 'fwrite', 'fread', 'fputs', 'fgets',756'clearerr', 'fseek', 'ferror', 'fclose', 'tmpfile', 'getc', 'ungetc', 'feof',757'ftell', 'freopen', 'remove', 'vfprintf', 'vfprintf_r', 'fscanf',758'_gettimeofday', '_times', '_times_r', '_gettimeofday_r', 'time', 'clock']759760# these functions use global state that is not thread safe761blacklist += ['gmtime']762763for w in wraplist + blacklist:764bld.env.LINKFLAGS += ['-Wl,--wrap,%s' % w]765766767