AP_Bootloader: use new hal CAN interface for CAN support

This commit is contained in:
Andrew Tridgell 2020-07-15 07:31:14 +10:00 committed by Peter Barker
parent a79efaeb1d
commit 246e790484
5 changed files with 71 additions and 61 deletions

View File

@ -321,62 +321,6 @@ cout_word(uint32_t val)
cout((uint8_t *)&val, 4); cout((uint8_t *)&val, 4);
} }
/*
we use a write buffer for flashing, both for efficiency and to
ensure that we only ever do 32 byte aligned writes on STM32H7. If
you attempt to do writes on a H7 of less than 32 bytes or not
aligned then the flash can end up in a CRC error state, which can
generate a hardware fault (a double ECC error) on flash read, even
after a power cycle
*/
static struct {
uint32_t buffer[8];
uint32_t address;
uint8_t n;
} fbuf;
/*
flush the write buffer
*/
static bool flash_write_flush(void)
{
if (fbuf.n == 0) {
return true;
}
fbuf.n = 0;
return flash_func_write_words(fbuf.address, fbuf.buffer, ARRAY_SIZE(fbuf.buffer));
}
/*
write to flash with buffering to 32 bytes alignment
*/
static bool flash_write_buffer(uint32_t address, const uint32_t *v, uint8_t nwords)
{
if (fbuf.n > 0 && address != fbuf.address + fbuf.n*4) {
if (!flash_write_flush()) {
return false;
}
}
while (nwords > 0) {
if (fbuf.n == 0) {
fbuf.address = address;
memset(fbuf.buffer, 0xff, sizeof(fbuf.buffer));
}
uint8_t n = MIN(ARRAY_SIZE(fbuf.buffer)-fbuf.n, nwords);
memcpy(&fbuf.buffer[fbuf.n], v, n*4);
address += n*4;
v += n;
nwords -= n;
fbuf.n += n;
if (fbuf.n == ARRAY_SIZE(fbuf.buffer)) {
if (!flash_write_flush()) {
return false;
}
}
}
return true;
}
#define TEST_FLASH 0 #define TEST_FLASH 0
#if TEST_FLASH #if TEST_FLASH

View File

@ -71,7 +71,7 @@ static uint8_t node_id_allocation_transfer_id;
static uavcan_protocol_NodeStatus node_status; static uavcan_protocol_NodeStatus node_status;
static uint32_t send_next_node_id_allocation_request_at_ms; static uint32_t send_next_node_id_allocation_request_at_ms;
static uint8_t node_id_allocation_unique_id_offset; static uint8_t node_id_allocation_unique_id_offset;
static uint32_t app_first_word = 0xFFFFFFFF; static uint32_t app_first_words[8];
static struct { static struct {
uint64_t ofs; uint64_t ofs;
@ -225,11 +225,11 @@ static void handle_file_read_response(CanardInstance* ins, CanardRxTransfer* tra
flash_func_erase_sector(fw_update.sector+1); flash_func_erase_sector(fw_update.sector+1);
} }
for (uint16_t i=0; i<len/4; i++) { for (uint16_t i=0; i<len/4; i++) {
if (i == 0 && fw_update.sector == 0 && fw_update.ofs == 0) { if (fw_update.sector == 0 && (fw_update.ofs+i*4) < sizeof(app_first_words)) {
// keep first word aside, to be flashed last // keep first word aside, to be flashed last
app_first_word = buf32[0]; app_first_words[i] = buf32[i];
} else { } else {
flash_func_write_word(fw_update.ofs+i*4, buf32[i]); flash_write_buffer(fw_update.ofs+i*4, &buf32[i], 1);
} }
} }
fw_update.ofs += len; fw_update.ofs += len;
@ -241,7 +241,8 @@ static void handle_file_read_response(CanardInstance* ins, CanardRxTransfer* tra
if (len < UAVCAN_PROTOCOL_FILE_READ_RESPONSE_DATA_MAX_LENGTH) { if (len < UAVCAN_PROTOCOL_FILE_READ_RESPONSE_DATA_MAX_LENGTH) {
fw_update.node_id = 0; fw_update.node_id = 0;
// now flash the first word // now flash the first word
flash_func_write_word(0, app_first_word); flash_write_buffer(0, app_first_words, ARRAY_SIZE(app_first_words));
flash_write_flush();
if (can_check_firmware()) { if (can_check_firmware()) {
jump_to_app(); jump_to_app();
} }
@ -262,6 +263,9 @@ static void handle_begin_firmware_update(CanardInstance* ins, CanardRxTransfer*
if (transfer->payload_len < 1 || transfer->payload_len > sizeof(fw_update.path)+1) { if (transfer->payload_len < 1 || transfer->payload_len > sizeof(fw_update.path)+1) {
return; return;
} }
memset(app_first_words, 0xff, sizeof(app_first_words));
if (fw_update.node_id == 0) { if (fw_update.node_id == 0) {
uint32_t offset = 0; uint32_t offset = 0;
canardDecodeScalar(transfer, 0, 8, false, (void*)&fw_update.node_id); canardDecodeScalar(transfer, 0, 8, false, (void*)&fw_update.node_id);

View File

@ -9,6 +9,7 @@
#include <AP_HAL_ChibiOS/hwdef/common/usbcfg.h> #include <AP_HAL_ChibiOS/hwdef/common/usbcfg.h>
#include <AP_HAL_ChibiOS/hwdef/common/flash.h> #include <AP_HAL_ChibiOS/hwdef/common/flash.h>
#include <AP_HAL_ChibiOS/hwdef/common/stm32_util.h> #include <AP_HAL_ChibiOS/hwdef/common/stm32_util.h>
#include <AP_Math/AP_Math.h>
#include "support.h" #include "support.h"
#include "mcu_f1.h" #include "mcu_f1.h"
#include "mcu_f3.h" #include "mcu_f3.h"
@ -161,6 +162,62 @@ uint32_t flash_func_read_sn(uint32_t idx)
return *(uint32_t *)(UDID_START + idx); return *(uint32_t *)(UDID_START + idx);
} }
/*
we use a write buffer for flashing, both for efficiency and to
ensure that we only ever do 32 byte aligned writes on STM32H7. If
you attempt to do writes on a H7 of less than 32 bytes or not
aligned then the flash can end up in a CRC error state, which can
generate a hardware fault (a double ECC error) on flash read, even
after a power cycle
*/
static struct {
uint32_t buffer[8];
uint32_t address;
uint8_t n;
} fbuf;
/*
flush the write buffer
*/
bool flash_write_flush(void)
{
if (fbuf.n == 0) {
return true;
}
fbuf.n = 0;
return flash_func_write_words(fbuf.address, fbuf.buffer, ARRAY_SIZE(fbuf.buffer));
}
/*
write to flash with buffering to 32 bytes alignment
*/
bool flash_write_buffer(uint32_t address, const uint32_t *v, uint8_t nwords)
{
if (fbuf.n > 0 && address != fbuf.address + fbuf.n*4) {
if (!flash_write_flush()) {
return false;
}
}
while (nwords > 0) {
if (fbuf.n == 0) {
fbuf.address = address;
memset(fbuf.buffer, 0xff, sizeof(fbuf.buffer));
}
uint8_t n = MIN(ARRAY_SIZE(fbuf.buffer)-fbuf.n, nwords);
memcpy(&fbuf.buffer[fbuf.n], v, n*4);
address += n*4;
v += n;
nwords -= n;
fbuf.n += n;
if (fbuf.n == ARRAY_SIZE(fbuf.buffer)) {
if (!flash_write_flush()) {
return false;
}
}
}
return true;
}
uint32_t get_mcu_id(void) uint32_t get_mcu_id(void)
{ {
return *(uint32_t *)DBGMCU_BASE; return *(uint32_t *)DBGMCU_BASE;

View File

@ -30,6 +30,9 @@ uint32_t flash_func_read_sn(uint32_t idx);
void flash_set_keep_unlocked(bool); void flash_set_keep_unlocked(bool);
void lock_bl_port(void); void lock_bl_port(void);
bool flash_write_flush(void);
bool flash_write_buffer(uint32_t address, const uint32_t *v, uint8_t nwords);
uint32_t get_mcu_id(void); uint32_t get_mcu_id(void);
uint32_t get_mcu_desc(uint32_t len, uint8_t *buf); uint32_t get_mcu_desc(uint32_t len, uint8_t *buf);
bool check_limit_flash_1M(void); bool check_limit_flash_1M(void);

View File

@ -7,6 +7,8 @@ undef ROMFS
undef HAL_HAVE_SAFETY_SWITCH undef HAL_HAVE_SAFETY_SWITCH
undef IMU undef IMU
undef HAL_CHIBIOS_ARCH_FMUV3 undef HAL_CHIBIOS_ARCH_FMUV3
undef BOOTLOADER_DEV_LIST
# board ID for firmware load # board ID for firmware load
APJ_BOARD_ID 1400 APJ_BOARD_ID 1400