Path: blob/master/Tools/AP_Bootloader/bl_protocol.cpp
9354 views
/*1ArduPilot bootloader protocol23based on bl.c from https://github.com/PX4/Bootloader.45Ported to ChibiOS for ArduPilot by Andrew Tridgell6*/78/****************************************************************************9*10* Copyright (c) 2012-2014 PX4 Development Team. All rights reserved.11*12* Redistribution and use in source and binary forms, with or without13* modification, are permitted provided that the following conditions14* are met:15*16* 1. Redistributions of source code must retain the above copyright17* notice, this list of conditions and the following disclaimer.18* 2. Redistributions in binary form must reproduce the above copyright19* notice, this list of conditions and the following disclaimer in20* the documentation and/or other materials provided with the21* distribution.22* 3. Neither the name PX4 nor the names of its contributors may be23* used to endorse or promote products derived from this software24* without specific prior written permission.25*26* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS27* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT28* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS29* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE30* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,31* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,32* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS33* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED34* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT35* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN36* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE37* POSSIBILITY OF SUCH DAMAGE.38*39****************************************************************************/4041#include <AP_HAL/AP_HAL.h>42#include <AP_Math/AP_Math.h>43#include <AP_Math/crc.h>44#include "ch.h"45#include "hal.h"46#include "hwdef.h"4748#include "bl_protocol.h"49#include "support.h"50#include "can.h"51#include <AP_HAL_ChibiOS/hwdef/common/watchdog.h>52#if EXT_FLASH_SIZE_MB53#include <AP_FlashIface/AP_FlashIface_JEDEC.h>54#endif55#include <AP_CheckFirmware/AP_CheckFirmware.h>5657#define FORCE_VERSION_H_INCLUDE58#include "ap_version.h"59#undef FORCE_VERSION_H_INCLUDE6061// bootloader flash update protocol.62//63// Command format:64//65// <opcode>[<command_data>]<EOC>66//67// Reply format:68//69// [<reply_data>]<INSYNC><status>70//71// The <opcode> and <status> values come from the PROTO_ defines below,72// the <*_data> fields is described only for opcodes that transfer data;73// in all other cases the field is omitted.74//75// Expected workflow (protocol 3) is:76//77// GET_SYNC verify that the board is present78// GET_DEVICE determine which board (select firmware to upload)79// CHIP_ERASE erase the program area and reset address counter80// loop:81// PROG_MULTI program bytes82// GET_CRC verify CRC of entire flashable area83// RESET finalise flash programming, reset chip and starts application84//8586#define BL_PROTOCOL_VERSION 5 // The revision of the bootloader protocol87// protocol bytes88#define PROTO_INSYNC 0x12 // 'in sync' byte sent before status89#define PROTO_EOC 0x20 // end of command9091// Reply bytes92#define PROTO_OK 0x10 // INSYNC/OK - 'ok' response93#define PROTO_FAILED 0x11 // INSYNC/FAILED - 'fail' response94#define PROTO_INVALID 0x13 // INSYNC/INVALID - 'invalid' response for bad commands95#define PROTO_BAD_SILICON_REV 0x14 // On the F4 series there is an issue with < Rev 3 silicon96// see https://pixhawk.org/help/errata97// Command bytes98#define PROTO_GET_SYNC 0x21 // NOP for re-establishing sync99#define PROTO_GET_DEVICE 0x22 // get device ID bytes100#define PROTO_CHIP_ERASE 0x23 // erase program area and reset program address101#define PROTO_PROG_MULTI 0x27 // write bytes at program address and increment102#define PROTO_READ_MULTI 0x28 // read bytes at address and increment103#define PROTO_GET_CRC 0x29 // compute & return a CRC104#define PROTO_GET_OTP 0x2a // read a byte from OTP at the given address105#define PROTO_GET_SN 0x2b // read a word from UDID area ( Serial) at the given address106#define PROTO_GET_CHIP 0x2c // read chip version (MCU IDCODE)107#define PROTO_SET_DELAY 0x2d // set minimum boot delay108#define PROTO_GET_CHIP_DES 0x2e // read chip version In ASCII109#define PROTO_GET_VERSION 0x2f // read version110#define PROTO_BOOT 0x30 // boot the application111#define PROTO_DEBUG 0x31 // emit debug information - format not defined112#define PROTO_SET_BAUD 0x33 // baud rate on uart113114// External Flash programming115#define PROTO_EXTF_ERASE 0x34 // Erase sectors from external flash116#define PROTO_EXTF_PROG_MULTI 0x35 // write bytes at external flash program address and increment117#define PROTO_EXTF_READ_MULTI 0x36 // read bytes at address and increment118#define PROTO_EXTF_GET_CRC 0x37 // compute & return a CRC of data in external flash119120#define PROTO_CHIP_FULL_ERASE 0x40 // erase program area and reset program address, skip any flash wear optimization and force an erase121122#define PROTO_PROG_MULTI_MAX 64 // maximum PROG_MULTI size123#define PROTO_READ_MULTI_MAX 255 // size of the size field124125/* argument values for PROTO_GET_DEVICE */126#define PROTO_DEVICE_BL_REV 1 // bootloader revision127#define PROTO_DEVICE_BOARD_ID 2 // board ID128#define PROTO_DEVICE_BOARD_REV 3 // board revision129#define PROTO_DEVICE_FW_SIZE 4 // size of flashable area130#define PROTO_DEVICE_VEC_AREA 5 // contents of reserved vectors 7-10131#define PROTO_DEVICE_EXTF_SIZE 6 // size of available external flash132// all except PROTO_DEVICE_VEC_AREA and PROTO_DEVICE_BOARD_REV should be done133#define CHECK_GET_DEVICE_FINISHED(x) ((x & (0xB)) == 0xB)134135// interrupt vector table for STM32136#define SCB_VTOR 0xE000ED08137138static virtual_timer_t systick_vt;139140/*141millisecond timer array142*/143#define NTIMERS 2144#define TIMER_BL_WAIT 0145#define TIMER_LED 1146147static enum led_state led_state;148149volatile unsigned timer[NTIMERS];150151// keep back 32 bytes at the front of flash. This is long enough to allow for aligned152// access on STM32H7153#define RESERVE_LEAD_WORDS 8154155156#if EXT_FLASH_SIZE_MB157extern AP_FlashIface_JEDEC ext_flash;158#endif159160#ifndef BOOT_FROM_EXT_FLASH161#define BOOT_FROM_EXT_FLASH 0162#endif163164/*1651ms timer tick callback166*/167static void sys_tick_handler(virtual_timer_t* vt, void *ctx)168{169chSysLockFromISR();170chVTSetI(&systick_vt, chTimeMS2I(1), sys_tick_handler, nullptr);171chSysUnlockFromISR();172uint8_t i;173for (i = 0; i < NTIMERS; i++)174if (timer[i] > 0) {175timer[i]--;176}177178if ((led_state == LED_BLINK) && (timer[TIMER_LED] == 0)) {179led_toggle(LED_BOOTLOADER);180timer[TIMER_LED] = 50;181}182183if ((led_state == LED_BAD_FW) && (timer[TIMER_LED] == 0)) {184led_toggle(LED_BOOTLOADER);185timer[TIMER_LED] = 1000;186}187}188189static void delay(unsigned msec)190{191chThdSleep(chTimeMS2I(msec));192}193194void195led_set(enum led_state state)196{197led_state = state;198199switch (state) {200case LED_OFF:201led_off(LED_BOOTLOADER);202break;203204case LED_ON:205led_on(LED_BOOTLOADER);206break;207208case LED_BLINK:209/* restart the blink state machine ASAP */210timer[TIMER_LED] = 0;211break;212213case LED_BAD_FW:214timer[TIMER_LED] = 0;215break;216}217}218219static void220do_jump(uint32_t stacktop, uint32_t entrypoint)221{222#if defined(STM32F7) || defined(STM32H7)223// disable caches on F7 before starting program224__DSB();225__ISB();226SCB_DisableDCache();227SCB_DisableICache();228#endif229230chSysLock();231232// we set sp as well as msp to avoid an issue with loading NuttX233asm volatile(234"mov sp, %0 \n"235"msr msp, %0 \n"236"bx %1 \n"237: : "r"(stacktop), "r"(entrypoint) :);238}239240#ifndef APP_START_ADDRESS241#define APP_START_ADDRESS (FLASH_LOAD_ADDRESS + (FLASH_BOOTLOADER_LOAD_KB + APP_START_OFFSET_KB)*1024U)242#endif243244#if !defined(STM32_OTG2_IS_OTG1)245#define STM32_OTG2_IS_OTG1 0246#endif247248void249jump_to_app()250{251const uint32_t *app_base = (const uint32_t *)(APP_START_ADDRESS);252253#if AP_CHECK_FIRMWARE_ENABLED254const auto ok = check_good_firmware();255if (ok != check_fw_result_t::CHECK_FW_OK) {256// bad firmware, don't try and boot257led_set(LED_BAD_FW);258return;259}260#endif261262// If we have QSPI chip start it263#if EXT_FLASH_SIZE_MB264uint8_t* ext_flash_start_addr;265if (!ext_flash.start_xip_mode((void**)&ext_flash_start_addr)) {266return;267}268#endif269/*270* We hold back the programming of the lead words until the upload271* is marked complete by the host. So if they are not 0xffffffff,272* we should try booting it.273*/274for (uint8_t i=0; i<RESERVE_LEAD_WORDS; i++) {275if (app_base[i] == 0xffffffff) {276goto exit;277}278}279280/*281* The second word of the app is the entrypoint; it must point within the282* flash area (or we have a bad flash).283*/284if (app_base[1] < APP_START_ADDRESS) {285goto exit;286}287288#if BOOT_FROM_EXT_FLASH289if (app_base[1] >= (APP_START_ADDRESS + board_info.extf_size)) {290goto exit;291}292#else293if (app_base[1] >= (APP_START_ADDRESS + board_info.fw_size)) {294goto exit;295}296#endif297298#if HAL_USE_CAN == TRUE || HAL_NUM_CAN_IFACES299// for CAN firmware we start the watchdog before we run the300// application code, to ensure we catch a bad firmare. If we get a301// watchdog reset and the firmware hasn't changed the RTC flag to302// indicate that it has been running OK for 30s then we will stay303// in bootloader304#ifndef DISABLE_WATCHDOG305stm32_watchdog_init();306#endif307stm32_watchdog_pat();308#endif309310flash_set_keep_unlocked(false);311312led_set(LED_OFF);313314// resetting the clocks is needed for loading NuttX315#if defined(STM32H7)316rccDisableAPB1L(~0);317rccDisableAPB1H(~0);318#elif defined(STM32G4)319rccDisableAPB1R1(~0);320rccDisableAPB1R2(~0);321#elif defined(STM32L4)322rccDisableAPB1R1(~0);323rccDisableAPB1R2(~0);324#elif defined(STM32L4PLUS)325rccDisableAPB1R1(~0);326rccDisableAPB1R2(~0);327#else328rccDisableAPB1(~0);329#endif330rccDisableAPB2(~0);331#if HAL_USE_SERIAL_USB == TRUE332#if !STM32_OTG2_IS_OTG1333rccResetOTG_FS();334#endif335#if defined(rccResetOTG_HS)336rccResetOTG_HS();337#endif338#endif339340// disable all interrupt sources341port_disable();342343/* switch exception handlers to the application */344*(volatile uint32_t *)SCB_VTOR = APP_START_ADDRESS;345346/* extract the stack and entrypoint from the app vector table and go */347do_jump(app_base[0], app_base[1]);348exit:349#if EXT_FLASH_SIZE_MB350ext_flash.stop_xip_mode();351#endif352return;353}354355static void356sync_response(void)357{358static const uint8_t data[] = {359PROTO_INSYNC, // "in sync"360PROTO_OK // "OK"361};362363cout(data, sizeof(data));364}365366static void367invalid_response(void)368{369static const uint8_t data[] = {370PROTO_INSYNC, // "in sync"371PROTO_INVALID // "invalid command"372};373374cout(data, sizeof(data));375}376377static void378failure_response(void)379{380static const uint8_t data[] = {381PROTO_INSYNC, // "in sync"382PROTO_FAILED // "command failed"383};384385cout(data, sizeof(data));386}387388/**389* Function to wait for EOC390*391* @param timeout length of time in ms to wait for the EOC to be received392* @return true if the EOC is returned within the timeout perio, else false393*/394inline static bool395wait_for_eoc(unsigned timeout)396{397return cin(timeout) == PROTO_EOC;398}399400static void401cout_word(uint32_t val)402{403cout((uint8_t *)&val, sizeof(uint32_t));404}405406#define TEST_FLASH 0407408#if TEST_FLASH409static void test_flash()410{411uint32_t loop = 1;412bool init_done = false;413while (true) {414uint32_t addr = 0;415uint32_t page = 0;416while (true) {417uint32_t v[8];418for (uint8_t i=0; i<8; i++) {419v[i] = (page<<16) + loop;420}421if (flash_func_sector_size(page) == 0) {422continue;423}424uint32_t num_writes = flash_func_sector_size(page) / sizeof(v);425uprintf("page %u size %u addr=0x%08x v=0x%08x\n",426unsigned(page), unsigned(flash_func_sector_size(page)), unsigned(addr), unsigned(v[0])); delay(10);427if (init_done) {428for (uint32_t j=0; j<flash_func_sector_size(page)/4; j++) {429uint32_t v1 = (page<<16) + (loop-1);430uint32_t v2 = flash_func_read_word(addr+j*4);431if (v2 != v1) {432uprintf("read error at 0x%08x v=0x%08x v2=0x%08x\n", unsigned(addr+j*4), unsigned(v1), unsigned(v2));433break;434}435}436}437if (!flash_func_erase_sector(page)) {438uprintf("erase of %u failed\n", unsigned(page));439}440for (uint32_t j=0; j<num_writes; j++) {441if (!flash_func_write_words(addr+j*sizeof(v), v, ARRAY_SIZE(v))) {442uprintf("write failed at 0x%08x\n", unsigned(addr+j*sizeof(v)));443break;444}445}446addr += flash_func_sector_size(page);447page++;448if (flash_func_sector_size(page) == 0) {449break;450}451}452init_done = true;453delay(1000);454loop++;455}456}457#endif458459void460bootloader(unsigned timeout)461{462#if TEST_FLASH463test_flash();464#endif465466uint32_t address = board_info.fw_size; /* force erase before upload will work */467#if EXT_FLASH_SIZE_MB468uint32_t extf_address = board_info.extf_size; /* force erase before upload will work */469#endif470uint32_t read_address = 0;471uint32_t first_words[RESERVE_LEAD_WORDS];472bool done_sync = false;473uint8_t done_get_device_flags = 0;474bool done_erase = false;475static bool done_timer_init;476unsigned original_timeout = timeout;477478memset(first_words, 0xFF, sizeof(first_words));479480if (!done_timer_init) {481done_timer_init = true;482chVTObjectInit(&systick_vt);483chVTSet(&systick_vt, chTimeMS2I(1), sys_tick_handler, nullptr);484}485486/* if we are working with a timeout, start it running */487if (timeout) {488timer[TIMER_BL_WAIT] = timeout;489}490491/* make the LED blink while we are idle */492// ensure we don't override BAD FW LED493if (led_state != LED_BAD_FW) {494led_set(LED_BLINK);495}496497while (true) {498int c;499int arg;500static union {501uint8_t c[256];502uint32_t w[64];503} flash_buffer;504505// Wait for a command byte506led_off(LED_ACTIVITY);507508do {509/* if we have a timeout and the timer has expired and serial forward is not busy, return now */510#if defined(BOOTLOADER_FORWARD_OTG2_SERIAL)511bool ser_forward_active = update_otg2_serial_forward();512#endif513if (timeout && !timer[TIMER_BL_WAIT]514#if defined(BOOTLOADER_FORWARD_OTG2_SERIAL)515// do serial forward only when idle516&& !ser_forward_active517#endif518) {519return;520}521522/* try to get a byte from the host */523c = cin(0);524#if HAL_USE_CAN == TRUE || HAL_NUM_CAN_IFACES525if (c < 0) {526can_update();527}528#endif529} while (c < 0);530531led_on(LED_ACTIVITY);532533// handle the command byte534switch (c) {535536// sync537//538// command: GET_SYNC/EOC539// reply: INSYNC/OK540//541case PROTO_GET_SYNC:542543/* expect EOC */544if (!wait_for_eoc(2)) {545goto cmd_bad;546}547done_sync = true;548break;549550// get device info551//552// command: GET_DEVICE/<arg:1>/EOC553// BL_REV reply: <revision:4>/INSYNC/EOC554// BOARD_ID reply: <board type:4>/INSYNC/EOC555// BOARD_REV reply: <board rev:4>/INSYNC/EOC556// FW_SIZE reply: <firmware size:4>/INSYNC/EOC557// VEC_AREA reply <vectors 7-10:16>/INSYNC/EOC558// bad arg reply: INSYNC/INVALID559//560case PROTO_GET_DEVICE:561/* expect arg then EOC */562arg = cin(1000);563564if (arg < 0) {565goto cmd_bad;566}567568if (!wait_for_eoc(2)) {569goto cmd_bad;570}571572// reset read pointer573read_address = 0;574575switch (arg) {576case PROTO_DEVICE_BL_REV: {577cout_word(BL_PROTOCOL_VERSION);578break;579}580581case PROTO_DEVICE_BOARD_ID:582cout_word(board_info.board_type);583break;584585case PROTO_DEVICE_BOARD_REV:586cout_word(board_info.board_rev);587break;588589case PROTO_DEVICE_FW_SIZE:590cout_word(board_info.fw_size);591break;592593case PROTO_DEVICE_VEC_AREA:594for (unsigned p = 7; p <= 10; p++) {595cout_word(flash_func_read_word(p * 4));596}597598break;599600case PROTO_DEVICE_EXTF_SIZE:601cout_word(board_info.extf_size);602break;603604default:605goto cmd_bad;606}607done_get_device_flags |= (1<<(arg-1)); // set the flags for use when resetting timeout608break;609610// erase and prepare for programming611//612// command: ERASE/EOC613// success reply: INSYNC/OK614// erase failure: INSYNC/FAILURE615//616case PROTO_CHIP_ERASE:617#if defined(STM32F7) || defined(STM32H7)618case PROTO_CHIP_FULL_ERASE:619#endif620621if (!done_sync || !CHECK_GET_DEVICE_FINISHED(done_get_device_flags)) {622// lower chance of random data on a uart triggering erase623goto cmd_bad;624}625626/* expect EOC */627if (!wait_for_eoc(2)) {628goto cmd_bad;629}630631// once erase is done there is no going back, set timeout632// to zero633done_erase = true;634timeout = 0;635636flash_set_keep_unlocked(true);637638// clear the bootloader LED while erasing - it stops blinking at random639// and that's confusing640led_set(LED_OFF);641642// erase all sectors643for (uint16_t i = 0; flash_func_sector_size(i) != 0; i++) {644#if defined(STM32F7) || defined(STM32H7)645if (!flash_func_erase_sector(i, c == PROTO_CHIP_FULL_ERASE)) {646#else647if (!flash_func_erase_sector(i)) {648#endif649goto cmd_fail;650}651}652653// enable the LED while verifying the erase654led_set(LED_ON);655656// verify the erase657for (address = 0; address < board_info.fw_size; address += 4) {658if (flash_func_read_word(address) != 0xffffffff) {659goto cmd_fail;660}661}662663address = 0;664665// resume blinking666led_set(LED_BLINK);667break;668669// program data from start of the flash670//671// command: EXTF_ERASE/<len:4>/EOC672// success reply: INSYNC/OK673// invalid reply: INSYNC/INVALID674// readback failure: INSYNC/FAILURE675//676case PROTO_EXTF_ERASE:677#if EXT_FLASH_SIZE_MB678{679if (!done_sync || !CHECK_GET_DEVICE_FINISHED(done_get_device_flags)) {680// lower chance of random data on a uart triggering erase681goto cmd_bad;682}683uint32_t cmd_erase_bytes;684if (cin_word(&cmd_erase_bytes, 100)) {685goto cmd_bad;686}687688// expect EOC689if (!wait_for_eoc(2)) {690goto cmd_bad;691}692uint32_t erased_bytes = 0;693uint32_t sector_number = EXT_FLASH_RESERVE_START_KB * 1024 / ext_flash.get_sector_size();694uint8_t pct_done = 0;695if (cmd_erase_bytes > (ext_flash.get_sector_size() * ext_flash.get_sector_count())) {696uprintf("Requested to erase more than we can\n");697goto cmd_bad;698}699uprintf("Erase Command Received\n");700sync_response();701cout(&pct_done, sizeof(pct_done));702// Flash all sectors that encompass the erase_bytes703while (erased_bytes < cmd_erase_bytes) {704uint32_t delay_ms = 0, timeout_ms = 0;705if (!ext_flash.start_sector_erase(sector_number, delay_ms, timeout_ms)) {706goto cmd_fail;707}708uint32_t next_check_ms = AP_HAL::millis() + delay_ms;709while (true) {710cout(&pct_done, sizeof(pct_done));711if (AP_HAL::millis() > next_check_ms) {712if (!ext_flash.is_device_busy()) {713pct_done = erased_bytes*100/cmd_erase_bytes;714uprintf("PCT DONE: %d\n", pct_done);715break;716}717if ((AP_HAL::millis() + timeout_ms) > next_check_ms) {718// We are out of time, return error719goto cmd_fail;720}721next_check_ms = AP_HAL::millis()+delay_ms;722}723chThdSleep(chTimeMS2I(delay_ms));724}725erased_bytes += ext_flash.get_sector_size();726sector_number++;727}728pct_done = 100;729extf_address = 0;730cout(&pct_done, sizeof(pct_done));731}732#else733goto cmd_bad;734#endif // EXT_FLASH_SIZE_MB735break;736737// program bytes at current external flash address738//739// command: PROG_MULTI/<len:1>/<data:len>/EOC740// success reply: INSYNC/OK741// invalid reply: INSYNC/INVALID742// readback failure: INSYNC/FAILURE743//744case PROTO_EXTF_PROG_MULTI:745{746#if EXT_FLASH_SIZE_MB747if (!done_sync || !CHECK_GET_DEVICE_FINISHED(done_get_device_flags)) {748// lower chance of random data on a uart triggering erase749goto cmd_bad;750}751752// expect count753led_set(LED_OFF);754755arg = cin(50);756757if (arg < 0) {758goto cmd_bad;759}760761if ((extf_address + arg) > board_info.extf_size) {762goto cmd_bad;763}764765if (arg > sizeof(flash_buffer.c)) {766goto cmd_bad;767}768769for (int i = 0; i < arg; i++) {770c = cin(1000);771772if (c < 0) {773goto cmd_bad;774}775776flash_buffer.c[i] = c;777}778779if (!wait_for_eoc(200)) {780goto cmd_bad;781}782783uint32_t offset = 0;784uint32_t size = arg;785#if BOOT_FROM_EXT_FLASH786// save the first words and don't program it until everything else is done787if (extf_address < sizeof(first_words)) {788uint8_t n = MIN(sizeof(first_words)-extf_address, arg);789memcpy(&first_words[extf_address/4], &flash_buffer.w[0], n);790// replace first words with 1 bits we can overwrite later791memset(&flash_buffer.w[0], 0xFF, n);792}793#endif794uint32_t programming;795uint32_t delay_us = 0, timeout_us = 0;796uint64_t start_time_us;797while (true) {798if (size == 0) {799extf_address += arg;800break;801}802if (!ext_flash.start_program_offset(extf_address+offset+EXT_FLASH_RESERVE_START_KB*1024,803&flash_buffer.c[offset], size, programming, delay_us, timeout_us)) {804// uprintf("ext flash write command failed\n");805goto cmd_fail;806}807start_time_us = AP_HAL::micros64();808// prepare for next run809offset += programming;810size -= programming;811while (true) {812if (AP_HAL::micros64() > (start_time_us+delay_us)) {813if (!ext_flash.is_device_busy()) {814// uprintf("flash program Successful, elapsed %ld us\n", uint32_t(AP_HAL::micros64() - start_time_us));815break;816} else {817// uprintf("Typical flash program time reached, Still Busy?!\n");818}819}820}821}822#endif823break;824}825826// program bytes at current address827//828// command: PROG_MULTI/<len:1>/<data:len>/EOC829// success reply: INSYNC/OK830// invalid reply: INSYNC/INVALID831// readback failure: INSYNC/FAILURE832//833case PROTO_PROG_MULTI: // program bytes834if (!done_sync || !CHECK_GET_DEVICE_FINISHED(done_get_device_flags)) {835// lower chance of random data on a uart triggering erase836goto cmd_bad;837}838839// expect count840led_set(LED_OFF);841842arg = cin(50);843844if (arg < 0) {845goto cmd_bad;846}847848// sanity-check arguments849if (arg % 4) {850goto cmd_bad;851}852853if ((address + arg) > board_info.fw_size) {854goto cmd_bad;855}856857if (arg > sizeof(flash_buffer.c)) {858goto cmd_bad;859}860861for (int i = 0; i < arg; i++) {862c = cin(1000);863864if (c < 0) {865goto cmd_bad;866}867868flash_buffer.c[i] = c;869}870871if (!wait_for_eoc(200)) {872goto cmd_bad;873}874875// save the first words and don't program it until everything else is done876#if !BOOT_FROM_EXT_FLASH877if (address < sizeof(first_words)) {878uint8_t n = MIN(sizeof(first_words)-address, arg);879memcpy(&first_words[address/4], &flash_buffer.w[0], n);880// replace first words with 1 bits we can overwrite later881memset(&flash_buffer.w[0], 0xFF, n);882}883#endif884arg /= 4;885// program the words886if (!flash_write_buffer(address, flash_buffer.w, arg)) {887goto cmd_fail;888}889address += arg * 4;890break;891892// fetch CRC of the entire flash area893//894// command: GET_CRC/EOC895// reply: <crc:4>/INSYNC/OK896//897case PROTO_GET_CRC: {898// expect EOC899if (!wait_for_eoc(2)) {900goto cmd_bad;901}902903if (!flash_write_flush()) {904goto cmd_bad;905}906907// compute CRC of the programmed area908uint32_t sum = 0;909910for (unsigned p = 0; p < board_info.fw_size; p += 4) {911uint32_t bytes;912913#if !BOOT_FROM_EXT_FLASH914if (p < sizeof(first_words) && first_words[0] != 0xFFFFFFFF) {915bytes = first_words[p/4];916} else917#endif918{919bytes = flash_func_read_word(p);920}921sum = crc32_small(sum, (uint8_t *)&bytes, sizeof(bytes));922}923924cout_word(sum);925break;926}927928// fetch CRC of the external flash area929//930// command: EXTF_GET_CRC/<len:4>/EOC931// reply: <crc:4>/INSYNC/OK932//933case PROTO_EXTF_GET_CRC: {934#if EXT_FLASH_SIZE_MB935// expect EOC936uint32_t cmd_verify_bytes;937if (cin_word(&cmd_verify_bytes, 100)) {938goto cmd_bad;939}940941if (!wait_for_eoc(2)) {942goto cmd_bad;943}944945// compute CRC of the programmed area946uint32_t sum = 0;947uint8_t rembytes = cmd_verify_bytes % 4;948for (unsigned p = 0; p < (cmd_verify_bytes-rembytes); p+=4) {949uint32_t bytes;950951#if BOOT_FROM_EXT_FLASH952if (p < sizeof(first_words) && first_words[0] != 0xFFFFFFFF) {953bytes = first_words[p/4];954} else955#endif956{957ext_flash.read(p+EXT_FLASH_RESERVE_START_KB*1024, (uint8_t *)&bytes, sizeof(bytes));958}959sum = crc32_small(sum, (uint8_t *)&bytes, sizeof(bytes));960}961if (rembytes) {962uint8_t bytes[3];963ext_flash.read(EXT_FLASH_RESERVE_START_KB*1024+cmd_verify_bytes-rembytes, bytes, rembytes);964sum = crc32_small(sum, bytes, rembytes);965}966cout_word(sum);967break;968#endif969}970971// read a word from the OTP972//973// command: GET_OTP/<addr:4>/EOC974// reply: <value:4>/INSYNC/OK975case PROTO_GET_OTP:976// expect argument977{978uint32_t index = 0;979980if (cin_word(&index, 100)) {981goto cmd_bad;982}983984// expect EOC985if (!wait_for_eoc(2)) {986goto cmd_bad;987}988989cout_word(flash_func_read_otp(index));990}991break;992993// read the SN from the UDID994//995// command: GET_SN/<addr:4>/EOC996// reply: <value:4>/INSYNC/OK997case PROTO_GET_SN:998// expect argument999{1000uint32_t index = 0;10011002if (cin_word(&index, 100)) {1003goto cmd_bad;1004}10051006// expect EOC1007if (!wait_for_eoc(2)) {1008goto cmd_bad;1009}10101011cout_word(flash_func_read_sn(index));1012}1013break;10141015// read the chip ID code1016//1017// command: GET_CHIP/EOC1018// reply: <value:4>/INSYNC/OK1019case PROTO_GET_CHIP: {1020// expect EOC1021if (!wait_for_eoc(2)) {1022goto cmd_bad;1023}10241025cout_word(get_mcu_id());1026}1027break;10281029// read the chip description1030//1031// command: GET_CHIP_DES/EOC1032// reply: <value:4>/INSYNC/OK1033case PROTO_GET_CHIP_DES: {1034uint8_t buffer[MAX_DES_LENGTH];1035unsigned len = MAX_DES_LENGTH;10361037// expect EOC1038if (!wait_for_eoc(2)) {1039goto cmd_bad;1040}10411042len = get_mcu_desc(len, buffer);1043cout_word(len);1044cout(buffer, len);1045}1046break;10471048// read the bootloader version (not to be confused with protocol revision)1049//1050// command: GET_VERSION/EOC1051// reply: <length:4><buffer...>/INSYNC/OK1052#if HAL_PROGRAM_SIZE_LIMIT_KB > 10241053case PROTO_GET_VERSION: {1054uint8_t buffer[MAX_VERSION_LENGTH];10551056// expect EOC1057if (!wait_for_eoc(2)) {1058goto cmd_bad;1059}10601061uint32_t len = strlen(GIT_VERSION_EXTENDED);1062if (len > MAX_VERSION_LENGTH) {1063len = MAX_VERSION_LENGTH;1064}1065memcpy(buffer, GIT_VERSION_EXTENDED, len);10661067cout_word(len);1068cout(buffer, len);1069}1070break;1071#endif10721073#ifdef BOOT_DELAY_ADDRESS10741075case PROTO_SET_DELAY: {1076/*1077Allow for the bootloader to setup a1078boot delay signature which tells the1079board to delay for at least a1080specified number of seconds on boot.1081*/1082int v = cin(100);10831084if (v < 0) {1085goto cmd_bad;1086}10871088uint8_t boot_delay = v & 0xFF;10891090if (boot_delay > BOOT_DELAY_MAX) {1091goto cmd_bad;1092}10931094// expect EOC1095if (!wait_for_eoc(2)) {1096goto cmd_bad;1097}10981099uint32_t sig1 = flash_func_read_word(BOOT_DELAY_ADDRESS);1100uint32_t sig2 = flash_func_read_word(BOOT_DELAY_ADDRESS + 4);11011102if (sig1 != BOOT_DELAY_SIGNATURE1 ||1103sig2 != BOOT_DELAY_SIGNATURE2) {1104goto cmd_bad;1105}11061107uint32_t value = (BOOT_DELAY_SIGNATURE1 & 0xFFFFFF00) | boot_delay;1108flash_func_write_word(BOOT_DELAY_ADDRESS, value);11091110if (flash_func_read_word(BOOT_DELAY_ADDRESS) != value) {1111goto cmd_fail;1112}1113}1114break;1115#endif11161117case PROTO_READ_MULTI: {1118arg = cin(50);1119if (arg < 0) {1120goto cmd_bad;1121}1122if (arg % 4) {1123goto cmd_bad;1124}1125if ((read_address + arg) > board_info.fw_size) {1126goto cmd_bad;1127}1128// expect EOC1129if (!wait_for_eoc(2)) {1130goto cmd_bad;1131}1132arg /= 4;11331134while (arg-- > 0) {1135cout_word(flash_func_read_word(read_address));1136read_address += 4;1137}1138break;1139}11401141// finalise programming and boot the system1142//1143// command: BOOT/EOC1144// reply: INSYNC/OK1145//1146case PROTO_BOOT:11471148// expect EOC1149if (!wait_for_eoc(1000)) {1150goto cmd_bad;1151}11521153if (!flash_write_flush()) {1154goto cmd_fail;1155}11561157// program the deferred first word1158if (first_words[0] != 0xffffffff) {1159#if !BOOT_FROM_EXT_FLASH1160if (!flash_write_buffer(0, first_words, RESERVE_LEAD_WORDS)) {1161goto cmd_fail;1162}1163#else1164uint32_t programming;1165uint32_t delay_us;1166uint32_t timeout_us;1167if (!ext_flash.start_program_offset(EXT_FLASH_RESERVE_START_KB*1024, (const uint8_t*)first_words, sizeof(first_words), programming, delay_us, timeout_us)) {1168// uprintf("ext flash write command failed\n");1169goto cmd_fail;1170}1171uint64_t start_time_us = AP_HAL::micros64();1172while (true) {1173if (AP_HAL::micros64() > (start_time_us+delay_us)) {1174if (!ext_flash.is_device_busy()) {1175// uprintf("flash program Successful, elapsed %ld us\n", uint32_t(AP_HAL::micros64() - start_time_us));1176break;1177} else {1178// uprintf("Typical flash program time reached, Still Busy?!\n");1179}1180}1181}1182#endif1183// revert in case the flash was bad...1184memset(first_words, 0xff, sizeof(first_words));1185}11861187// send a sync and wait for it to be collected1188sync_response();1189delay(100);11901191// quiesce and jump to the app1192return;11931194case PROTO_DEBUG:1195// XXX reserved for ad-hoc debugging as required1196break;11971198case PROTO_SET_BAUD: {1199if (!done_sync || !CHECK_GET_DEVICE_FINISHED(done_get_device_flags)) {1200// prevent timeout going to zero on noise1201goto cmd_bad;1202}1203/* expect arg then EOC */1204uint32_t baud = 0;12051206if (cin_word(&baud, 100)) {1207goto cmd_bad;1208}12091210if (!wait_for_eoc(2)) {1211goto cmd_bad;1212}12131214// send the sync response for this command1215sync_response();12161217delay(5);12181219// set the baudrate1220port_setbaud(baud);12211222lock_bl_port();1223timeout = 0;12241225// this is different to what every other case in this1226// switch does! Most go through sync_response down the1227// bottom, but we need to undertake an action after1228// returning the response...1229continue;1230}12311232default:1233continue;1234}12351236// we got a good command on this port, lock to the port1237lock_bl_port();12381239// once we get both a valid sync and valid get_device then kill1240// the timeout1241if (done_sync && CHECK_GET_DEVICE_FINISHED(done_get_device_flags)) {1242timeout = 0;1243}12441245// send the sync response for this command1246sync_response();1247continue;1248cmd_bad:1249// if we get a bad command it could be line noise on a1250// uart. Set timeout back to original timeout so we don't get1251// stuck in the bootloader1252if (!done_erase) {1253timeout = original_timeout;1254}1255// send an 'invalid' response but don't kill the timeout - could be garbage1256invalid_response();1257continue;12581259cmd_fail:1260// send a 'command failed' response but don't kill the timeout - could be garbage1261failure_response();1262continue;1263}1264}126512661267