mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-02 22:18:28 -04:00
AP_Bootloader: fixed can bootloader with old UAVCAN GUI tool
the part that was failing was the write of the leading words. That part is not actually needed in this bootloader as we use a CRC before running, so remove it, which fixes the old windows GUI tool. This also saves some memory and flash
This commit is contained in:
parent
908b348c31
commit
e0e4198358
@ -71,7 +71,6 @@ 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_words[8];
|
|
||||||
|
|
||||||
static struct {
|
static struct {
|
||||||
uint64_t ofs;
|
uint64_t ofs;
|
||||||
@ -226,12 +225,7 @@ 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 (fw_update.sector == 0 && (fw_update.ofs+i*4) < sizeof(app_first_words)) {
|
flash_write_buffer(fw_update.ofs+i*4, &buf32[i], 1);
|
||||||
// keep first word aside, to be flashed last
|
|
||||||
app_first_words[i] = buf32[i];
|
|
||||||
} else {
|
|
||||||
flash_write_buffer(fw_update.ofs+i*4, &buf32[i], 1);
|
|
||||||
}
|
|
||||||
}
|
}
|
||||||
fw_update.ofs += len;
|
fw_update.ofs += len;
|
||||||
fw_update.sector_ofs += len;
|
fw_update.sector_ofs += len;
|
||||||
@ -241,8 +235,6 @@ 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
|
|
||||||
flash_write_buffer(0, app_first_words, ARRAY_SIZE(app_first_words));
|
|
||||||
flash_write_flush();
|
flash_write_flush();
|
||||||
if (can_check_firmware()) {
|
if (can_check_firmware()) {
|
||||||
jump_to_app();
|
jump_to_app();
|
||||||
@ -265,8 +257,6 @@ static void handle_begin_firmware_update(CanardInstance* ins, CanardRxTransfer*
|
|||||||
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);
|
||||||
|
Loading…
Reference in New Issue
Block a user