mirror of https://github.com/ArduPilot/ardupilot
AP_Bootloader: use AP_CheckFirmware
This commit is contained in:
parent
635acc370f
commit
3313ca103c
|
@ -35,6 +35,7 @@
|
|||
#if EXT_FLASH_SIZE_MB
|
||||
#include <AP_FlashIface/AP_FlashIface_JEDEC.h>
|
||||
#endif
|
||||
#include <AP_CheckFirmware/AP_CheckFirmware.h>
|
||||
|
||||
extern "C" {
|
||||
int main(void);
|
||||
|
@ -103,7 +104,8 @@ int main(void)
|
|||
try_boot = false;
|
||||
timeout = 0;
|
||||
}
|
||||
if (!can_check_firmware()) {
|
||||
const auto ok = check_good_firmware();
|
||||
if (ok != check_fw_result_t::CHECK_FW_OK) {
|
||||
// bad firmware CRC, don't try and boot
|
||||
timeout = 0;
|
||||
try_boot = false;
|
||||
|
@ -123,7 +125,15 @@ int main(void)
|
|||
try_boot = false;
|
||||
timeout = 0;
|
||||
}
|
||||
#elif AP_CHECK_FIRMWARE_ENABLED
|
||||
const auto ok = check_good_firmware();
|
||||
if (ok != check_fw_result_t::CHECK_FW_OK) {
|
||||
// bad firmware, don't try and boot
|
||||
timeout = 0;
|
||||
try_boot = false;
|
||||
}
|
||||
#endif
|
||||
|
||||
#if defined(HAL_GPIO_PIN_VBUS) && defined(HAL_ENABLE_VBUS_CHECK)
|
||||
#if HAL_USE_SERIAL_USB == TRUE
|
||||
else if (palReadLine(HAL_GPIO_PIN_VBUS) == 0) {
|
||||
|
|
|
@ -15,35 +15,3 @@ struct app_bootloader_comms {
|
|||
uint8_t my_node_id;
|
||||
uint8_t path[201];
|
||||
};
|
||||
|
||||
#ifndef FW_MAJOR
|
||||
#define FW_MAJOR 0
|
||||
#define FW_MINOR 0
|
||||
#endif
|
||||
|
||||
/*
|
||||
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] = { 0x40, 0xa2, 0xe4, 0xf1, 0x64, 0x68, 0x91, 0x06 };
|
||||
// crc1 is the crc32 from firmware start to start of image_crc1
|
||||
uint32_t image_crc1 = 0;
|
||||
// crc2 is the crc32 from the start of version_major to the end of the firmware
|
||||
uint32_t image_crc2 = 0;
|
||||
// total size of firmware image in bytes
|
||||
uint32_t image_size = 0;
|
||||
uint32_t git_hash = 0;
|
||||
// software version number
|
||||
uint8_t version_major = FW_MAJOR;
|
||||
uint8_t version_minor = FW_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 = APJ_BOARD_ID;
|
||||
uint8_t reserved[8] = { 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff };
|
||||
};
|
||||
|
||||
#define APP_DESCRIPTOR_TOTAL_LENGTH 36
|
||||
static_assert(sizeof(app_descriptor) == APP_DESCRIPTOR_TOTAL_LENGTH, "app_descriptor incorrect length");
|
||||
|
|
|
@ -53,6 +53,8 @@
|
|||
#if EXT_FLASH_SIZE_MB
|
||||
#include <AP_FlashIface/AP_FlashIface_JEDEC.h>
|
||||
#endif
|
||||
#include <AP_CheckFirmware/AP_CheckFirmware.h>
|
||||
|
||||
// #pragma GCC optimize("O0")
|
||||
|
||||
|
||||
|
@ -232,6 +234,14 @@ jump_to_app()
|
|||
{
|
||||
const uint32_t *app_base = (const uint32_t *)(APP_START_ADDRESS);
|
||||
|
||||
#if AP_CHECK_FIRMWARE_ENABLED
|
||||
const auto ok = check_good_firmware();
|
||||
if (ok != check_fw_result_t::CHECK_FW_OK) {
|
||||
// bad firmware, don't try and boot
|
||||
return;
|
||||
}
|
||||
#endif
|
||||
|
||||
// If we have QSPI chip start it
|
||||
#if EXT_FLASH_SIZE_MB
|
||||
uint8_t* ext_flash_start_addr;
|
||||
|
|
|
@ -38,7 +38,7 @@
|
|||
#include <AP_HAL_ChibiOS/hwdef/common/watchdog.h>
|
||||
#include <stdio.h>
|
||||
#include <AP_HAL_ChibiOS/CANIface.h>
|
||||
|
||||
#include <AP_CheckFirmware/AP_CheckFirmware.h>
|
||||
|
||||
static CanardInstance canard;
|
||||
static uint32_t canard_memory_pool[4096/4];
|
||||
|
@ -84,16 +84,6 @@ static struct {
|
|||
uint32_t sector_ofs;
|
||||
} fw_update;
|
||||
|
||||
enum {
|
||||
FAIL_REASON_NO_APP_SIG = 10,
|
||||
FAIL_REASON_BAD_LENGTH_APP = 11,
|
||||
FAIL_REASON_BAD_BOARD_ID = 12,
|
||||
FAIL_REASON_BAD_CRC = 13,
|
||||
FAIL_REASON_IN_UPDATE = 14,
|
||||
FAIL_REASON_WATCHDOG = 15,
|
||||
FAIL_REASON_BAD_LENGTH_DESCRIPTOR = 16,
|
||||
};
|
||||
|
||||
/*
|
||||
get cpu unique ID
|
||||
*/
|
||||
|
@ -238,7 +228,9 @@ static void handle_file_read_response(CanardInstance* ins, CanardRxTransfer* tra
|
|||
if (len < UAVCAN_PROTOCOL_FILE_READ_RESPONSE_DATA_MAX_LENGTH) {
|
||||
fw_update.node_id = 0;
|
||||
flash_write_flush();
|
||||
if (can_check_firmware()) {
|
||||
const auto ok = check_good_firmware();
|
||||
node_status.vendor_specific_status_code = uint8_t(ok);
|
||||
if (ok == check_fw_result_t::CHECK_FW_OK) {
|
||||
jump_to_app();
|
||||
}
|
||||
}
|
||||
|
@ -624,64 +616,6 @@ void can_set_node_id(uint8_t node_id)
|
|||
initial_node_id = node_id;
|
||||
}
|
||||
|
||||
/*
|
||||
check firmware CRC to see if it matches
|
||||
*/
|
||||
bool can_check_firmware(void)
|
||||
{
|
||||
if (fw_update.node_id != 0) {
|
||||
// we're doing an update, don't boot this fw
|
||||
node_status.vendor_specific_status_code = FAIL_REASON_IN_UPDATE;
|
||||
return false;
|
||||
}
|
||||
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 + APP_START_OFFSET_KB)*1024);
|
||||
const uint32_t flash_size = (BOARD_FLASH_SIZE - (FLASH_BOOTLOADER_LOAD_KB + APP_START_OFFSET_KB))*1024;
|
||||
const app_descriptor *ad = (const app_descriptor *)memmem(flash, flash_size-sizeof(app_descriptor), sig, sizeof(sig));
|
||||
if (ad == nullptr) {
|
||||
// no application signature
|
||||
node_status.vendor_specific_status_code = FAIL_REASON_NO_APP_SIG;
|
||||
printf("No app sig\n");
|
||||
return false;
|
||||
}
|
||||
// check length
|
||||
if (ad->image_size > flash_size) {
|
||||
node_status.vendor_specific_status_code = FAIL_REASON_BAD_LENGTH_APP;
|
||||
printf("Bad fw length %u\n", ad->image_size);
|
||||
return false;
|
||||
}
|
||||
|
||||
bool id_ok = (ad->board_id == APJ_BOARD_ID);
|
||||
#ifdef ALT_BOARD_ID
|
||||
id_ok |= (ad->board_id == ALT_BOARD_ID);
|
||||
#endif
|
||||
|
||||
if (!id_ok) {
|
||||
node_status.vendor_specific_status_code = FAIL_REASON_BAD_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;
|
||||
if ((len1 + desc_len) > ad->image_size) {
|
||||
node_status.vendor_specific_status_code = FAIL_REASON_BAD_LENGTH_DESCRIPTOR;
|
||||
printf("Bad fw descriptor length %u\n", ad->image_size);
|
||||
return false;
|
||||
}
|
||||
|
||||
uint32_t len2 = ad->image_size - (len1 + desc_len);
|
||||
uint32_t crc1 = crc32_small(0, flash, len1);
|
||||
uint32_t crc2 = crc32_small(0, (const uint8_t *)&ad->version_major, len2);
|
||||
if (crc1 != ad->image_crc1 || crc2 != ad->image_crc2) {
|
||||
node_status.vendor_specific_status_code = FAIL_REASON_BAD_CRC;
|
||||
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");
|
||||
return true;
|
||||
}
|
||||
|
||||
// check for a firmware update marker left by app
|
||||
bool can_check_update(void)
|
||||
{
|
||||
|
@ -742,6 +676,7 @@ bool can_check_update(void)
|
|||
|
||||
void can_start()
|
||||
{
|
||||
node_status.vendor_specific_status_code = uint8_t(check_good_firmware());
|
||||
node_status.mode = UAVCAN_PROTOCOL_NODESTATUS_MODE_MAINTENANCE;
|
||||
|
||||
#if HAL_USE_CAN
|
||||
|
@ -770,7 +705,7 @@ void can_start()
|
|||
get_random_range(UAVCAN_PROTOCOL_DYNAMIC_NODE_ID_ALLOCATION_MAX_FOLLOWUP_DELAY_MS);
|
||||
|
||||
if (stm32_was_watchdog_reset()) {
|
||||
node_status.vendor_specific_status_code = FAIL_REASON_WATCHDOG;
|
||||
node_status.vendor_specific_status_code = uint8_t(check_fw_result_t::FAIL_REASON_WATCHDOG);
|
||||
}
|
||||
}
|
||||
|
||||
|
|
|
@ -1,5 +1,4 @@
|
|||
void can_start();
|
||||
void can_update();
|
||||
void can_set_node_id(uint8_t node_id);
|
||||
bool can_check_firmware(void);
|
||||
bool can_check_update(void);
|
||||
|
|
|
@ -25,7 +25,8 @@ def build(bld):
|
|||
name= 'AP_Bootloader_libs',
|
||||
ap_vehicle='AP_Bootloader',
|
||||
ap_libraries= flashiface_lib + [
|
||||
'AP_Math'
|
||||
'AP_Math',
|
||||
'AP_CheckFirmware'
|
||||
])
|
||||
|
||||
bld(
|
||||
|
|
Loading…
Reference in New Issue