mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-03-11 17:13:56 -03:00
AP_Bootloader: stay in CAN bootloader if in watchdog reset
if the app has not been running for at least 30s then stay in bootloader to allow used to load new fw
This commit is contained in:
parent
d1bc0f236d
commit
c1ef2e29d7
@ -31,6 +31,7 @@
|
||||
#include "support.h"
|
||||
#include "bl_protocol.h"
|
||||
#include "can.h"
|
||||
#include <stdio.h>
|
||||
|
||||
extern "C" {
|
||||
int main(void);
|
||||
@ -68,7 +69,8 @@ int main(void)
|
||||
|
||||
#ifndef NO_FASTBOOT
|
||||
enum rtc_boot_magic m = check_fast_reboot();
|
||||
if (stm32_was_watchdog_reset()) {
|
||||
bool was_watchdog = stm32_was_watchdog_reset();
|
||||
if (was_watchdog) {
|
||||
try_boot = true;
|
||||
timeout = 0;
|
||||
} else if (m == RTC_BOOT_HOLD) {
|
||||
@ -93,6 +95,14 @@ int main(void)
|
||||
try_boot = true;
|
||||
timeout = 1000;
|
||||
}
|
||||
if (was_watchdog && m != RTC_BOOT_FWOK) {
|
||||
// we've had a watchdog within 30s of booting main CAN
|
||||
// firmware. We will stay in bootloader to allow the user to
|
||||
// load a fixed firmware
|
||||
stm32_watchdog_clear_reason();
|
||||
try_boot = false;
|
||||
timeout = 0;
|
||||
}
|
||||
#endif
|
||||
|
||||
// if we fail to boot properly we want to pause in bootloader to give
|
||||
|
@ -4,6 +4,8 @@
|
||||
UAVCAN
|
||||
*/
|
||||
|
||||
#pragma once
|
||||
|
||||
#define APP_BOOTLOADER_COMMS_MAGIC 0xc544ad9a
|
||||
|
||||
struct app_bootloader_comms {
|
||||
@ -13,3 +15,30 @@ struct app_bootloader_comms {
|
||||
uint8_t my_node_id;
|
||||
uint8_t path[201];
|
||||
};
|
||||
|
||||
/*
|
||||
the app_descriptor stored in flash in the main firmware and is used
|
||||
by the bootloader to confirm that the firmware is not corrupt and is
|
||||
suitable for this board. The build dependent values in this structure
|
||||
are filled in by set_app_descriptor() in the waf build
|
||||
*/
|
||||
struct app_descriptor {
|
||||
uint8_t sig[8];
|
||||
// crc1 is the crc32 from firmware start to start of image_crc1
|
||||
uint32_t image_crc1;
|
||||
// crc2 is the crc32 from the start of version_major to the end of the firmware
|
||||
uint32_t image_crc2;
|
||||
// total size of firmware image in bytes
|
||||
uint32_t image_size;
|
||||
uint32_t git_hash;
|
||||
// software version number
|
||||
uint8_t version_major;
|
||||
uint8_t version_minor;
|
||||
// APJ_BOARD_ID (hardware version). This is also used in CAN NodeInfo
|
||||
// with high byte in HardwareVersion.major and low byte in HardwareVersion.minor
|
||||
uint16_t board_id;
|
||||
uint8_t reserved[8];
|
||||
};
|
||||
|
||||
#define APP_DESCRIPTOR_TOTAL_LENGTH 36
|
||||
static_assert(sizeof(app_descriptor) == APP_DESCRIPTOR_TOTAL_LENGTH, "app_descriptor incorrect length");
|
||||
|
@ -48,6 +48,7 @@
|
||||
#include "bl_protocol.h"
|
||||
#include "support.h"
|
||||
#include "can.h"
|
||||
#include <AP_HAL_ChibiOS/hwdef/common/watchdog.h>
|
||||
|
||||
// #pragma GCC optimize("O0")
|
||||
|
||||
@ -231,6 +232,15 @@ jump_to_app()
|
||||
return;
|
||||
}
|
||||
|
||||
#if HAL_USE_CAN == TRUE
|
||||
// for CAN firmware we start the watchdog before we run the
|
||||
// application code, to ensure we catch a bad firmare. If we get a
|
||||
// watchdog reset and the firmware hasn't changed the RTC flag to
|
||||
// indicate that it has been running OK for 30s then we will stay
|
||||
// in bootloader
|
||||
stm32_watchdog_init();
|
||||
#endif
|
||||
|
||||
flash_set_keep_unlocked(false);
|
||||
|
||||
led_set(LED_OFF);
|
||||
|
@ -561,29 +561,30 @@ bool can_check_firmware(void)
|
||||
const uint8_t sig[8] = { 0x40, 0xa2, 0xe4, 0xf1, 0x64, 0x68, 0x91, 0x06 };
|
||||
const uint8_t *flash = (const uint8_t *)(FLASH_LOAD_ADDRESS + FLASH_BOOTLOADER_LOAD_KB*1024);
|
||||
const uint32_t flash_size = (BOARD_FLASH_SIZE - FLASH_BOOTLOADER_LOAD_KB)*1024;
|
||||
const uint8_t desc_len = 16;
|
||||
const uint8_t *ptr = (const uint8_t *)memmem(flash, flash_size-(desc_len+sizeof(sig)), sig, sizeof(sig));
|
||||
if (ptr == nullptr) {
|
||||
const app_descriptor *ad = (const app_descriptor *)memmem(flash, flash_size-sizeof(app_descriptor), sig, sizeof(sig));
|
||||
if (ad == nullptr) {
|
||||
// no application signature
|
||||
printf("No app sig\n");
|
||||
return false;
|
||||
}
|
||||
ptr += sizeof(sig);
|
||||
uint32_t desc[4];
|
||||
memcpy(desc, ptr, sizeof(desc));
|
||||
|
||||
// check length
|
||||
if (desc[2] > flash_size) {
|
||||
printf("Bad fw length %u\n", desc[2]);
|
||||
if (ad->image_size > flash_size) {
|
||||
printf("Bad fw length %u\n", ad->image_size);
|
||||
return false;
|
||||
}
|
||||
|
||||
uint32_t len1 = ptr - flash;
|
||||
uint32_t len2 = desc[2] - (len1 + sizeof(desc));
|
||||
if (ad->board_id != APJ_BOARD_ID) {
|
||||
printf("Bad board_id %u should be %u\n", ad->board_id, APJ_BOARD_ID);
|
||||
return false;
|
||||
}
|
||||
|
||||
const uint8_t desc_len = offsetof(app_descriptor, version_major) - offsetof(app_descriptor, image_crc1);
|
||||
uint32_t len1 = ((const uint8_t *)&ad->image_crc1) - flash;
|
||||
uint32_t len2 = ad->image_size - (len1 + desc_len);
|
||||
uint32_t crc1 = crc_crc32(0, flash, len1);
|
||||
uint32_t crc2 = crc_crc32(0, ptr+sizeof(desc), len2);
|
||||
if (crc1 != desc[0] || crc2 != desc[1]) {
|
||||
printf("Bad app CRC 0x%08x:0x%08x 0x%08x:0x%08x\n", desc[0], desc[1], crc1, crc2);
|
||||
uint32_t crc2 = crc_crc32(0, (const uint8_t *)&ad->version_major, len2);
|
||||
if (crc1 != ad->image_crc1 || crc2 != ad->image_crc2) {
|
||||
printf("Bad app CRC 0x%08x:0x%08x 0x%08x:0x%08x\n", ad->image_crc1, ad->image_crc2, crc1, crc2);
|
||||
return false;
|
||||
}
|
||||
printf("Good firmware\n");
|
||||
|
Loading…
Reference in New Issue
Block a user