mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-08 17:08:28 -04:00
AP_Bootloader: speed up CAN fw load
This commit is contained in:
parent
8812466355
commit
9c4a01e0b0
@ -83,6 +83,7 @@ int main(void)
|
|||||||
timeout = 10000;
|
timeout = 10000;
|
||||||
can_set_node_id(m & 0xFF);
|
can_set_node_id(m & 0xFF);
|
||||||
}
|
}
|
||||||
|
can_check_update();
|
||||||
if (!can_check_firmware()) {
|
if (!can_check_firmware()) {
|
||||||
// bad firmware CRC, don't try and boot
|
// bad firmware CRC, don't try and boot
|
||||||
timeout = 0;
|
timeout = 0;
|
||||||
|
@ -243,19 +243,21 @@ 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;
|
||||||
}
|
}
|
||||||
uint32_t offset = 0;
|
|
||||||
canardDecodeScalar(transfer, 0, 8, false, (void*)&fw_update.node_id);
|
|
||||||
offset += 8;
|
|
||||||
for (uint8_t i=0; i<transfer->payload_len-1; i++) {
|
|
||||||
canardDecodeScalar(transfer, offset, 8, false, (void*)&fw_update.path[i]);
|
|
||||||
offset += 8;
|
|
||||||
}
|
|
||||||
fw_update.ofs = 0;
|
|
||||||
fw_update.last_ms = 0;
|
|
||||||
fw_update.sector = 0;
|
|
||||||
fw_update.sector_ofs = 0;
|
|
||||||
if (fw_update.node_id == 0) {
|
if (fw_update.node_id == 0) {
|
||||||
fw_update.node_id = transfer->source_node_id;
|
uint32_t offset = 0;
|
||||||
|
canardDecodeScalar(transfer, 0, 8, false, (void*)&fw_update.node_id);
|
||||||
|
offset += 8;
|
||||||
|
for (uint8_t i=0; i<transfer->payload_len-1; i++) {
|
||||||
|
canardDecodeScalar(transfer, offset, 8, false, (void*)&fw_update.path[i]);
|
||||||
|
offset += 8;
|
||||||
|
}
|
||||||
|
fw_update.ofs = 0;
|
||||||
|
fw_update.last_ms = 0;
|
||||||
|
fw_update.sector = 0;
|
||||||
|
fw_update.sector_ofs = 0;
|
||||||
|
if (fw_update.node_id == 0) {
|
||||||
|
fw_update.node_id = transfer->source_node_id;
|
||||||
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
uint8_t buffer[UAVCAN_PROTOCOL_FILE_BEGINFIRMWAREUPDATE_RESPONSE_MAX_SIZE];
|
uint8_t buffer[UAVCAN_PROTOCOL_FILE_BEGINFIRMWAREUPDATE_RESPONSE_MAX_SIZE];
|
||||||
@ -547,6 +549,10 @@ void can_set_node_id(uint8_t node_id)
|
|||||||
*/
|
*/
|
||||||
bool can_check_firmware(void)
|
bool can_check_firmware(void)
|
||||||
{
|
{
|
||||||
|
if (fw_update.node_id != 0) {
|
||||||
|
// we're doing an update, don't boot this fw
|
||||||
|
return false;
|
||||||
|
}
|
||||||
const uint8_t sig[8] = { 0x40, 0xa2, 0xe4, 0xf1, 0x64, 0x68, 0x91, 0x06 };
|
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 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 uint32_t flash_size = (BOARD_FLASH_SIZE - FLASH_BOOTLOADER_LOAD_KB)*1024;
|
||||||
@ -579,10 +585,10 @@ bool can_check_firmware(void)
|
|||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
|
|
||||||
void can_start()
|
// check for a firmware update marker left by app
|
||||||
|
void can_check_update(void)
|
||||||
{
|
{
|
||||||
#if HAL_RAM_RESERVE_START >= 256
|
#if HAL_RAM_RESERVE_START >= 256
|
||||||
// check for a firmware update marker left by app
|
|
||||||
struct app_bootloader_comms *comms = (struct app_bootloader_comms *)HAL_RAM0_START;
|
struct app_bootloader_comms *comms = (struct app_bootloader_comms *)HAL_RAM0_START;
|
||||||
if (comms->magic == APP_BOOTLOADER_COMMS_MAGIC) {
|
if (comms->magic == APP_BOOTLOADER_COMMS_MAGIC) {
|
||||||
can_set_node_id(comms->my_node_id);
|
can_set_node_id(comms->my_node_id);
|
||||||
@ -592,7 +598,10 @@ void can_start()
|
|||||||
// clear comms region
|
// clear comms region
|
||||||
memset(comms, 0, sizeof(struct app_bootloader_comms));
|
memset(comms, 0, sizeof(struct app_bootloader_comms));
|
||||||
#endif
|
#endif
|
||||||
|
}
|
||||||
|
|
||||||
|
void can_start()
|
||||||
|
{
|
||||||
// calculate optimal CAN timings given PCLK1 and baudrate
|
// calculate optimal CAN timings given PCLK1 and baudrate
|
||||||
CanardSTM32CANTimings timings {};
|
CanardSTM32CANTimings timings {};
|
||||||
canardSTM32ComputeCANTimings(STM32_PCLK1, baudrate, &timings);
|
canardSTM32ComputeCANTimings(STM32_PCLK1, baudrate, &timings);
|
||||||
|
@ -2,4 +2,4 @@ void can_start();
|
|||||||
void can_update();
|
void can_update();
|
||||||
void can_set_node_id(uint8_t node_id);
|
void can_set_node_id(uint8_t node_id);
|
||||||
bool can_check_firmware(void);
|
bool can_check_firmware(void);
|
||||||
|
void can_check_update(void);
|
||||||
|
Loading…
Reference in New Issue
Block a user