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/flash_from_sd.cpp
Views: 1798
#include "flash_from_sd.h"12#if AP_BOOTLOADER_FLASH_FROM_SD_ENABLED34#include "ch.h"5#include "ff.h"67#include "md5.h"89#include <string.h>10#include <stdint.h>11#include <stdio.h>12#include <fcntl.h>13#include "stm32_util.h"1415#include <AP_HAL_ChibiOS/hwdef/common/flash.h>16#include <AP_Math/AP_Math.h>17#include "support.h"1819// swiped from support.cpp:20static const uint8_t *flash_base = (const uint8_t *)(0x08000000 + (FLASH_BOOTLOADER_LOAD_KB + APP_START_OFFSET_KB)*1024U);212223// taken from AP_Common.cpp as we don't want to compile the AP_Common24// directory. This function is defined in AP_Common.h - so we can't25// use "static" here.26/**27* return the numeric value of an ascii hex character28*29* @param[in] a Hexadecimal character30* @return Returns a binary value31*/32uint8_t char_to_hex(char a)33{34if (a >= 'A' && a <= 'F')35return a - 'A' + 10;36else if (a >= 'a' && a <= 'f')37return a - 'a' + 10;38else39return a - '0';40}4142#define MAX_IO_SIZE 409643static uint8_t buffer[MAX_IO_SIZE];4445// a class which provides parsing functionality for abin files;46// inheritors must supply a function to deal with the body of the abin47// and may supply methods run() (to initialise their state) and48// name_value_callback (to handle name/value pairs extracted from the49// abin header.50class ABinParser {51public:52ABinParser(const char *_path) :53path{_path}54{ }55virtual ~ABinParser() {}5657virtual bool run() = 0;5859protected:6061virtual void name_value_callback(const char *name, const char *value) {}62virtual void body_callback(const uint8_t *bytes, uint32_t n) = 0;63bool parse();6465private:6667const char *path;6869};7071bool ABinParser::parse()72{73FIL fh;74if (f_open(&fh, path, FA_READ) != FR_OK) {75return false;76}77enum class State {78START_NAME=17, // "MD5: "79ACCUMULATING_NAME=19,80ACCUMULATING_VALUE = 30,81START_BODY = 40,82PROCESSING_BODY = 45,83SKIPPING_POST_COLON_SPACES = 50,84START_VALUE = 55,85};8687State state = State::START_NAME;88uint16_t name_start = 0;89uint16_t name_end = 0;90uint16_t value_start = 0;91// for efficiency we assume all headers are within the first chunk92// read i.e. the name/value pairs do not cross a MAX_IO_SIZE93// boundary94while (true) {95UINT bytes_read;96if (f_read(&fh, buffer, sizeof(buffer), &bytes_read) != FR_OK) {97return false;98}99if (bytes_read > sizeof(buffer)) {100// error101return false;102}103if (bytes_read == 0) {104break;105}106for (uint16_t i=0; i<bytes_read; i++) {107switch (state) {108case State::START_NAME: {109// check for delimiter:110if (bytes_read-i >= 3) {111if (!strncmp((char*)&buffer[i], "--\n", bytes_read-i)) {112// end of headers113i += 2;114state = State::START_BODY;115continue;116}117}118// sanity check input:119if (buffer[i] == ':') {120// zero-length name?! just say no:121return false;122}123if (buffer[i] == '\n') {124// empty line... ignore it125continue;126}127name_start = i;128state = State::ACCUMULATING_NAME;129continue;130}131case State::ACCUMULATING_NAME: {132if (buffer[i] == '\n') {133// no colon on this line; just say no:134return false;135}136if (buffer[i] == ':') {137name_end = i;138state = State::SKIPPING_POST_COLON_SPACES;139continue;140}141// continue to accumulate name142continue;143}144case State::SKIPPING_POST_COLON_SPACES:145if (buffer[i] == ' ') {146// continue to accumulate spaces147continue;148}149state = State::START_VALUE;150FALLTHROUGH;151case State::START_VALUE:152value_start = i;153state = State::ACCUMULATING_VALUE;154FALLTHROUGH;155case State::ACCUMULATING_VALUE: {156if (buffer[i] != '\n') {157// continue to accumate value bytes158continue;159}160char name[80];161char value[80];162strncpy(name, (char*)&buffer[name_start], MIN(sizeof(name)-1, name_end-name_start));163strncpy(value, (char*)&buffer[value_start], MIN(sizeof(value)-1, i-value_start));164name_value_callback(name, value);165state = State::START_NAME;166continue;167}168case State::START_BODY:169state = State::PROCESSING_BODY;170FALLTHROUGH;171case State::PROCESSING_BODY:172body_callback(&buffer[i], bytes_read-i);173i = bytes_read;174continue;175}176}177}178179// successfully parsed the abin. Call the body callback once more180// with zero bytes indicating EOF:181body_callback((uint8_t*)"", 0);182183return true;184}185186// a sub-class of ABinParser which takes the supplied MD5 from the187// abin header and compares it against the calculated md5sum of the188// abin body189class ABinVerifier : ABinParser {190public:191192using ABinParser::ABinParser;193194bool run() override {195MD5Init(&md5_context);196197if (!parse()) {198return false;199}200201// verify the checksum is as expected202uint8_t calculated_md5[16];203MD5Final(calculated_md5, &md5_context);204if (!memcmp(calculated_md5, expected_md5, sizeof(calculated_md5))) {205// checksums match206return true;207}208209return false;210}211212protected:213214void name_value_callback(const char *name, const char *value) override {215if (strncmp(name, "MD5", 3)) {216// only interested in MD5 header217return;218}219220// convert from 32-byte-string to 16-byte number:221for (uint8_t j=0; j<16; j++) {222expected_md5[j] = (char_to_hex(value[j*2]) << 4) | char_to_hex(value[j*2+1]);223}224}225226void body_callback(const uint8_t *bytes, uint32_t nbytes) override {227MD5Update(&md5_context, bytes, nbytes);228}229230private:231232uint8_t expected_md5[16];233MD5Context md5_context;234};235236237// a sub-class of ABinParser which flashes the body of the supplied abin238class ABinFlasher : public ABinParser {239public:240using ABinParser::ABinParser;241242bool run() override {243// start by erasing all sectors244for (uint8_t i = 0; flash_func_sector_size(i) != 0; i++) {245if (!flash_func_erase_sector(i)) {246return false;247}248led_toggle(LED_BOOTLOADER);249}250251// parse and flash252if (!parse()) {253return false;254}255256return !failed;257}258259protected:260261void body_callback(const uint8_t *bytes, uint32_t nbytes) override {262if (failed) {263return;264}265266memcpy(&buffer[buffer_ofs], bytes, nbytes);267buffer_ofs += nbytes;268269const uint32_t WRITE_CHUNK_SIZE = 32*1024; // must be less than size of state buffer270// nbytes is zero after the last chunk in the body271if (buffer_ofs > WRITE_CHUNK_SIZE || nbytes == 0) {272uint32_t write_size = WRITE_CHUNK_SIZE;273uint32_t padded_write_size = write_size;274if (nbytes == 0) {275// final chunk. We have to align to 128 bytes276write_size = buffer_ofs;277padded_write_size = write_size;278const uint8_t pad_size = 128 - (write_size % 128);279// zero those extra bytes:280memset(&buffer[buffer_ofs], '\0', pad_size);281padded_write_size += pad_size;282}283const uint32_t ofs = uint32_t(flash_base) + flash_ofs;284if (!stm32_flash_write(ofs, buffer, padded_write_size)) {285failed = true;286return;287}288flash_ofs += padded_write_size;289buffer_ofs -= write_size;290memcpy(buffer, &buffer[write_size], buffer_ofs);291led_toggle(LED_BOOTLOADER);292}293}294295private:296297uint32_t flash_ofs = 0;298uint32_t buffer_ofs = 0;299uint8_t buffer[64*1024]; // constrained by memory map on bootloader300bool failed = false;301};302303304// main entry point to the flash-from-sd-card functionality; called305// from the bootloader main function306bool flash_from_sd()307{308peripheral_power_enable();309310if (!sdcard_init()) {311return false;312}313314bool ret = false;315316// expected filepath for abin:317const char *abin_path = "/ardupilot.abin";318// we rename to this before verifying the abin:319const char *verify_abin_path = "/ardupilot-verify.abin";320// we rename to this before flashing the abin:321const char *flash_abin_path = "/ardupilot-flash.abin";322// we rename to this after flashing the abin:323const char *flashed_abin_path = "/ardupilot-flashed.abin";324325ABinVerifier *verifier = nullptr;326ABinFlasher *flasher = nullptr;327328FILINFO info;329if (f_stat(abin_path, &info) != FR_OK) {330goto out;331}332333f_unlink(verify_abin_path);334f_unlink(flash_abin_path);335f_unlink(flashed_abin_path);336337// rename the file so we only ever attempt to flash from it once:338if (f_rename(abin_path, verify_abin_path) != FR_OK) {339// we would be nice to indicate an error here.340// we could try to drop a message on the SD card?341return false;342}343344verifier = NEW_NOTHROW ABinVerifier{verify_abin_path};345if (!verifier->run()) {346goto out;347}348349// rename the file so we only ever attempt to flash from it once:350if (f_rename(verify_abin_path, flash_abin_path) != FR_OK) {351// we would be nice to indicate an error here.352// we could try to drop a message on the SD card?353return false;354}355356flasher = NEW_NOTHROW ABinFlasher{flash_abin_path};357if (!flasher->run()) {358goto out;359}360361// rename the file to indicate successful flash:362if (f_rename(flash_abin_path, flashed_abin_path) != FR_OK) {363// we would be nice to indicate an error here.364// we could try to drop a message on the SD card?365return false;366}367368ret = true;369370out:371372delete verifier;373verifier = nullptr;374375delete flasher;376flasher = nullptr;377378sdcard_stop();379// should we disable peripheral power again?!380381return ret;382}383384#endif // AP_BOOTLOADER_FLASH_FROM_SD_ENABLED385386387