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/AP_Bootloader/bl_protocol.cpp
Views: 1798
/*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// #pragma GCC optimize("O0")585960// bootloader flash update protocol.61//62// Command format:63//64// <opcode>[<command_data>]<EOC>65//66// Reply format:67//68// [<reply_data>]<INSYNC><status>69//70// The <opcode> and <status> values come from the PROTO_ defines below,71// the <*_data> fields is described only for opcodes that transfer data;72// in all other cases the field is omitted.73//74// Expected workflow (protocol 3) is:75//76// GET_SYNC verify that the board is present77// GET_DEVICE determine which board (select firmware to upload)78// CHIP_ERASE erase the program area and reset address counter79// loop:80// PROG_MULTI program bytes81// GET_CRC verify CRC of entire flashable area82// RESET finalise flash programming, reset chip and starts application83//8485#define BL_PROTOCOL_VERSION 5 // The revision of the bootloader protocol86// protocol bytes87#define PROTO_INSYNC 0x12 // 'in sync' byte sent before status88#define PROTO_EOC 0x20 // end of command8990// Reply bytes91#define PROTO_OK 0x10 // INSYNC/OK - 'ok' response92#define PROTO_FAILED 0x11 // INSYNC/FAILED - 'fail' response93#define PROTO_INVALID 0x13 // INSYNC/INVALID - 'invalid' response for bad commands94#define PROTO_BAD_SILICON_REV 0x14 // On the F4 series there is an issue with < Rev 3 silicon95// see https://pixhawk.org/help/errata96// Command bytes97#define PROTO_GET_SYNC 0x21 // NOP for re-establishing sync98#define PROTO_GET_DEVICE 0x22 // get device ID bytes99#define PROTO_CHIP_ERASE 0x23 // erase program area and reset program address100#define PROTO_PROG_MULTI 0x27 // write bytes at program address and increment101#define PROTO_READ_MULTI 0x28 // read bytes at address and increment102#define PROTO_GET_CRC 0x29 // compute & return a CRC103#define PROTO_GET_OTP 0x2a // read a byte from OTP at the given address104#define PROTO_GET_SN 0x2b // read a word from UDID area ( Serial) at the given address105#define PROTO_GET_CHIP 0x2c // read chip version (MCU IDCODE)106#define PROTO_SET_DELAY 0x2d // set minimum boot delay107#define PROTO_GET_CHIP_DES 0x2e // read chip version In ASCII108#define PROTO_BOOT 0x30 // boot the application109#define PROTO_DEBUG 0x31 // emit debug information - format not defined110#define PROTO_SET_BAUD 0x33 // baud rate on uart111112// External Flash programming113#define PROTO_EXTF_ERASE 0x34 // Erase sectors from external flash114#define PROTO_EXTF_PROG_MULTI 0x35 // write bytes at external flash program address and increment115#define PROTO_EXTF_READ_MULTI 0x36 // read bytes at address and increment116#define PROTO_EXTF_GET_CRC 0x37 // compute & return a CRC of data in external flash117118#define PROTO_CHIP_FULL_ERASE 0x40 // erase program area and reset program address, skip any flash wear optimization and force an erase119120#define PROTO_PROG_MULTI_MAX 64 // maximum PROG_MULTI size121#define PROTO_READ_MULTI_MAX 255 // size of the size field122123/* argument values for PROTO_GET_DEVICE */124#define PROTO_DEVICE_BL_REV 1 // bootloader revision125#define PROTO_DEVICE_BOARD_ID 2 // board ID126#define PROTO_DEVICE_BOARD_REV 3 // board revision127#define PROTO_DEVICE_FW_SIZE 4 // size of flashable area128#define PROTO_DEVICE_VEC_AREA 5 // contents of reserved vectors 7-10129#define PROTO_DEVICE_EXTF_SIZE 6 // size of available external flash130// all except PROTO_DEVICE_VEC_AREA and PROTO_DEVICE_BOARD_REV should be done131#define CHECK_GET_DEVICE_FINISHED(x) ((x & (0xB)) == 0xB)132133// interrupt vector table for STM32134#define SCB_VTOR 0xE000ED08135136static virtual_timer_t systick_vt;137138/*139millisecond timer array140*/141#define NTIMERS 2142#define TIMER_BL_WAIT 0143#define TIMER_LED 1144145static enum led_state led_state;146147volatile unsigned timer[NTIMERS];148149// keep back 32 bytes at the front of flash. This is long enough to allow for aligned150// access on STM32H7151#define RESERVE_LEAD_WORDS 8152153154#if EXT_FLASH_SIZE_MB155extern AP_FlashIface_JEDEC ext_flash;156#endif157158#ifndef BOOT_FROM_EXT_FLASH159#define BOOT_FROM_EXT_FLASH 0160#endif161162/*1631ms timer tick callback164*/165static void sys_tick_handler(virtual_timer_t* vt, void *ctx)166{167chSysLockFromISR();168chVTSetI(&systick_vt, chTimeMS2I(1), sys_tick_handler, nullptr);169chSysUnlockFromISR();170uint8_t i;171for (i = 0; i < NTIMERS; i++)172if (timer[i] > 0) {173timer[i]--;174}175176if ((led_state == LED_BLINK) && (timer[TIMER_LED] == 0)) {177led_toggle(LED_BOOTLOADER);178timer[TIMER_LED] = 50;179}180181if ((led_state == LED_BAD_FW) && (timer[TIMER_LED] == 0)) {182led_toggle(LED_BOOTLOADER);183timer[TIMER_LED] = 1000;184}185}186187static void delay(unsigned msec)188{189chThdSleep(chTimeMS2I(msec));190}191192void193led_set(enum led_state state)194{195led_state = state;196197switch (state) {198case LED_OFF:199led_off(LED_BOOTLOADER);200break;201202case LED_ON:203led_on(LED_BOOTLOADER);204break;205206case LED_BLINK:207/* restart the blink state machine ASAP */208timer[TIMER_LED] = 0;209break;210211case LED_BAD_FW:212timer[TIMER_LED] = 0;213break;214}215}216217static void218do_jump(uint32_t stacktop, uint32_t entrypoint)219{220#if defined(STM32F7) || defined(STM32H7)221// disable caches on F7 before starting program222__DSB();223__ISB();224SCB_DisableDCache();225SCB_DisableICache();226#endif227228chSysLock();229230// we set sp as well as msp to avoid an issue with loading NuttX231asm volatile(232"mov sp, %0 \n"233"msr msp, %0 \n"234"bx %1 \n"235: : "r"(stacktop), "r"(entrypoint) :);236}237238#ifndef APP_START_ADDRESS239#define APP_START_ADDRESS (FLASH_LOAD_ADDRESS + (FLASH_BOOTLOADER_LOAD_KB + APP_START_OFFSET_KB)*1024U)240#endif241242#if !defined(STM32_OTG2_IS_OTG1)243#define STM32_OTG2_IS_OTG1 0244#endif245246void247jump_to_app()248{249const uint32_t *app_base = (const uint32_t *)(APP_START_ADDRESS);250251#if AP_CHECK_FIRMWARE_ENABLED252const auto ok = check_good_firmware();253if (ok != check_fw_result_t::CHECK_FW_OK) {254// bad firmware, don't try and boot255led_set(LED_BAD_FW);256return;257}258#endif259260// If we have QSPI chip start it261#if EXT_FLASH_SIZE_MB262uint8_t* ext_flash_start_addr;263if (!ext_flash.start_xip_mode((void**)&ext_flash_start_addr)) {264return;265}266#endif267/*268* We hold back the programming of the lead words until the upload269* is marked complete by the host. So if they are not 0xffffffff,270* we should try booting it.271*/272for (uint8_t i=0; i<RESERVE_LEAD_WORDS; i++) {273if (app_base[i] == 0xffffffff) {274goto exit;275}276}277278/*279* The second word of the app is the entrypoint; it must point within the280* flash area (or we have a bad flash).281*/282if (app_base[1] < APP_START_ADDRESS) {283goto exit;284}285286#if BOOT_FROM_EXT_FLASH287if (app_base[1] >= (APP_START_ADDRESS + board_info.extf_size)) {288goto exit;289}290#else291if (app_base[1] >= (APP_START_ADDRESS + board_info.fw_size)) {292goto exit;293}294#endif295296#if HAL_USE_CAN == TRUE || HAL_NUM_CAN_IFACES297// for CAN firmware we start the watchdog before we run the298// application code, to ensure we catch a bad firmare. If we get a299// watchdog reset and the firmware hasn't changed the RTC flag to300// indicate that it has been running OK for 30s then we will stay301// in bootloader302#ifndef DISABLE_WATCHDOG303stm32_watchdog_init();304#endif305stm32_watchdog_pat();306#endif307308flash_set_keep_unlocked(false);309310led_set(LED_OFF);311312// resetting the clocks is needed for loading NuttX313#if defined(STM32H7)314rccDisableAPB1L(~0);315rccDisableAPB1H(~0);316#elif defined(STM32G4)317rccDisableAPB1R1(~0);318rccDisableAPB1R2(~0);319#elif defined(STM32L4)320rccDisableAPB1R1(~0);321rccDisableAPB1R2(~0);322#elif defined(STM32L4PLUS)323rccDisableAPB1R1(~0);324rccDisableAPB1R2(~0);325#else326rccDisableAPB1(~0);327#endif328rccDisableAPB2(~0);329#if HAL_USE_SERIAL_USB == TRUE330#if !STM32_OTG2_IS_OTG1331rccResetOTG_FS();332#endif333#if defined(rccResetOTG_HS)334rccResetOTG_HS();335#endif336#endif337338// disable all interrupt sources339port_disable();340341/* switch exception handlers to the application */342*(volatile uint32_t *)SCB_VTOR = APP_START_ADDRESS;343344/* extract the stack and entrypoint from the app vector table and go */345do_jump(app_base[0], app_base[1]);346exit:347#if EXT_FLASH_SIZE_MB348ext_flash.stop_xip_mode();349#endif350return;351}352353static void354sync_response(void)355{356uint8_t data[] = {357PROTO_INSYNC, // "in sync"358PROTO_OK // "OK"359};360361cout(data, sizeof(data));362}363364static void365invalid_response(void)366{367uint8_t data[] = {368PROTO_INSYNC, // "in sync"369PROTO_INVALID // "invalid command"370};371372cout(data, sizeof(data));373}374375static void376failure_response(void)377{378uint8_t data[] = {379PROTO_INSYNC, // "in sync"380PROTO_FAILED // "command failed"381};382383cout(data, sizeof(data));384}385386/**387* Function to wait for EOC388*389* @param timeout length of time in ms to wait for the EOC to be received390* @return true if the EOC is returned within the timeout perio, else false391*/392inline static bool393wait_for_eoc(unsigned timeout)394{395return cin(timeout) == PROTO_EOC;396}397398static void399cout_word(uint32_t val)400{401cout((uint8_t *)&val, 4);402}403404#define TEST_FLASH 0405406#if TEST_FLASH407static void test_flash()408{409uint32_t loop = 1;410bool init_done = false;411while (true) {412uint32_t addr = 0;413uint32_t page = 0;414while (true) {415uint32_t v[8];416for (uint8_t i=0; i<8; i++) {417v[i] = (page<<16) + loop;418}419if (flash_func_sector_size(page) == 0) {420continue;421}422uint32_t num_writes = flash_func_sector_size(page) / sizeof(v);423uprintf("page %u size %u addr=0x%08x v=0x%08x\n",424unsigned(page), unsigned(flash_func_sector_size(page)), unsigned(addr), unsigned(v[0])); delay(10);425if (init_done) {426for (uint32_t j=0; j<flash_func_sector_size(page)/4; j++) {427uint32_t v1 = (page<<16) + (loop-1);428uint32_t v2 = flash_func_read_word(addr+j*4);429if (v2 != v1) {430uprintf("read error at 0x%08x v=0x%08x v2=0x%08x\n", unsigned(addr+j*4), unsigned(v1), unsigned(v2));431break;432}433}434}435if (!flash_func_erase_sector(page)) {436uprintf("erase of %u failed\n", unsigned(page));437}438for (uint32_t j=0; j<num_writes; j++) {439if (!flash_func_write_words(addr+j*sizeof(v), v, ARRAY_SIZE(v))) {440uprintf("write failed at 0x%08x\n", unsigned(addr+j*sizeof(v)));441break;442}443}444addr += flash_func_sector_size(page);445page++;446if (flash_func_sector_size(page) == 0) {447break;448}449}450init_done = true;451delay(1000);452loop++;453}454}455#endif456457void458bootloader(unsigned timeout)459{460#if TEST_FLASH461test_flash();462#endif463464uint32_t address = board_info.fw_size; /* force erase before upload will work */465#if EXT_FLASH_SIZE_MB466uint32_t extf_address = board_info.extf_size; /* force erase before upload will work */467#endif468uint32_t read_address = 0;469uint32_t first_words[RESERVE_LEAD_WORDS];470bool done_sync = false;471uint8_t done_get_device_flags = 0;472bool done_erase = false;473static bool done_timer_init;474unsigned original_timeout = timeout;475476memset(first_words, 0xFF, sizeof(first_words));477478if (!done_timer_init) {479done_timer_init = true;480chVTObjectInit(&systick_vt);481chVTSet(&systick_vt, chTimeMS2I(1), sys_tick_handler, nullptr);482}483484/* if we are working with a timeout, start it running */485if (timeout) {486timer[TIMER_BL_WAIT] = timeout;487}488489/* make the LED blink while we are idle */490// ensure we don't override BAD FW LED491if (led_state != LED_BAD_FW) {492led_set(LED_BLINK);493}494495while (true) {496volatile int c;497int arg;498static union {499uint8_t c[256];500uint32_t w[64];501} flash_buffer;502503// Wait for a command byte504led_off(LED_ACTIVITY);505506do {507/* if we have a timeout and the timer has expired and serial forward is not busy, return now */508#if defined(BOOTLOADER_FORWARD_OTG2_SERIAL)509bool ser_forward_active = update_otg2_serial_forward();510#endif511if (timeout && !timer[TIMER_BL_WAIT]512#if defined(BOOTLOADER_FORWARD_OTG2_SERIAL)513// do serial forward only when idle514&& !ser_forward_active515#endif516) {517return;518}519520/* try to get a byte from the host */521c = cin(0);522#if HAL_USE_CAN == TRUE || HAL_NUM_CAN_IFACES523if (c < 0) {524can_update();525}526#endif527} while (c < 0);528529led_on(LED_ACTIVITY);530531// handle the command byte532switch (c) {533534// sync535//536// command: GET_SYNC/EOC537// reply: INSYNC/OK538//539case PROTO_GET_SYNC:540541/* expect EOC */542if (!wait_for_eoc(2)) {543goto cmd_bad;544}545done_sync = true;546break;547548// get device info549//550// command: GET_DEVICE/<arg:1>/EOC551// BL_REV reply: <revision:4>/INSYNC/EOC552// BOARD_ID reply: <board type:4>/INSYNC/EOC553// BOARD_REV reply: <board rev:4>/INSYNC/EOC554// FW_SIZE reply: <firmware size:4>/INSYNC/EOC555// VEC_AREA reply <vectors 7-10:16>/INSYNC/EOC556// bad arg reply: INSYNC/INVALID557//558case PROTO_GET_DEVICE:559/* expect arg then EOC */560arg = cin(1000);561562if (arg < 0) {563goto cmd_bad;564}565566if (!wait_for_eoc(2)) {567goto cmd_bad;568}569570// reset read pointer571read_address = 0;572573switch (arg) {574case PROTO_DEVICE_BL_REV: {575uint32_t bl_proto_rev = BL_PROTOCOL_VERSION;576cout((uint8_t *)&bl_proto_rev, sizeof(bl_proto_rev));577break;578}579580case PROTO_DEVICE_BOARD_ID:581cout((uint8_t *)&board_info.board_type, sizeof(board_info.board_type));582break;583584case PROTO_DEVICE_BOARD_REV:585cout((uint8_t *)&board_info.board_rev, sizeof(board_info.board_rev));586break;587588case PROTO_DEVICE_FW_SIZE:589cout((uint8_t *)&board_info.fw_size, sizeof(board_info.fw_size));590break;591592case PROTO_DEVICE_VEC_AREA:593for (unsigned p = 7; p <= 10; p++) {594uint32_t bytes = flash_func_read_word(p * 4);595596cout((uint8_t *)&bytes, sizeof(bytes));597}598599break;600601case PROTO_DEVICE_EXTF_SIZE:602cout((uint8_t *)&board_info.extf_size, sizeof(board_info.extf_size));603break;604605default:606goto cmd_bad;607}608done_get_device_flags |= (1<<(arg-1)); // set the flags for use when resetting timeout609break;610611// erase and prepare for programming612//613// command: ERASE/EOC614// success reply: INSYNC/OK615// erase failure: INSYNC/FAILURE616//617case PROTO_CHIP_ERASE:618#if defined(STM32F7) || defined(STM32H7)619case PROTO_CHIP_FULL_ERASE:620#endif621622if (!done_sync || !CHECK_GET_DEVICE_FINISHED(done_get_device_flags)) {623// lower chance of random data on a uart triggering erase624goto cmd_bad;625}626627/* expect EOC */628if (!wait_for_eoc(2)) {629goto cmd_bad;630}631632// once erase is done there is no going back, set timeout633// to zero634done_erase = true;635timeout = 0;636637flash_set_keep_unlocked(true);638639// clear the bootloader LED while erasing - it stops blinking at random640// and that's confusing641led_set(LED_OFF);642643// erase all sectors644for (uint16_t i = 0; flash_func_sector_size(i) != 0; i++) {645#if defined(STM32F7) || defined(STM32H7)646if (!flash_func_erase_sector(i, c == PROTO_CHIP_FULL_ERASE)) {647#else648if (!flash_func_erase_sector(i)) {649#endif650goto cmd_fail;651}652}653654// enable the LED while verifying the erase655led_set(LED_ON);656657// verify the erase658for (address = 0; address < board_info.fw_size; address += 4) {659if (flash_func_read_word(address) != 0xffffffff) {660goto cmd_fail;661}662}663664address = 0;665666// resume blinking667led_set(LED_BLINK);668break;669670// program data from start of the flash671//672// command: EXTF_ERASE/<len:4>/EOC673// success reply: INSYNC/OK674// invalid reply: INSYNC/INVALID675// readback failure: INSYNC/FAILURE676//677case PROTO_EXTF_ERASE:678#if EXT_FLASH_SIZE_MB679{680if (!done_sync || !CHECK_GET_DEVICE_FINISHED(done_get_device_flags)) {681// lower chance of random data on a uart triggering erase682goto cmd_bad;683}684uint32_t cmd_erase_bytes;685if (cin_word(&cmd_erase_bytes, 100)) {686goto cmd_bad;687}688689// expect EOC690if (!wait_for_eoc(2)) {691goto cmd_bad;692}693uint32_t erased_bytes = 0;694uint32_t sector_number = EXT_FLASH_RESERVE_START_KB * 1024 / ext_flash.get_sector_size();695uint8_t pct_done = 0;696if (cmd_erase_bytes > (ext_flash.get_sector_size() * ext_flash.get_sector_count())) {697uprintf("Requested to erase more than we can\n");698goto cmd_bad;699}700uprintf("Erase Command Received\n");701sync_response();702cout(&pct_done, sizeof(pct_done));703// Flash all sectors that encompass the erase_bytes704while (erased_bytes < cmd_erase_bytes) {705uint32_t delay_ms = 0, timeout_ms = 0;706if (!ext_flash.start_sector_erase(sector_number, delay_ms, timeout_ms)) {707goto cmd_fail;708}709uint32_t next_check_ms = AP_HAL::millis() + delay_ms;710while (true) {711cout(&pct_done, sizeof(pct_done));712if (AP_HAL::millis() > next_check_ms) {713if (!ext_flash.is_device_busy()) {714pct_done = erased_bytes*100/cmd_erase_bytes;715uprintf("PCT DONE: %d\n", pct_done);716break;717}718if ((AP_HAL::millis() + timeout_ms) > next_check_ms) {719// We are out of time, return error720goto cmd_fail;721}722next_check_ms = AP_HAL::millis()+delay_ms;723}724chThdSleep(chTimeMS2I(delay_ms));725}726erased_bytes += ext_flash.get_sector_size();727sector_number++;728}729pct_done = 100;730extf_address = 0;731cout(&pct_done, sizeof(pct_done));732}733#else734goto cmd_bad;735#endif // EXT_FLASH_SIZE_MB736break;737738// program bytes at current external flash address739//740// command: PROG_MULTI/<len:1>/<data:len>/EOC741// success reply: INSYNC/OK742// invalid reply: INSYNC/INVALID743// readback failure: INSYNC/FAILURE744//745case PROTO_EXTF_PROG_MULTI:746{747#if EXT_FLASH_SIZE_MB748if (!done_sync || !CHECK_GET_DEVICE_FINISHED(done_get_device_flags)) {749// lower chance of random data on a uart triggering erase750goto cmd_bad;751}752753// expect count754led_set(LED_OFF);755756arg = cin(50);757758if (arg < 0) {759goto cmd_bad;760}761762if ((extf_address + arg) > board_info.extf_size) {763goto cmd_bad;764}765766if (arg > sizeof(flash_buffer.c)) {767goto cmd_bad;768}769770for (int i = 0; i < arg; i++) {771c = cin(1000);772773if (c < 0) {774goto cmd_bad;775}776777flash_buffer.c[i] = c;778}779780if (!wait_for_eoc(200)) {781goto cmd_bad;782}783784uint32_t offset = 0;785uint32_t size = arg;786#if BOOT_FROM_EXT_FLASH787// save the first words and don't program it until everything else is done788if (extf_address < sizeof(first_words)) {789uint8_t n = MIN(sizeof(first_words)-extf_address, arg);790memcpy(&first_words[extf_address/4], &flash_buffer.w[0], n);791// replace first words with 1 bits we can overwrite later792memset(&flash_buffer.w[0], 0xFF, n);793}794#endif795uint32_t programming;796uint32_t delay_us = 0, timeout_us = 0;797uint64_t start_time_us;798while (true) {799if (size == 0) {800extf_address += arg;801break;802}803if (!ext_flash.start_program_offset(extf_address+offset+EXT_FLASH_RESERVE_START_KB*1024,804&flash_buffer.c[offset], size, programming, delay_us, timeout_us)) {805// uprintf("ext flash write command failed\n");806goto cmd_fail;807}808start_time_us = AP_HAL::micros64();809// prepare for next run810offset += programming;811size -= programming;812while (true) {813if (AP_HAL::micros64() > (start_time_us+delay_us)) {814if (!ext_flash.is_device_busy()) {815// uprintf("flash program Successful, elapsed %ld us\n", uint32_t(AP_HAL::micros64() - start_time_us));816break;817} else {818// uprintf("Typical flash program time reached, Still Busy?!\n");819}820}821}822}823#endif824break;825}826827// program bytes at current address828//829// command: PROG_MULTI/<len:1>/<data:len>/EOC830// success reply: INSYNC/OK831// invalid reply: INSYNC/INVALID832// readback failure: INSYNC/FAILURE833//834case PROTO_PROG_MULTI: // program bytes835if (!done_sync || !CHECK_GET_DEVICE_FINISHED(done_get_device_flags)) {836// lower chance of random data on a uart triggering erase837goto cmd_bad;838}839840// expect count841led_set(LED_OFF);842843arg = cin(50);844845if (arg < 0) {846goto cmd_bad;847}848849// sanity-check arguments850if (arg % 4) {851goto cmd_bad;852}853854if ((address + arg) > board_info.fw_size) {855goto cmd_bad;856}857858if (arg > sizeof(flash_buffer.c)) {859goto cmd_bad;860}861862for (int i = 0; i < arg; i++) {863c = cin(1000);864865if (c < 0) {866goto cmd_bad;867}868869flash_buffer.c[i] = c;870}871872if (!wait_for_eoc(200)) {873goto cmd_bad;874}875876// save the first words and don't program it until everything else is done877#if !BOOT_FROM_EXT_FLASH878if (address < sizeof(first_words)) {879uint8_t n = MIN(sizeof(first_words)-address, arg);880memcpy(&first_words[address/4], &flash_buffer.w[0], n);881// replace first words with 1 bits we can overwrite later882memset(&flash_buffer.w[0], 0xFF, n);883}884#endif885arg /= 4;886// program the words887if (!flash_write_buffer(address, flash_buffer.w, arg)) {888goto cmd_fail;889}890address += arg * 4;891break;892893// fetch CRC of the entire flash area894//895// command: GET_CRC/EOC896// reply: <crc:4>/INSYNC/OK897//898case PROTO_GET_CRC: {899// expect EOC900if (!wait_for_eoc(2)) {901goto cmd_bad;902}903904if (!flash_write_flush()) {905goto cmd_bad;906}907908// compute CRC of the programmed area909uint32_t sum = 0;910911for (unsigned p = 0; p < board_info.fw_size; p += 4) {912uint32_t bytes;913914#if !BOOT_FROM_EXT_FLASH915if (p < sizeof(first_words) && first_words[0] != 0xFFFFFFFF) {916bytes = first_words[p/4];917} else918#endif919{920bytes = flash_func_read_word(p);921}922sum = crc32_small(sum, (uint8_t *)&bytes, sizeof(bytes));923}924925cout_word(sum);926break;927}928929// fetch CRC of the external flash area930//931// command: EXTF_GET_CRC/<len:4>/EOC932// reply: <crc:4>/INSYNC/OK933//934case PROTO_EXTF_GET_CRC: {935#if EXT_FLASH_SIZE_MB936// expect EOC937uint32_t cmd_verify_bytes;938if (cin_word(&cmd_verify_bytes, 100)) {939goto cmd_bad;940}941942if (!wait_for_eoc(2)) {943goto cmd_bad;944}945946// compute CRC of the programmed area947uint32_t sum = 0;948uint8_t rembytes = cmd_verify_bytes % 4;949for (unsigned p = 0; p < (cmd_verify_bytes-rembytes); p+=4) {950uint32_t bytes;951952#if BOOT_FROM_EXT_FLASH953if (p < sizeof(first_words) && first_words[0] != 0xFFFFFFFF) {954bytes = first_words[p/4];955} else956#endif957{958ext_flash.read(p+EXT_FLASH_RESERVE_START_KB*1024, (uint8_t *)&bytes, sizeof(bytes));959}960sum = crc32_small(sum, (uint8_t *)&bytes, sizeof(bytes));961}962if (rembytes) {963uint8_t bytes[3];964ext_flash.read(EXT_FLASH_RESERVE_START_KB*1024+cmd_verify_bytes-rembytes, bytes, rembytes);965sum = crc32_small(sum, bytes, rembytes);966}967cout_word(sum);968break;969#endif970}971972// read a word from the OTP973//974// command: GET_OTP/<addr:4>/EOC975// reply: <value:4>/INSYNC/OK976case PROTO_GET_OTP:977// expect argument978{979uint32_t index = 0;980981if (cin_word(&index, 100)) {982goto cmd_bad;983}984985// expect EOC986if (!wait_for_eoc(2)) {987goto cmd_bad;988}989990cout_word(flash_func_read_otp(index));991}992break;993994// read the SN from the UDID995//996// command: GET_SN/<addr:4>/EOC997// reply: <value:4>/INSYNC/OK998case PROTO_GET_SN:999// expect argument1000{1001uint32_t index = 0;10021003if (cin_word(&index, 100)) {1004goto cmd_bad;1005}10061007// expect EOC1008if (!wait_for_eoc(2)) {1009goto cmd_bad;1010}10111012cout_word(flash_func_read_sn(index));1013}1014break;10151016// read the chip ID code1017//1018// command: GET_CHIP/EOC1019// reply: <value:4>/INSYNC/OK1020case PROTO_GET_CHIP: {1021// expect EOC1022if (!wait_for_eoc(2)) {1023goto cmd_bad;1024}10251026cout_word(get_mcu_id());1027}1028break;10291030// read the chip description1031//1032// command: GET_CHIP_DES/EOC1033// reply: <value:4>/INSYNC/OK1034case PROTO_GET_CHIP_DES: {1035uint8_t buffer[MAX_DES_LENGTH];1036unsigned len = MAX_DES_LENGTH;10371038// expect EOC1039if (!wait_for_eoc(2)) {1040goto cmd_bad;1041}10421043len = get_mcu_desc(len, buffer);1044cout_word(len);1045cout(buffer, len);1046}1047break;10481049#ifdef BOOT_DELAY_ADDRESS10501051case PROTO_SET_DELAY: {1052/*1053Allow for the bootloader to setup a1054boot delay signature which tells the1055board to delay for at least a1056specified number of seconds on boot.1057*/1058int v = cin(100);10591060if (v < 0) {1061goto cmd_bad;1062}10631064uint8_t boot_delay = v & 0xFF;10651066if (boot_delay > BOOT_DELAY_MAX) {1067goto cmd_bad;1068}10691070// expect EOC1071if (!wait_for_eoc(2)) {1072goto cmd_bad;1073}10741075uint32_t sig1 = flash_func_read_word(BOOT_DELAY_ADDRESS);1076uint32_t sig2 = flash_func_read_word(BOOT_DELAY_ADDRESS + 4);10771078if (sig1 != BOOT_DELAY_SIGNATURE1 ||1079sig2 != BOOT_DELAY_SIGNATURE2) {1080goto cmd_bad;1081}10821083uint32_t value = (BOOT_DELAY_SIGNATURE1 & 0xFFFFFF00) | boot_delay;1084flash_func_write_word(BOOT_DELAY_ADDRESS, value);10851086if (flash_func_read_word(BOOT_DELAY_ADDRESS) != value) {1087goto cmd_fail;1088}1089}1090break;1091#endif10921093case PROTO_READ_MULTI: {1094arg = cin(50);1095if (arg < 0) {1096goto cmd_bad;1097}1098if (arg % 4) {1099goto cmd_bad;1100}1101if ((read_address + arg) > board_info.fw_size) {1102goto cmd_bad;1103}1104// expect EOC1105if (!wait_for_eoc(2)) {1106goto cmd_bad;1107}1108arg /= 4;11091110while (arg-- > 0) {1111cout_word(flash_func_read_word(read_address));1112read_address += 4;1113}1114break;1115}11161117// finalise programming and boot the system1118//1119// command: BOOT/EOC1120// reply: INSYNC/OK1121//1122case PROTO_BOOT:11231124// expect EOC1125if (!wait_for_eoc(1000)) {1126goto cmd_bad;1127}11281129if (!flash_write_flush()) {1130goto cmd_fail;1131}11321133// program the deferred first word1134if (first_words[0] != 0xffffffff) {1135#if !BOOT_FROM_EXT_FLASH1136if (!flash_write_buffer(0, first_words, RESERVE_LEAD_WORDS)) {1137goto cmd_fail;1138}1139#else1140uint32_t programming;1141uint32_t delay_us;1142uint32_t timeout_us;1143if (!ext_flash.start_program_offset(EXT_FLASH_RESERVE_START_KB*1024, (const uint8_t*)first_words, sizeof(first_words), programming, delay_us, timeout_us)) {1144// uprintf("ext flash write command failed\n");1145goto cmd_fail;1146}1147uint64_t start_time_us = AP_HAL::micros64();1148while (true) {1149if (AP_HAL::micros64() > (start_time_us+delay_us)) {1150if (!ext_flash.is_device_busy()) {1151// uprintf("flash program Successful, elapsed %ld us\n", uint32_t(AP_HAL::micros64() - start_time_us));1152break;1153} else {1154// uprintf("Typical flash program time reached, Still Busy?!\n");1155}1156}1157}1158#endif1159// revert in case the flash was bad...1160memset(first_words, 0xff, sizeof(first_words));1161}11621163// send a sync and wait for it to be collected1164sync_response();1165delay(100);11661167// quiesce and jump to the app1168return;11691170case PROTO_DEBUG:1171// XXX reserved for ad-hoc debugging as required1172break;11731174case PROTO_SET_BAUD: {1175if (!done_sync || !CHECK_GET_DEVICE_FINISHED(done_get_device_flags)) {1176// prevent timeout going to zero on noise1177goto cmd_bad;1178}1179/* expect arg then EOC */1180uint32_t baud = 0;11811182if (cin_word(&baud, 100)) {1183goto cmd_bad;1184}11851186if (!wait_for_eoc(2)) {1187goto cmd_bad;1188}11891190// send the sync response for this command1191sync_response();11921193delay(5);11941195// set the baudrate1196port_setbaud(baud);11971198lock_bl_port();1199timeout = 0;12001201// this is different to what every other case in this1202// switch does! Most go through sync_response down the1203// bottom, but we need to undertake an action after1204// returning the response...1205continue;1206}12071208default:1209continue;1210}12111212// we got a good command on this port, lock to the port1213lock_bl_port();12141215// once we get both a valid sync and valid get_device then kill1216// the timeout1217if (done_sync && CHECK_GET_DEVICE_FINISHED(done_get_device_flags)) {1218timeout = 0;1219}12201221// send the sync response for this command1222sync_response();1223continue;1224cmd_bad:1225// if we get a bad command it could be line noise on a1226// uart. Set timeout back to original timeout so we don't get1227// stuck in the bootloader1228if (!done_erase) {1229timeout = original_timeout;1230}1231// send an 'invalid' response but don't kill the timeout - could be garbage1232invalid_response();1233continue;12341235cmd_fail:1236// send a 'command failed' response but don't kill the timeout - could be garbage1237failure_response();1238continue;1239}1240}124112421243