19 #define ENABLE_HEX_BOOT_LOADER 1 20 #define MAX_SEND_COUNT 510 21 #define MAX_VERIFY_CHUNK_SIZE 1024 22 #define BOOTLOADER_TIMEOUT_DEFAULT 1000 23 #define SAM_BA_BAUDRATE 115200 24 #define SAM_BA_FLASH_PAGE_SIZE 512 25 #define SAM_BA_FLASH_START_ADDRESS 0x00400000 26 #define SAM_BA_BOOTLOADER_SIZE 16384 33 #define CRC_POLY 0x1021 34 #define XMODEM_PAYLOAD_SIZE 128 37 #define FLASH_PAGE_SIZE 65536 62 #if PLATFORM_IS_WINDOWS 64 #define bootloader_snprintf _snprintf 68 #define bootloader_snprintf snprintf 72 #define bootloader_perror(s, ...) \ 73 if ((s)->error != 0 && BOOTLOADER_ERROR_LENGTH > 0) \ 75 bootloader_snprintf((s)->error + strlen((s)->error), BOOTLOADER_ERROR_LENGTH - strlen((s)->error), __VA_ARGS__); \ 78 #define bootloader_min(a, b) (a < b ? a : b) 79 #define bootloader_max(a, b) (a > b ? a : b) 81 static const unsigned char hexLookupTable[16] = {
'0',
'1',
'2',
'3',
'4',
'5',
'6',
'7',
'8',
'9',
'A',
'B',
'C',
'D',
'E',
'F' };
88 uint16_t crc = crc_in >> 15;
89 uint16_t out = crc_in << 1;
109 for (crc = 0; size > 0; size--, data++)
111 for (i = 0x80; i; i >>= 1)
117 for (i = 0; i < 16; i++)
138 if (
serialPortRead(s, &answer,
sizeof(uint8_t)) !=
sizeof(uint8_t))
142 }
while (answer !=
'C');
165 if (ret !=
sizeof(uint8_t))
195 if (ret !=
sizeof(uint8_t))
253 else if (v >=
'2' && v <=
'4')
265 #if PLATFORM_IS_WINDOWS 281 if (error != 0 && errorLength > 0)
298 static int bootloaderChecksum(
int checkSum,
unsigned char* ptr,
int start,
int end,
int checkSumPosition,
int finalCheckSum)
300 unsigned char c1, c2;
301 unsigned char* currentPtr = (
unsigned char*)(ptr + start);
302 unsigned char* endPtr = (
unsigned char*)(ptr + end - 1);
305 while (currentPtr < endPtr)
307 c1 = *(currentPtr++) | 0x20;
308 c1 = (c1 <=
'9' ? c1 + 0xD0 : c1 + 0xA9);
309 c2 = *(currentPtr++) | 0x20;
310 c2 = (c2 <=
'9' ? c2 + 0xD0 : c2 + 0xA9);
317 checkSum = (
unsigned char)(~checkSum + 1);
319 if (checkSumPosition != 0)
330 static const int eraseFlashTimeoutMilliseconds = 60000;
332 unsigned char selectFlash[24];
334 memcpy(selectFlash,
":03000006030000F4CC\0\0\0\0\0", 24);
342 memcpy(selectFlash,
":0200000400FFFBCC\0", 18);
356 unsigned char changePage[24];
375 unsigned char programPage[24];
376 bootloader_snprintf((
char*)programPage, 24,
":0500000100%.4X%.4XCC", startOffset, endOffset);
381 bootloader_perror(s,
"Failed to select offset %X to %X\n", startOffset, endOffset);
391 char* currentPtr = line;
392 char* endPtr = currentPtr + 1023;
394 while (currentPtr != endPtr)
397 c = (char)fgetc(file);
403 else if (c ==
'\n' || c == (
char)
EOF)
414 if (currentPtr - line == 1023)
418 return (
int)(currentPtr - line);
431 unsigned char programLine[12];
435 bootloader_perror(s,
"Failed to write start page at offset %d\n", *currentOffset);
443 int charsForThisPage = byteCount * 2;
446 bootloader_perror(s,
"Failed to write page data at offset %d\n", *currentOffset);
451 for (i = 0; i < charsForThisPage; i++)
453 *verifyCheckSum = ((*verifyCheckSum << 5) + *verifyCheckSum) + hexData[i];
457 unsigned char checkSumHex[3];
461 bootloader_perror(s,
"Failed to write checksum %s at offset %d\n", checkSumHex, *currentOffset);
465 *totalBytes += byteCount;
466 *currentOffset += byteCount;
475 bootloader_perror(s,
"Unexpected char count of %d for page %d at offset %X\n", charCount, *currentPage, *currentOffset);
478 else if (charCount == 0)
483 int byteCount = charCount / 2;
491 bootloader_perror(s,
"Failed to upload %d bytes to page %d at offset %d\n", pageByteCount, *currentPage, *currentOffset);
494 hexData += (pageByteCount * 2);
495 charCount -= (pageByteCount * 2);
509 bootloader_perror(s,
"Failed to upload %d bytes to page %d at offset %d\n", charCount / 2, *currentPage, *currentOffset);
520 unsigned char hexData[256];
521 memset(hexData,
'F', 256);
530 memset(hexData,
'F', byteCount);
534 bootloader_perror(s,
"Failed to fill page %d with %d bytes at offset %d\n", *currentPage, byteCount, *currentOffset);
546 unsigned char programLine[24];
548 n =
bootloader_snprintf((
char*)programLine, 24,
":0500000300%.4X%.4XCC", startOffset, endOffset);
553 bootloader_perror(s,
"Failed to attempt download offsets %X to %X\n", startOffset, endOffset);
565 int realCheckSum = 5381;
568 int i, pageOffset, readCount, actualPageOffset, pageChars, chunkIndex, lines;
571 float percent = 0.0f;
573 FILE* verifyFile = 0;
590 for (i = 0; i <= lastPage; i++)
610 lines = (int)ceilf((
float)readCount / 255.0f);
614 while (chunkIndex < readCount)
616 if (chunkIndex > readCount - 5)
623 if (chunkBuffer[chunkIndex] ==
'X')
628 else if (chunkBuffer[chunkIndex += 4] !=
'=')
633 chunkBuffer[chunkIndex] =
'\0';
634 actualPageOffset = strtol((
char*)(chunkBuffer + chunkIndex - 4), 0, 16);
635 if (actualPageOffset != pageOffset)
642 while (chunkIndex < readCount)
644 c = chunkBuffer[chunkIndex++];
645 if ((c >=
'0' && c <=
'9') || (c >=
'A' && c <=
'F'))
649 realCheckSum = ((realCheckSum << 5) + realCheckSum) + c;
653 if (verifyByte == -1)
655 verifyByte = ((c >=
'0' && c <=
'9') ? c -
'0' : c -
'A' + 10) << 4;
659 verifyByte |= (c >=
'0' && c <=
'9') ? c -
'0' : c -
'A' + 10;
660 fputc(verifyByte, verifyFile);
687 pageOffset += (pageChars / 2);
691 percent = (float)totalCharCount / (
float)grandTotalCharCount;
707 if (realCheckSum != checkSum)
720 #define BUFFER_SIZE 1024 724 int lastSubOffset = currentOffset;
728 int verifyCheckSum = 5381;
730 float percent = 0.0f;
733 unsigned char* outputPtr = output;
734 const unsigned char* outputPtrEnd = output + (
BUFFER_SIZE * 2);
739 unsigned char tmp[5];
742 fseek(file, 0, SEEK_END);
743 fileSize = ftell(file);
744 fseek(file, 0, SEEK_SET);
748 if (lineLength > 12 && line[7] ==
'0' && line[8] ==
'0')
757 memcpy(tmp, line + 3, 4);
759 subOffset = strtol((
char*)tmp, 0, 16);
763 if (subOffset > lastSubOffset)
766 pad = (subOffset - lastSubOffset);
767 if (outputPtr + pad >= outputPtrEnd)
782 pad = lineLength - 11;
783 if (outputPtr + pad >= outputPtrEnd)
789 for (i = 9; i < lineLength - 2; i++)
791 *outputPtr++ = line[i];
795 lastSubOffset = subOffset + ((lineLength - 11) / 2);
796 outputSize = (int)(outputPtr - output);
818 else if (outputSize > 0)
825 outputPtr = output + outputSize;
827 else if (strncmp(line,
":020000048", 10) == 0 && strlen(line) >= 13)
829 memcpy(tmp, line + 10, 3);
831 page = strtol((
char*)tmp, 0, 16);
837 outputSize = (int)(outputPtr - output);
864 percent = (float)ftell(file) / (float)fileSize;
865 percent = (float)ftell(file) / (float)fileSize;
875 outputSize = (int)(outputPtr - output);
915 memset(&state, 0,
sizeof(state));
922 unsigned char buf[16];
923 unsigned char commandType;
925 float percent = 0.0f;
926 fseek(file, 0, SEEK_END);
927 int fileSize = ftell(file);
928 fseek(file, 0, SEEK_SET);
931 verifyCheckSum = fgetc(file) | (fgetc(file) << 8) | (fgetc(file) << 16) | (fgetc(file) << 24);
934 lastPage = fgetc(file) | (fgetc(file) << 8);
956 while (ftell(file) != fileSize)
958 commandType = (
unsigned char)fgetc(file);
959 commandCount = fgetc(file) | (fgetc(file) << 8);
961 if (commandType == 0)
963 while (commandCount-- > 0)
966 commandLength = (fgetc(file) | (fgetc(file) << 8));
967 dataLength = fgetc(file);
972 while (dataLength-- > -1)
974 c = (
unsigned char)fgetc(file);
984 percent = (float)ftell(file) / (float)fileSize;
989 else if (commandType == 1)
992 while (commandCount-- > 0)
994 commandLength = fgetc(file);
995 c = (
unsigned char)fgetc(file);
998 if (commandLength == 1 && c ==
'U')
1001 c = (
unsigned char)fgetc(file);
1002 c = (
unsigned char)fgetc(file);
1008 while (--commandLength > 0)
1010 c = (
unsigned char)fgetc(file);
1015 c = (
unsigned char)fgetc(file);
1016 commandLength = fgetc(file) * 250;
1017 if (commandLength != 0)
1023 commandLength = fgetc(file) * 250;
1024 if (commandLength != 0)
1026 unsigned char waitFor[4];
1034 percent = (float)ftell(file) / (float)fileSize;
1058 if (dataLength == 1)
1091 static const unsigned char handshakerChar =
'U';
1117 #if ENABLE_BOOTLOADER_BAUD_DETECTION 1143 #if ENABLE_BOOTLOADER_BAUD_DETECTION 1149 #endif // ENABLE_BOOTLOADER_BAUD_DETECTION 1161 #define BUF_SIZE 100 1171 if (count != 8 || buf[0] != 0xAA || buf[1] != 0x55 || buf[5] !=
'.' || buf[6] !=
'\r' || buf[7] !=
'\n')
1175 *sambaAvaliable = 1;
1181 *sambaAvaliable = buf[4] == 0x1;
1191 if (p->
error[0] != 0)
1200 p->
statusText(p->
obj,
"Attempting to reload bootloader...");
1204 memset(¶ms, 0,
sizeof(params));
1232 int fileNameLength = (int)strnlen(p->
fileName, 255);
1233 if (fileNameLength > 4 && strncmp(p->
fileName + fileNameLength - 4,
".bin", 4) == 0)
1245 #if ENABLE_HEX_BOOT_LOADER 1248 memset(&state, 0,
sizeof(state));
1256 int blVerMajor, sambaSupport;
1262 bootloader_snprintf(str, 100,
"Bootloader version %d%c found. SAM-BA is %s on port.", blVerMajor, blVerMinor, sambaSupport == 1 ?
"supported" :
"NOT supported");
1268 int fileVerMajor = 0;
1269 char fileVerMinor = 0;
1277 if (blVerMajor < fileVerMajor || blVerMinor < fileVerMinor || p->forceBootloaderUpdate > 0)
1285 bootloader_snprintf(str, 100,
"Updating bootloader to version %d%c...", fileVerMajor, fileVerMinor);
1296 memset(¶ms, 0,
sizeof(params));
1317 p->
statusText(p->
obj,
"WARNING! Bootloader is out of date. Port used to communicate with bootloader does not support updating the bootloader. To force firmware update, run update without including the bootloader file.");
1351 unsigned char buf[32];
1352 int count =
SNPRINTF((
char*)buf,
sizeof(buf),
"W%08x,%08x#", address, value);
1358 unsigned char buf[16];
1359 int count =
SNPRINTF((
char*)buf,
sizeof(buf),
"w%08x,#", address);
1363 uint32_t val = (buf[3] << 24) | (buf[2] << 16) | (buf[1] << 8) | buf[0];
1371 uint32_t status = 0;
1372 for (
int i = 0; i < 10; i++)
1387 if (
samBaWriteWord(port, 0x400e0c04, 0x5a000000 | 0x00000100 | 0x0000000b))
1397 uint16_t page = (uint16_t)(offset / SAM_BA_FLASH_PAGE_SIZE);
1398 unsigned char _buf[32];
1404 count =
SNPRINTF((
char*)_buf,
sizeof(_buf),
"S%08x,%08x#",
1406 (
unsigned int)SAM_BA_FLASH_PAGE_SIZE);
1416 if (
xModemSend(port, buf, SAM_BA_FLASH_PAGE_SIZE))
1423 count =
SNPRINTF((
char*)_buf,
sizeof(_buf),
"W%08x,5a%04x03#", 0x400e0c04, page);
1430 uint32_t checksum2 = 0;
1431 uint32_t nextAddress;
1432 unsigned char buf[512];
1438 while (address < nextAddress)
1440 count =
SNPRINTF((
char*)buf,
sizeof(buf),
"w%08x,#", address);
1442 address +=
sizeof(uint32_t);
1446 if (count == SAM_BA_FLASH_PAGE_SIZE)
1448 for (uint32_t* ptr = (uint32_t*)buf, *ptrEnd = (uint32_t*)(buf +
sizeof(buf)); ptr < ptrEnd; ptr++)
1457 if (verifyProgress != 0)
1462 if (checksum != checksum2)
1477 for (
int i = 0; i < 100; i++)
1480 if (!(status & 0x00020000))
1493 memset(¶ms, 0,
sizeof(params));
1523 *params->
error =
'\0';
1532 fopen_s(&file, params->
fileName,
"rb");
1536 file = fopen(params->
fileName,
"rb");
1542 if (params->
error != 0)
1556 fopen_s(&blfile, params->
bootName,
"rb");
1560 blfile = fopen(params->
bootName,
"rb");
1600 fopen_s(&blfile, bootName,
"rb");
1604 blfile = fopen(bootName,
"rb");
1611 fseek(blfile, 0x3DFC, SEEK_SET);
1612 unsigned char ver_info[4];
1613 size_t n = fread(ver_info, 1, 4, blfile);
1618 if (ver_info[0] == 0xAA && ver_info[1] == 0x55)
1621 *verMajor = ver_info[2];
1623 *verMinor = ver_info[3];
1635 memset(¶ms, 0,
sizeof(params));
1662 uint32_t checksum = 0;
1665 for (
int isUSB = 0; isUSB < 2; isUSB++)
1711 fseek(file, 0, SEEK_END);
1712 int size = ftell(file);
1713 fseek(file, 0, SEEK_SET);
1726 uint32_t offset = 0;
1740 for (uint32_t* ptr = (uint32_t*)buf, *ptrEnd = (uint32_t*)(buf +
sizeof(buf)); ptr < ptrEnd; ptr++)
1850 memset(&p, 0,
sizeof(p));
1861 unsigned char c = 0;
1864 if (baudRates[i] == 0)
1873 for (
size_t loop = 0; loop < 10; loop++)
static int bootloaderProcessHexFile(FILE *file, bootloader_state_t *state)
int bootloadFile(serial_port_t *port, const char *fileName, const char *bootName, const void *obj, pfnBootloadProgress uploadProgress, pfnBootloadProgress verifyProgress)
bootload_params_t * param
static uint32_t samBaFlashWaitForReady(serial_port_t *port)
int disableBootloader(serial_port_t *port, char *error, int errorLength)
static int bootloadFileInternal(FILE *file, bootload_params_t *p)
int serialPortOpenRetry(serial_port_t *serialPort, const char *port, int baudRate, int blocking)
static int bootloaderSelectPage(serial_port_t *s, int page)
int serialPortReadTimeout(serial_port_t *serialPort, unsigned char *buffer, int readCount, int timeoutMilliseconds)
int serialPortWriteAndWaitFor(serial_port_t *serialPort, const unsigned char *buffer, int writeCount, const unsigned char *waitFor, int waitForLength)
static void bootloaderRestart(serial_port_t *s)
#define BOOTLOADER_REFRESH_DELAY
static int serialPortOpenInternal(serial_port_t *s, int baudRate, char *error, int errorLength)
static uint32_t samBaReadWord(serial_port_t *port, uint32_t address)
static void bootloaderRestartAssist(serial_port_t *s)
uint8_t payload[XMODEM_PAYLOAD_SIZE]
GeneratorWrapper< T > value(T &&value)
GeneratorWrapper< std::vector< T > > chunk(size_t size, GeneratorWrapper< T > &&generator)
static int bootloaderReadLine(FILE *file, char line[1024])
static int bootloaderNegotiateVersion(bootloader_state_t *state)
static uint16_t crc16(uint8_t *data, uint16_t size)
size_t count(InputIterator first, InputIterator last, T const &item)
static int samBaVerify(serial_port_t *port, uint32_t checksum, const void *obj, pfnBootloadProgress verifyProgress)
int bootloaderCycleBaudRate(int baudRate)
#define IS_BAUD_RATE_BOOTLOADER_SLOW
#define SAM_BA_FLASH_START_ADDRESS
struct bootload_params_t::@41::@42 bitFields
static int bootloadUpdateBootloaderSendFile(bootload_params_t *p)
static int bootloaderChecksum(int checkSum, unsigned char *ptr, int start, int end, int checkSumPosition, int finalCheckSum)
static int samBaSetBootFromFlash(serial_port_t *port)
int bootloaderClosestBaudRate(int baudRate)
static int samBaSoftReset(serial_port_t *port)
char port[MAX_SERIAL_PORT_NAME_LENGTH+1]
#define IS_BAUD_RATE_BOOTLOADER_RS232
const char * verifyFileName
static int bootloaderDownloadData(serial_port_t *s, int startOffset, int endOffset)
#define bootloader_snprintf
static int bootloaderProcessBinFile(FILE *file, bootload_params_t *p)
int serialPortWaitForTimeout(serial_port_t *serialPort, const unsigned char *waitFor, int waitForLength, int timeoutMilliseconds)
pfnBootloadProgress uploadProgress
int serialPortWriteAndWaitForTimeout(serial_port_t *serialPort, const unsigned char *buffer, int writeCount, const unsigned char *waitFor, int waitForLength, const int timeoutMilliseconds)
static int bootloaderFillCurrentPage(serial_port_t *s, int *currentPage, int *currentOffset, int *totalBytes, int *verifyCheckSum)
static int bootloaderSync(serial_port_t *s)
int enableBootloader(serial_port_t *port, int baudRate, char *error, int errorLength, const char *bootloadEnableCmd)
int serialPortClose(serial_port_t *serialPort)
#define IS_BAUD_RATE_BOOTLOADER_LEGACY
#define MAX_VERIFY_CHUNK_SIZE
pfnBootloadStatus statusText
int serialPortWrite(serial_port_t *serialPort, const unsigned char *buffer, int writeCount)
int(* pfnBootloadProgress)(const void *obj, float percent)
#define bootloader_min(a, b)
#define bootloader_perror(s,...)
static const unsigned char hexLookupTable[16]
static int samBaFlashEraseWritePage(serial_port_t *port, size_t offset, unsigned char buf[SAM_BA_FLASH_PAGE_SIZE], int isUSB)
static int bootloaderEraseFlash(serial_port_t *s)
static int bootloaderUploadHexData(serial_port_t *s, unsigned char *hexData, int charCount, int *currentOffset, int *currentPage, int *totalBytes, int *verifyCheckSum)
static const int s_baudRateList[]
USBInterfaceDescriptor data
int bootloadFileEx(bootload_params_t *params)
#define BOOTLOADER_RESPONSE_DELAY
static int bootloaderUploadHexDataPage(serial_port_t *s, unsigned char *hexData, int byteCount, int *currentOffset, int *totalBytes, int *verifyCheckSum)
char error[BOOTLOADER_ERROR_LENGTH]
#define XMODEM_PAYLOAD_SIZE
#define SAM_BA_BOOTLOADER_SIZE
static int disableBootloaderInternal(serial_port_t *port, char *error, int errorLength, int baud)
int bootloadGetBootloaderVersionFromFile(const char *bootName, int *verMajor, char *verMinor)
int bootloadUpdateBootloaderEx(bootload_params_t *p)
static int bootloaderVerify(int lastPage, int checkSum, bootloader_state_t *state)
int serialPortReadChar(serial_port_t *serialPort, unsigned char *c)
int serialPortReadCharTimeout(serial_port_t *serialPort, unsigned char *c, int timeoutMilliseconds)
#define BOOTLOADER_TIMEOUT_DEFAULT
#define IS_BAUD_RATE_BOOTLOADER
static int xModemSend(serial_port_t *s, uint8_t *buf, size_t len)
int serialPortFlush(serial_port_t *serialPort)
static int bootloaderHandshake(bootload_params_t *p)
static int samBaWriteWord(serial_port_t *port, uint32_t address, uint32_t value)
char bootloadEnableCmd[16]
int serialPortWriteAscii(serial_port_t *serialPort, const char *buffer, int bufferLength)
static uint16_t crc_update(uint16_t crc_in, int incr)
#define _ARRAY_ELEMENT_COUNT(a)
int forceBootloaderUpdate
static void bootloadGetVersion(serial_port_t *s, int *major, char *minor, int *sambaAvaliable)
pfnBootloadProgress verifyProgress
#define BOOTLOADER_ERROR_LENGTH
int serialPortRead(serial_port_t *serialPort, unsigned char *buffer, int readCount)
#define SAM_BA_FLASH_PAGE_SIZE
int bootloadUpdateBootloader(serial_port_t *port, const char *fileName, const void *obj, pfnBootloadProgress uploadProgress, pfnBootloadProgress verifyProgress)
static int bootloaderBeginProgramForCurrentPage(serial_port_t *s, int startOffset, int endOffset)
union bootload_params_t::@41 flags
#define BOOTLOADER_RETRIES
int serialPortSleep(serial_port_t *serialPort, int sleepMilliseconds)