Path: blob/master/Tools/AP_Bootloader/AP_Bootloader.cpp
9361 views
/*1This program is free software: you can redistribute it and/or modify2it under the terms of the GNU General Public License as published by3the Free Software Foundation, either version 3 of the License, or4(at your option) any later version.56This program is distributed in the hope that it will be useful,7but WITHOUT ANY WARRANTY; without even the implied warranty of8MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the9GNU General Public License for more details.1011You should have received a copy of the GNU General Public License12along with this program. If not, see <http://www.gnu.org/licenses/>.13*/14/*15ArduPilot bootloader. This implements the same protocol originally16developed for PX4, but builds on top of the ChibiOS HAL1718It does not use the full AP_HAL API in order to keep the firmware19size below the maximum of 16kByte required for F4 based20boards. Instead it uses the ChibiOS APIs directly21*/2223#include <AP_HAL/AP_HAL.h>24#include "ch.h"25#include "hal.h"26#include "hwdef.h"27#include <AP_HAL_ChibiOS/hwdef/common/usbcfg.h>28#include <AP_HAL_ChibiOS/hwdef/common/stm32_util.h>29#include <AP_HAL_ChibiOS/hwdef/common/watchdog.h>30#include "support.h"31#include "bl_protocol.h"32#include "flash_from_sd.h"33#include "can.h"34#include <stdio.h>35#if EXT_FLASH_SIZE_MB36#include <AP_FlashIface/AP_FlashIface_JEDEC.h>37#endif38#include <AP_CheckFirmware/AP_CheckFirmware.h>39#include "network.h"4041extern "C" {42int main(void);43}4445struct boardinfo board_info = {46.board_type = APJ_BOARD_ID,47.board_rev = 0,48.fw_size = (BOARD_FLASH_SIZE - (FLASH_BOOTLOADER_LOAD_KB + FLASH_RESERVE_END_KB + APP_START_OFFSET_KB))*1024,49.extf_size = (EXT_FLASH_SIZE_MB * 1024 * 1024) - (EXT_FLASH_RESERVE_START_KB + EXT_FLASH_RESERVE_END_KB) * 102450};5152#ifndef HAL_BOOTLOADER_TIMEOUT53#define HAL_BOOTLOADER_TIMEOUT 500054#endif5556#ifndef HAL_STAY_IN_BOOTLOADER_VALUE57#define HAL_STAY_IN_BOOTLOADER_VALUE 058#endif5960#if EXT_FLASH_SIZE_MB61AP_FlashIface_JEDEC ext_flash;62#endif6364#if AP_BOOTLOADER_NETWORK_ENABLED65static BL_Network network;66#endif6768int main(void)69{70#ifdef AP_BOOTLOADER_CUSTOM_HERE471custom_startup();72#endif7374flash_init();7576#if AP_FLASH_ECC_CHECK_ENABLED77check_ecc_errors();78#endif7980#ifdef STM32F427xx81if (BOARD_FLASH_SIZE > 1024 && check_limit_flash_1M()) {82board_info.fw_size = (1024 - (FLASH_BOOTLOADER_LOAD_KB + APP_START_OFFSET_KB))*1024;83}84#endif8586bool try_boot = false;87uint32_t timeout = HAL_BOOTLOADER_TIMEOUT;8889#ifdef HAL_BOARD_AP_PERIPH_ZUBAXGNSS90// setup remapping register for ZubaxGNSS91uint32_t mapr = AFIO->MAPR;92mapr &= ~AFIO_MAPR_SWJ_CFG;93mapr |= AFIO_MAPR_SWJ_CFG_JTAGDISABLE;94AFIO->MAPR = mapr | AFIO_MAPR_CAN_REMAP_REMAP2 | AFIO_MAPR_SPI3_REMAP;95#endif9697#if HAL_FLASH_PROTECTION98stm32_flash_unprotect_flash();99#endif100101#if AP_BOOTLOADER_NETWORK_ENABLED102network.save_comms_ip();103#endif104105#if AP_FASTBOOT_ENABLED106enum rtc_boot_magic m = check_fast_reboot();107bool was_watchdog = stm32_was_watchdog_reset();108if (was_watchdog) {109try_boot = true;110timeout = 0;111} else if (m == RTC_BOOT_HOLD) {112timeout = 0;113} else if (m == RTC_BOOT_FAST) {114try_boot = true;115timeout = 0;116}117#if HAL_USE_CAN == TRUE || HAL_NUM_CAN_IFACES118else if ((m & 0xFFFFFF00) == RTC_BOOT_CANBL) {119try_boot = false;120timeout = 10000;121can_set_node_id(m & 0xFF);122}123if (can_check_update()) {124// trying to update firmware, stay in bootloader125try_boot = false;126timeout = 0;127}128#if AP_CHECK_FIRMWARE_ENABLED129const auto ok = check_good_firmware();130if (ok != check_fw_result_t::CHECK_FW_OK) {131// bad firmware CRC, don't try and boot132timeout = 0;133try_boot = false;134led_set(LED_BAD_FW);135}136#ifndef BOOTLOADER_DEV_LIST137else if (timeout == HAL_BOOTLOADER_TIMEOUT) {138// fast boot for good firmware if we haven't been told to stay139// in bootloader140try_boot = true;141timeout = 1000;142}143#endif // ifndef(BOOTLOADER_DEV_LIST)144#if AP_BOOTLOADER_NETWORK_ENABLED145if (ok == check_fw_result_t::CHECK_FW_OK) {146const auto *app_descriptor = get_app_descriptor();147if (app_descriptor != nullptr) {148network.status_printf("Firmware OK: %ld.%ld.%lx\n", app_descriptor->version_major,149app_descriptor->version_minor,150app_descriptor->git_hash);151}152} else {153network.status_printf("Firmware Error: %d\n", (int)ok);154}155#endif156#endif // AP_CHECK_FIRMWARE_ENABLED157158if (was_watchdog && m != RTC_BOOT_FWOK) {159// we've had a watchdog within 30s of booting main CAN160// firmware. We will stay in bootloader to allow the user to161// load a fixed firmware162stm32_watchdog_clear_reason();163try_boot = false;164timeout = 0;165}166#elif AP_CHECK_FIRMWARE_ENABLED167const auto ok = check_good_firmware();168if (ok != check_fw_result_t::CHECK_FW_OK) {169// bad firmware, don't try and boot170timeout = 0;171try_boot = false;172led_set(LED_BAD_FW);173}174#endif175176#if defined(HAL_GPIO_PIN_VBUS) && defined(HAL_ENABLE_VBUS_CHECK)177#if HAL_USE_SERIAL_USB == TRUE178else if (palReadLine(HAL_GPIO_PIN_VBUS) == 0) {179try_boot = true;180timeout = 0;181}182#endif183#endif184185// if we fail to boot properly we want to pause in bootloader to give186// a chance to load new app code187set_fast_reboot(RTC_BOOT_OFF);188#endif // AP_FASTBOOT_ENABLED189190#ifdef HAL_GPIO_PIN_STAY_IN_BOOTLOADER191// optional "stay in bootloader" pin192if (palReadLine(HAL_GPIO_PIN_STAY_IN_BOOTLOADER) == HAL_STAY_IN_BOOTLOADER_VALUE) {193try_boot = false;194timeout = 0;195}196#endif197198#if EXT_FLASH_SIZE_MB199while (!ext_flash.init()) {200// keep trying until we get it working201// there's no future without it202chThdSleep(chTimeMS2I(20));203}204#endif205206if (try_boot) {207jump_to_app();208}209210#if defined(BOOTLOADER_DEV_LIST)211init_uarts();212#endif213#if HAL_USE_CAN == TRUE || HAL_NUM_CAN_IFACES214can_start();215#endif216217#if AP_BOOTLOADER_NETWORK_ENABLED218network.init();219#endif220221#if AP_BOOTLOADER_FLASH_FROM_SD_ENABLED222if (flash_from_sd()) {223jump_to_app();224}225#endif226227#if defined(BOOTLOADER_DEV_LIST)228while (true) {229bootloader(timeout);230jump_to_app();231}232#else233// CAN and network only234while (true) {235uint32_t t0 = AP_HAL::millis();236while (timeout == 0 || AP_HAL::millis() - t0 <= timeout) {237can_update();238chThdSleep(chTimeMS2I(1));239}240jump_to_app();241}242#endif243}244245246247248