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/support.cpp
Views: 1798
/*1bootloader support functions2*/34#include <AP_HAL/AP_HAL.h>5#include "ch.h"6#include "hal.h"7#include "hwdef.h"8#include <AP_HAL_ChibiOS/hwdef/common/usbcfg.h>9#include <AP_HAL_ChibiOS/hwdef/common/flash.h>10#include <AP_HAL_ChibiOS/hwdef/common/stm32_util.h>11#include <AP_Math/AP_Math.h>12#include "support.h"13#include "mcu_f1.h"14#include "mcu_f3.h"15#include "mcu_f4.h"16#include "mcu_f7.h"17#include "mcu_h7.h"18#include "mcu_g4.h"19#include "mcu_l4.h"2021// optional uprintf() code for debug22// #define BOOTLOADER_DEBUG SD12324#ifndef AP_BOOTLOADER_ALWAYS_ERASE25#define AP_BOOTLOADER_ALWAYS_ERASE 026#endif2728#if defined(BOOTLOADER_DEV_LIST)29static BaseChannel *uarts[] = { BOOTLOADER_DEV_LIST };30#if HAL_USE_SERIAL == TRUE31static SerialConfig sercfg;32#endif33static int8_t locked_uart = -1;34static uint8_t last_uart;3536#ifndef BOOTLOADER_BAUDRATE37#define BOOTLOADER_BAUDRATE 11520038#endif3940// #pragma GCC optimize("O0")4142static bool cin_data(uint8_t *data, uint8_t len, unsigned timeout_ms)43{44for (uint8_t i=0; i<ARRAY_SIZE(uarts); i++) {45if (locked_uart == -1 || locked_uart == i) {46if (chnReadTimeout(uarts[i], data, len, chTimeMS2I(timeout_ms)) == len) {47last_uart = i;48return true;49}50}51}52chThdSleepMicroseconds(500);53return false;54}5556int16_t cin(unsigned timeout_ms)57{58uint8_t b = 0;59if (cin_data(&b, 1, timeout_ms)) {60return b;61}62return -1;63}6465int cin_word(uint32_t *wp, unsigned timeout_ms)66{67if (cin_data((uint8_t *)wp, 4, timeout_ms)) {68return 0;69}70return -1;71}727374void cout(uint8_t *data, uint32_t len)75{76chnWriteTimeout(uarts[last_uart], data, len, chTimeMS2I(100));77}78#endif // BOOTLOADER_DEV_LIST7980static uint32_t flash_base_page;81static uint16_t num_pages;82static const uint8_t *flash_base = (const uint8_t *)(0x08000000 + (FLASH_BOOTLOADER_LOAD_KB + APP_START_OFFSET_KB)*1024U);8384/*85initialise flash_base_page and num_pages86*/87void flash_init(void)88{89uint32_t reserved = 0;90num_pages = stm32_flash_getnumpages();91/*92advance flash_base_page to account for (FLASH_BOOTLOADER_LOAD_KB + APP_START_OFFSET_KB)93*/94while (reserved < (FLASH_BOOTLOADER_LOAD_KB + APP_START_OFFSET_KB) * 1024U &&95flash_base_page < num_pages) {96reserved += stm32_flash_getpagesize(flash_base_page);97flash_base_page++;98}99/*100reduce num_pages to account for FLASH_RESERVE_END_KB101*/102reserved = 0;103while (reserved < FLASH_RESERVE_END_KB * 1024U) {104reserved += stm32_flash_getpagesize(num_pages-1);105num_pages--;106}107}108109void flash_set_keep_unlocked(bool set)110{111stm32_flash_keep_unlocked(set);112}113114/*115read a word at offset relative to flash base116*/117118#pragma GCC diagnostic push119#pragma GCC diagnostic ignored "-Wcast-align"120121uint32_t flash_func_read_word(uint32_t offset)122{123return *(const uint32_t *)(flash_base + offset);124}125#pragma GCC diagnostic pop126127bool flash_func_write_word(uint32_t offset, uint32_t v)128{129return stm32_flash_write(uint32_t(flash_base+offset), &v, sizeof(v));130}131132bool flash_func_write_words(uint32_t offset, uint32_t *v, uint8_t n)133{134return stm32_flash_write(uint32_t(flash_base+offset), v, n*sizeof(*v));135}136137uint32_t flash_func_sector_size(uint32_t sector)138{139if (sector >= num_pages-flash_base_page) {140return 0;141}142return stm32_flash_getpagesize(flash_base_page+sector);143}144145bool flash_func_is_erased(uint32_t sector)146{147return stm32_flash_ispageerased(flash_base_page+sector);148}149150bool flash_func_erase_sector(uint32_t sector, bool force_erase)151{152#if AP_BOOTLOADER_ALWAYS_ERASE153return stm32_flash_erasepage(flash_base_page+sector);154#else155if (force_erase || !stm32_flash_ispageerased(flash_base_page+sector)) {156return stm32_flash_erasepage(flash_base_page+sector);157}158return true;159#endif160}161162// read one-time programmable memory163uint32_t flash_func_read_otp(uint32_t idx)164{165#ifndef OTP_SIZE166return 0;167#else168if (idx & 3) {169return 0;170}171172if (idx > OTP_SIZE) {173return 0;174}175176return *(uint32_t *)(idx + OTP_BASE);177#endif178}179180// read chip serial number181uint32_t flash_func_read_sn(uint32_t idx)182{183return *(uint32_t *)(UDID_START + idx);184}185186/*187we use a write buffer for flashing, both for efficiency and to188ensure that we only ever do 32 byte aligned writes on STM32H7. If189you attempt to do writes on a H7 of less than 32 bytes or not190aligned then the flash can end up in a CRC error state, which can191generate a hardware fault (a double ECC error) on flash read, even192after a power cycle193*/194static struct {195uint32_t buffer[8];196uint32_t address;197uint8_t n;198} fbuf;199200/*201flush the write buffer202*/203bool flash_write_flush(void)204{205if (fbuf.n == 0) {206return true;207}208fbuf.n = 0;209return flash_func_write_words(fbuf.address, fbuf.buffer, ARRAY_SIZE(fbuf.buffer));210}211212/*213write to flash with buffering to 32 bytes alignment214*/215bool flash_write_buffer(uint32_t address, const uint32_t *v, uint8_t nwords)216{217if (fbuf.n > 0 && address != fbuf.address + fbuf.n*4) {218if (!flash_write_flush()) {219return false;220}221}222while (nwords > 0) {223if (fbuf.n == 0) {224fbuf.address = address;225memset(fbuf.buffer, 0xff, sizeof(fbuf.buffer));226}227uint8_t n = MIN(ARRAY_SIZE(fbuf.buffer)-fbuf.n, nwords);228memcpy(&fbuf.buffer[fbuf.n], v, n*4);229address += n*4;230v += n;231nwords -= n;232fbuf.n += n;233if (fbuf.n == ARRAY_SIZE(fbuf.buffer)) {234if (!flash_write_flush()) {235return false;236}237}238}239return true;240}241242uint32_t get_mcu_id(void)243{244return *(uint32_t *)DBGMCU_BASE;245}246247#define REVID_MASK 0xFFFF0000248#define DEVID_MASK 0xFFF249250uint32_t get_mcu_desc(uint32_t max, uint8_t *revstr)251{252uint32_t idcode = (*(uint32_t *)DBGMCU_BASE);253int32_t mcuid = idcode & DEVID_MASK;254uint16_t revid = ((idcode & REVID_MASK) >> 16);255256uint8_t *endp = &revstr[max - 1];257uint8_t *strp = revstr;258259for (const auto &desc : mcu_descriptions) {260if (mcuid == desc.mcuid) {261// copy the string in:262const char *tmp = desc.desc;263while (strp < endp && *tmp) {264*strp++ = *tmp++;265}266break;267}268}269270// comma-separated:271if (strp < endp) {272*strp++ = ',';273}274275for (const auto &rev : silicon_revs) {276if (rev.revid == revid) {277if (strp < endp) {278*strp++ = rev.rev;279}280}281}282283return strp - revstr;284}285286void led_on(unsigned led)287{288#ifdef HAL_GPIO_PIN_LED_BOOTLOADER289if (led == LED_BOOTLOADER) {290palWriteLine(HAL_GPIO_PIN_LED_BOOTLOADER, HAL_LED_ON);291}292#endif293#ifdef HAL_GPIO_PIN_LED_ACTIVITY294if (led == LED_ACTIVITY) {295palWriteLine(HAL_GPIO_PIN_LED_ACTIVITY, HAL_LED_ON);296}297#endif298}299300void led_off(unsigned led)301{302#ifdef HAL_GPIO_PIN_LED_BOOTLOADER303if (led == LED_BOOTLOADER) {304palWriteLine(HAL_GPIO_PIN_LED_BOOTLOADER, !HAL_LED_ON);305}306#endif307#ifdef HAL_GPIO_PIN_LED_ACTIVITY308if (led == LED_ACTIVITY) {309palWriteLine(HAL_GPIO_PIN_LED_ACTIVITY, !HAL_LED_ON);310}311#endif312}313314void led_toggle(unsigned led)315{316#ifdef HAL_GPIO_PIN_LED_BOOTLOADER317if (led == LED_BOOTLOADER) {318palToggleLine(HAL_GPIO_PIN_LED_BOOTLOADER);319}320#endif321#ifdef HAL_GPIO_PIN_LED_ACTIVITY322if (led == LED_ACTIVITY) {323palToggleLine(HAL_GPIO_PIN_LED_ACTIVITY);324}325#endif326}327328extern "C" {329int vsnprintf(char *str, size_t size, const char *fmt, va_list ap);330}331332// printf to USB for debugging333void uprintf(const char *fmt, ...)334{335#ifdef BOOTLOADER_DEBUG336va_list ap;337static bool initialised;338static SerialConfig debug_sercfg;339char umsg[200];340if (!initialised) {341initialised = true;342debug_sercfg.speed = 57600;343sdStart(&BOOTLOADER_DEBUG, &debug_sercfg);344}345va_start(ap, fmt);346uint32_t n = vsnprintf(umsg, sizeof(umsg), fmt, ap);347va_end(ap);348if (n > sizeof(umsg)) {349n = sizeof(umsg);350}351chnWriteTimeout(&BOOTLOADER_DEBUG, (const uint8_t *)umsg, n, chTimeMS2I(100));352#endif353}354355void thread_sleep_ms(uint32_t ms)356{357while (ms > 0) {358// don't sleep more than 65 at a time, to cope with 16 bit359// timer360const uint32_t dt = ms > 65? 65: ms;361chThdSleepMilliseconds(dt);362ms -= dt;363}364}365366void thread_sleep_us(uint32_t us)367{368while (us > 0) {369// don't sleep more than 65 at a time, to cope with 16 bit370// timer371const uint32_t dt = us > 6500? 6500: us;372chThdSleepMicroseconds(dt);373us -= dt;374}375}376377// generate a pulse sequence forever, for debugging378void led_pulses(uint8_t npulses)379{380led_off(LED_BOOTLOADER);381while (true) {382for (uint8_t i=0; i<npulses; i++) {383led_on(LED_BOOTLOADER);384thread_sleep_ms(200);385led_off(LED_BOOTLOADER);386thread_sleep_ms(200);387}388thread_sleep_ms(2000);389}390}391392//simple variant of std c function to reduce used flash space393void *memcpy(void *dest, const void *src, size_t n)394{395uint8_t *tdest = (uint8_t *)dest;396uint8_t *tsrc = (uint8_t *)src;397for (int i=0; i<n; i++) {398tdest[i] = tsrc[i];399}400return dest;401}402403//simple variant of std c function to reduce used flash space404int strncmp(const char *s1, const char *s2, size_t n)405{406while ((*s1 != 0) && (*s1 == *s2) && n--) {407s1++;408s2++;409}410if (n == 0) {411return 0;412}413return (*s1 - *s2);414}415416//simple variant of std c function to reduce used flash space417int strcmp(const char *s1, const char *s2)418{419while ((*s1 != 0) && (*s1 == *s2)) {420s1++;421s2++;422}423return (*s1 - *s2);424}425426//simple variant of std c function to reduce used flash space427size_t strlen(const char *s1)428{429size_t ret = 0;430while (*s1++) ret++;431return ret;432}433434//simple variant of std c function to reduce used flash space435void *memset(void *s, int c, size_t n)436{437uint8_t *b = (uint8_t *)s;438while (n--) {439*b++ = c;440}441return s;442}443444#if defined(BOOTLOADER_DEV_LIST)445void lock_bl_port(void)446{447locked_uart = last_uart;448}449450/*451initialise serial ports452*/453void init_uarts(void)454{455#if HAL_USE_SERIAL_USB == TRUE456sduObjectInit(&SDU1);457sduStart(&SDU1, &serusbcfg1);458#if HAL_HAVE_DUAL_USB_CDC459sduObjectInit(&SDU2);460sduStart(&SDU2, &serusbcfg2);461#endif462463usbDisconnectBus(serusbcfg1.usbp);464thread_sleep_ms(1000);465usbStart(serusbcfg1.usbp, &usbcfg);466usbConnectBus(serusbcfg1.usbp);467#endif468469#if HAL_USE_SERIAL == TRUE470sercfg.speed = BOOTLOADER_BAUDRATE;471472for (const auto &uart : uarts) {473#if HAL_USE_SERIAL_USB == TRUE474if (uart == (BaseChannel *)&SDU1475#if HAL_HAVE_DUAL_USB_CDC476|| uart == (BaseChannel *)&SDU2477#endif478) {479continue;480}481#endif482sdStart((SerialDriver *)uart, &sercfg);483}484#endif485}486487488#if defined(BOOTLOADER_FORWARD_OTG2_SERIAL)489/* forward serial to OTG2490Used for devices containing multiple devices in one491*/492static SerialConfig forward_sercfg;493static uint32_t otg2_serial_deadline_ms;494bool update_otg2_serial_forward()495{496// get baudrate set on SDU2 and set it on HAL_FORWARD_OTG2_SERIAL if changed497if (forward_sercfg.speed != BOOTLOADER_FORWARD_OTG2_SERIAL_BAUDRATE) {498forward_sercfg.speed = BOOTLOADER_FORWARD_OTG2_SERIAL_BAUDRATE;499#if defined(BOOTLOADER_FORWARD_OTG2_SERIAL_SWAP) && BOOTLOADER_FORWARD_OTG2_SERIAL_SWAP500forward_sercfg.cr2 = USART_CR2_SWAP;501#endif502sdStart(&BOOTLOADER_FORWARD_OTG2_SERIAL, &forward_sercfg);503}504// check how many bytes are available to read from HAL_FORWARD_OTG2_SERIAL505uint8_t data[SERIAL_BUFFERS_SIZE]; // read upto SERIAL_BUFFERS_SIZE at a time506int n = chnReadTimeout(&SDU2, data, SERIAL_BUFFERS_SIZE, TIME_IMMEDIATE);507if (n > 0) {508// do a blocking write to HAL_FORWARD_OTG2_SERIAL509chnWriteTimeout(&BOOTLOADER_FORWARD_OTG2_SERIAL, data, n, TIME_IMMEDIATE);510otg2_serial_deadline_ms = AP_HAL::millis() + 1000;511}512513n = chnReadTimeout(&BOOTLOADER_FORWARD_OTG2_SERIAL, data, SERIAL_BUFFERS_SIZE, TIME_IMMEDIATE);514if (n > 0) {515// do a blocking write to SDU2516chnWriteTimeout(&SDU2, data, n, TIME_IMMEDIATE);517}518519return (AP_HAL::millis() < otg2_serial_deadline_ms);520}521#endif522523/*524set baudrate on the current port525*/526void port_setbaud(uint32_t baudrate)527{528#if HAL_USE_SERIAL_USB == TRUE529if (uarts[last_uart] == (BaseChannel *)&SDU1530#if HAL_HAVE_DUAL_USB_CDC531|| uarts[last_uart] == (BaseChannel *)&SDU2532#endif533) {534// can't set baudrate on USB535return;536}537#endif538#if HAL_USE_SERIAL == TRUE539memset(&sercfg, 0, sizeof(sercfg));540sercfg.speed = baudrate;541sdStart((SerialDriver *)uarts[last_uart], &sercfg);542#endif543}544#endif // BOOTLOADER_DEV_LIST545546#if defined(STM32H7) && CH_CFG_USE_HEAP547/*548check if flash has any ECC errors and if it does then erase all of549flash550*/551#define ECC_CHECK_CHUNK_SIZE (32*sizeof(uint32_t))552void check_ecc_errors(void)553{554__disable_fault_irq();555// stm32_flash_corrupt(0x8043200);556auto *dma = dmaStreamAlloc(STM32_DMA_STREAM_ID(1, 1), 0, nullptr, nullptr);557558uint32_t *buf = (uint32_t*)malloc_dma(ECC_CHECK_CHUNK_SIZE);559560if (buf == nullptr) {561// DMA'ble memory not available562return;563}564uint32_t ofs = 0;565while (ofs < BOARD_FLASH_SIZE*1024) {566if (FLASH->SR1 & (FLASH_SR_SNECCERR | FLASH_SR_DBECCERR)) {567break;568}569#if BOARD_FLASH_SIZE > 1024570if (FLASH->SR2 & (FLASH_SR_SNECCERR | FLASH_SR_DBECCERR)) {571break;572}573#endif574dmaStartMemCopy(dma,575STM32_DMA_CR_PL(0) | STM32_DMA_CR_PSIZE_BYTE |576STM32_DMA_CR_MSIZE_BYTE,577ofs+(uint8_t*)FLASH_BASE, buf, ECC_CHECK_CHUNK_SIZE);578dmaWaitCompletion(dma);579ofs += ECC_CHECK_CHUNK_SIZE;580}581dmaStreamFree(dma);582583if (ofs < BOARD_FLASH_SIZE*1024) {584// we must have ECC errors in flash585flash_set_keep_unlocked(true);586for (uint32_t i=0; i<num_pages; i++) {587stm32_flash_erasepage(flash_base_page+i);588}589flash_set_keep_unlocked(false);590}591__enable_fault_irq();592}593#endif // defined(STM32H7) && CH_CFG_USE_HEAP594595596597