inertialSenseBootLoader.c
Go to the documentation of this file.
1 /*
2 MIT LICENSE
3 
4 Copyright (c) 2014-2021 Inertial Sense, Inc. - http://inertialsense.com
5 
6 Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files(the "Software"), to deal in the Software without restriction, including without limitation the rights to use, copy, modify, merge, publish, distribute, sublicense, and/or sell copies of the Software, and to permit persons to whom the Software is furnished to do so, subject to the following conditions :
7 
8 The above copyright notice and this permission notice shall be included in all copies or substantial portions of the Software.
9 
10 THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT.IN NO EVENT SHALL THE AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE.
11 */
12 
13 #include <stdio.h>
14 #include <math.h>
16 #include "ISConstants.h"
17 #include "ISUtilities.h"
18 
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
27 
28 #define X_SOH 0x01
29 #define X_EOT 0x04
30 #define X_ACK 0x06
31 #define X_NAK 0x15
32 #define X_CAN 0x18
33 #define CRC_POLY 0x1021
34 #define XMODEM_PAYLOAD_SIZE 128
35 
36 // logical page size, offsets for pages are 0x0000 to 0xFFFF - flash page size on devices will vary and is not relevant to the bootloader client
37 #define FLASH_PAGE_SIZE 65536
38 
40 
41 typedef struct
42 {
43  int version;
48 
50 
51 typedef struct
52 {
53  uint8_t start;
54  uint8_t block;
55  uint8_t block_neg;
56  uint8_t payload[XMODEM_PAYLOAD_SIZE];
57  uint16_t crc;
59 
61 
62 #if PLATFORM_IS_WINDOWS
63 
64 #define bootloader_snprintf _snprintf
65 
66 #else
67 
68 #define bootloader_snprintf snprintf
69 
70 #endif
71 
72 #define bootloader_perror(s, ...) \
73  if ((s)->error != 0 && BOOTLOADER_ERROR_LENGTH > 0) \
74  { \
75  bootloader_snprintf((s)->error + strlen((s)->error), BOOTLOADER_ERROR_LENGTH - strlen((s)->error), __VA_ARGS__); \
76  }
77 
78 #define bootloader_min(a, b) (a < b ? a : b)
79 #define bootloader_max(a, b) (a > b ? a : b)
80 
81 static const unsigned char hexLookupTable[16] = { '0', '1', '2', '3', '4', '5', '6', '7', '8', '9', 'A', 'B', 'C', 'D', 'E', 'F' };
82 
83 // Fastest to slowest
85 
86 static uint16_t crc_update(uint16_t crc_in, int incr)
87 {
88  uint16_t crc = crc_in >> 15;
89  uint16_t out = crc_in << 1;
90 
91  if (incr)
92  {
93  out++;
94  }
95 
96  if (crc)
97  {
98  out ^= CRC_POLY;
99  }
100 
101  return out;
102 }
103 
104 
105 static uint16_t crc16(uint8_t* data, uint16_t size)
106 {
107  uint16_t crc, i;
108 
109  for (crc = 0; size > 0; size--, data++)
110  {
111  for (i = 0x80; i; i >>= 1)
112  {
113  crc = crc_update(crc, *data & i);
114  }
115  }
116 
117  for (i = 0; i < 16; i++)
118  {
119  crc = crc_update(crc, 0);
120  }
121 
122  return crc;
123 }
124 
125 static int xModemSend(serial_port_t* s, uint8_t* buf, size_t len)
126 {
127  int ret;
128  uint8_t eot = X_EOT;
129  uint8_t answer;
131 
132  chunk.block = 1;
133  chunk.start = X_SOH;
134 
135  // wait for receiver ping
136  do
137  {
138  if (serialPortRead(s, &answer, sizeof(uint8_t)) != sizeof(uint8_t))
139  {
140  return -1;
141  }
142  } while (answer != 'C');
143 
144  // write up to one sector
145  while (len)
146  {
147  size_t z = 0;
148  int next = 0;
149 // char status;
150 
151  z = _MIN(len, sizeof(chunk.payload));
152  memcpy(chunk.payload, buf, z);
153  memset(chunk.payload + z, 0xff, sizeof(chunk.payload) - z);
154 
155  chunk.crc = SWAP16(crc16(chunk.payload, sizeof(chunk.payload)));
156  chunk.block_neg = 0xff - chunk.block;
157 
158  ret = serialPortWrite(s, (const uint8_t*)&chunk, sizeof(xmodem_chunk_t));
159  if (ret != sizeof(xmodem_chunk_t))
160  {
161  return -1;
162  }
163 
164  ret = serialPortReadTimeout(s, &answer, sizeof(uint8_t), BOOTLOADER_TIMEOUT_DEFAULT);
165  if (ret != sizeof(uint8_t))
166  {
167  return -1;
168  }
169 
170  switch (answer)
171  {
172  case X_NAK:
173 // status = 'N';
174  break;
175  case X_ACK:
176 // status = '.';
177  next = 1;
178  break;
179  case X_CAN:
180  return -1;
181  default:
182 // status = '?';
183  break;
184  }
185 
186  if (next)
187  {
188  chunk.block++;
189  len -= z;
190  buf += z;
191  }
192  }
193 
194  ret = serialPortWrite(s, &eot, sizeof(uint8_t));
195  if (ret != sizeof(uint8_t))
196  {
197  return -1;
198  }
199  serialPortReadChar(s, &eot);
200  return 0;
201 }
202 
203 int bootloaderCycleBaudRate(int baudRate)
204 {
205  for (unsigned int i = 0; i < _ARRAY_ELEMENT_COUNT(s_baudRateList); i++)
206  { // Find current baudrate
207  if (baudRate == s_baudRateList[i])
208  {
209  // Get next baudrate
211  {
212  return s_baudRateList[i + 1];
213  }
214  }
215  }
216 
217  return s_baudRateList[0];
218 }
219 
220 // Finds the closest bootloader supported baudrate
221 int bootloaderClosestBaudRate(int baudRate)
222 {
223  for (unsigned int i = 0; i < _ARRAY_ELEMENT_COUNT(s_baudRateList); i++)
224  {
225  if (baudRate >= s_baudRateList[i])
226  {
227  return s_baudRateList[i];
228  }
229  }
230 
232 }
233 
234 // negotiate the bootloader version, once a 'U' character has been read, we read another character, timing out after 500 milliseconds
235 // if nothing comes back, we are using version 1, otherwise the version is the number sent back
237 {
238  unsigned char v = 0;
239 
240  do {
241  if (serialPortReadCharTimeout(state->param->port, &v, 500) == 0)
242  {
243  v = '1';
244  }
245  } while (v == 'U');
246 
247  if (v == '1')
248  {
249  // version 1
250  state->version = 1;
251  state->firstPageSkipBytes = 8192;
252  }
253  else if (v >= '2' && v <= '4')
254  {
255  // version 2, 3 (which sent v2), 4
256  state->version = v-'0';
257  state->firstPageSkipBytes = 16384;
258  }
259  else
260  {
261  bootloader_perror(state->param->port, "Invalid version sent from bootloader: 0x%02X\n", (int)v);
262  return 0;
263  }
264 
265 #if PLATFORM_IS_WINDOWS
266 
267  // EvalTool and multiple bootloads under Windows 10 have issues with dropped data if verify runs too fast
268  state->verifyChunkSize = 125;
269 
270 #else
271 
273 
274 #endif
275 
276  return 1;
277 }
278 
279 static int serialPortOpenInternal(serial_port_t* s, int baudRate, char* error, int errorLength)
280 {
281  if (error != 0 && errorLength > 0)
282  {
283  *error = '\0';
284  }
285  serialPortClose(s);
286  s->error = error;
287  s->errorLength = errorLength;
288  if (serialPortOpenRetry(s, s->port, baudRate == 0 ? IS_BAUD_RATE_BOOTLOADER : baudRate, 1) == 0)
289  {
290  bootloader_perror(s, "Unable to open serial port at %s\n", s->port);
291  return 0;
292  }
293 
294  return 1;
295 }
296 
297 // calculate checksum - start is INCLUSIVE and end is EXCLUSIVE, if checkSumPosition is not 0, the checkSum is written to ptr + checkSumPosition
298 static int bootloaderChecksum(int checkSum, unsigned char* ptr, int start, int end, int checkSumPosition, int finalCheckSum)
299 {
300  unsigned char c1, c2;
301  unsigned char* currentPtr = (unsigned char*)(ptr + start);
302  unsigned char* endPtr = (unsigned char*)(ptr + end - 1);
303  unsigned char b;
304 
305  while (currentPtr < endPtr)
306  {
307  c1 = *(currentPtr++) | 0x20;
308  c1 = (c1 <= '9' ? c1 + 0xD0 : c1 + 0xA9);
309  c2 = *(currentPtr++) | 0x20;
310  c2 = (c2 <= '9' ? c2 + 0xD0 : c2 + 0xA9);
311  b = (c1 << 4) | c2;
312  checkSum += b;
313  }
314 
315  if (finalCheckSum)
316  {
317  checkSum = (unsigned char)(~checkSum + 1);
318  }
319  if (checkSumPosition != 0)
320  {
321  bootloader_snprintf((char*)(ptr + checkSumPosition), 3, "%.2X", checkSum);
322  }
323 
324  return checkSum;
325 }
326 
328 {
329  // give the device this many seconds to erase flash before giving up
330  static const int eraseFlashTimeoutMilliseconds = 60000;
331 
332  unsigned char selectFlash[24];
333 
334  memcpy(selectFlash, ":03000006030000F4CC\0\0\0\0\0", 24);
335  bootloaderChecksum(0, selectFlash, 1, 17, 17, 1);
336  if (serialPortWriteAndWaitForTimeout(s, selectFlash, 19, (unsigned char*)".\r\n", 3, BOOTLOADER_TIMEOUT_DEFAULT) == 0)
337  {
338  bootloader_perror(s, "Failed to select flash memory to erase\n");
339  return 0;
340  }
341 
342  memcpy(selectFlash, ":0200000400FFFBCC\0", 18);
343  bootloaderChecksum(0, selectFlash, 1, 15, 15, 1);
344  if (serialPortWriteAndWaitForTimeout(s, selectFlash, 17, (unsigned char*)".\r\n", 3, eraseFlashTimeoutMilliseconds) == 0)
345  {
346  bootloader_perror(s, "Failed to perform erase flash memory operation\n");
347  return 0;
348  }
349 
350  return 1;
351 }
352 
353 static int bootloaderSelectPage(serial_port_t* s, int page)
354 {
355  // Atmel select page command (0x06) is 4 bytes and the data is always 0301xxxx where xxxx is a 16 bit page number in hex
356  unsigned char changePage[24];
357  bootloader_snprintf((char*)changePage, 24, ":040000060301%.4XCC", page);
358  bootloaderChecksum(0, changePage, 1, 17, 17, 1);
359 
360  if (serialPortWriteAndWaitForTimeout(s, changePage, 19, (unsigned char*)".\r\n", 3, BOOTLOADER_TIMEOUT_DEFAULT) == 0)
361  {
362  bootloader_perror(s, "Failed to change to page %d\n", page);
363  return 0;
364  }
365 
366  return 1;
367 }
368 
369 static int bootloaderBeginProgramForCurrentPage(serial_port_t* s, int startOffset, int endOffset)
370 {
371  // Atmel begin program command is 0x01, different from standard intel hex where command 0x01 is end of file
372  // After the 0x01 is a 00 which means begin writing program
373  // The begin program command uses the current page and specifies two 16 bit addresses that specify where in the current page
374  // the program code will be written
375  unsigned char programPage[24];
376  bootloader_snprintf((char*)programPage, 24, ":0500000100%.4X%.4XCC", startOffset, endOffset);
377  bootloaderChecksum(0, programPage, 1, 19, 19, 1);
378 
379  if (serialPortWriteAndWaitForTimeout(s, programPage, 21, (unsigned char*)".\r\n", 3, BOOTLOADER_TIMEOUT_DEFAULT) == 0)
380  {
381  bootloader_perror(s, "Failed to select offset %X to %X\n", startOffset, endOffset);
382  return 0;
383  }
384 
385  return 1;
386 }
387 
388 static int bootloaderReadLine(FILE* file, char line[1024])
389 {
390  char c;
391  char* currentPtr = line;
392  char* endPtr = currentPtr + 1023;
393 
394  while (currentPtr != endPtr)
395  {
396  // read one char
397  c = (char)fgetc(file);
398  if (c == '\r')
399  {
400  // eat '\r' chars
401  continue;
402  }
403  else if (c == '\n' || c == (char)EOF)
404  {
405  // newline char, we have a line
406  break;
407  }
408  *currentPtr++ = c;
409  }
410 
411  *currentPtr = '\0';
412 
413  // TODO: Figure out why ARM64 bootloader hits this...
414  if (currentPtr - line == 1023)
415  {
416  return 0;
417  }
418  return (int)(currentPtr - line);
419 }
420 
421 static int bootloaderUploadHexDataPage(serial_port_t* s, unsigned char* hexData, int byteCount, int* currentOffset, int* totalBytes, int* verifyCheckSum)
422 {
423  int i;
424 
425  if (byteCount == 0)
426  {
427  return 1;
428  }
429 
430  // create a program request with just the hex characters that will fit on this page
431  unsigned char programLine[12];
432  bootloader_snprintf((char*)programLine, 12, ":%.2X%.4X00", byteCount, *currentOffset);
433  if (serialPortWrite(s, programLine, 9) != 9)
434  {
435  bootloader_perror(s, "Failed to write start page at offset %d\n", *currentOffset);
436  return 0;
437  }
438 
439  // add the previously written chars to the checksum
440  int checkSum = bootloaderChecksum(0, programLine, 1, 9, 0, 0);
441 
442  // write all of the hex chars
443  int charsForThisPage = byteCount * 2;
444  if (serialPortWrite(s, hexData, charsForThisPage) != charsForThisPage)
445  {
446  bootloader_perror(s, "Failed to write page data at offset %d\n", *currentOffset);
447  return 0;
448  }
449 
450  // calculate verification checksum for this data
451  for (i = 0; i < charsForThisPage; i++)
452  {
453  *verifyCheckSum = ((*verifyCheckSum << 5) + *verifyCheckSum) + hexData[i];
454  }
455 
456  checkSum = bootloaderChecksum(checkSum, hexData, 0, charsForThisPage, 0, 1);
457  unsigned char checkSumHex[3];
458  bootloader_snprintf((char*)checkSumHex, 3, "%.2X", checkSum);
459  if (serialPortWriteAndWaitForTimeout(s, checkSumHex, 2, (unsigned char*)".\r\n", 3, BOOTLOADER_TIMEOUT_DEFAULT) == 0)
460  {
461  bootloader_perror(s, "Failed to write checksum %s at offset %d\n", checkSumHex, *currentOffset);
462  return 0;
463  }
464 
465  *totalBytes += byteCount;
466  *currentOffset += byteCount;
467 
468  return 1;
469 }
470 
471 static int bootloaderUploadHexData(serial_port_t* s, unsigned char* hexData, int charCount, int* currentOffset, int* currentPage, int* totalBytes, int* verifyCheckSum)
472 {
473  if (charCount > MAX_SEND_COUNT)
474  {
475  bootloader_perror(s, "Unexpected char count of %d for page %d at offset %X\n", charCount, *currentPage, *currentOffset);
476  return 0;
477  }
478  else if (charCount == 0)
479  {
480  return 1;
481  }
482 
483  int byteCount = charCount / 2;
484 
485  // check if we will overrun the current page
486  if (*currentOffset + byteCount > FLASH_PAGE_SIZE)
487  {
488  int pageByteCount = FLASH_PAGE_SIZE - *currentOffset;
489  if (bootloaderUploadHexDataPage(s, hexData, pageByteCount, currentOffset, totalBytes, verifyCheckSum) == 0)
490  {
491  bootloader_perror(s, "Failed to upload %d bytes to page %d at offset %d\n", pageByteCount, *currentPage, *currentOffset);
492  return 0;
493  }
494  hexData += (pageByteCount * 2);
495  charCount -= (pageByteCount * 2);
496 
497  // change to the next page
498  *currentOffset = 0;
499  (*currentPage)++;
501  {
502  bootloader_perror(s, "Failure issuing select page command for upload\n");
503  return 0;
504  }
505  }
506 
507  if (charCount != 0 && bootloaderUploadHexDataPage(s, hexData, charCount / 2, currentOffset, totalBytes, verifyCheckSum) == 0)
508  {
509  bootloader_perror(s, "Failed to upload %d bytes to page %d at offset %d\n", charCount / 2, *currentPage, *currentOffset);
510  return 0;
511  }
512 
513  return 1;
514 }
515 
516 static int bootloaderFillCurrentPage(serial_port_t* s, int* currentPage, int* currentOffset, int* totalBytes, int* verifyCheckSum)
517 {
518  if (*currentOffset < FLASH_PAGE_SIZE)
519  {
520  unsigned char hexData[256];
521  memset(hexData, 'F', 256);
522 
523  while (*currentOffset < FLASH_PAGE_SIZE)
524  {
525  int byteCount = (FLASH_PAGE_SIZE - *currentOffset) * 2;
526  if (byteCount > 256)
527  {
528  byteCount = 256;
529  }
530  memset(hexData, 'F', byteCount);
531 
532  if (bootloaderUploadHexDataPage(s, hexData, byteCount / 2, currentOffset, totalBytes, verifyCheckSum) == 0)
533  {
534  bootloader_perror(s, "Failed to fill page %d with %d bytes at offset %d\n", *currentPage, byteCount, *currentOffset);
535  return 0;
536  }
537  }
538  }
539 
540  return 1;
541 }
542 
543 static int bootloaderDownloadData(serial_port_t* s, int startOffset, int endOffset)
544 {
545  // Atmel download data command is 0x03, different from standard intel hex where command 0x03 is start segment address
546  unsigned char programLine[24];
547  int n;
548  n = bootloader_snprintf((char*)programLine, 24, ":0500000300%.4X%.4XCC", startOffset, endOffset);
549  programLine[n] = 0;
550  bootloaderChecksum(0, programLine, 1, 19, 19, 1);
551  if (serialPortWrite(s, programLine, 21) != 21)
552  {
553  bootloader_perror(s, "Failed to attempt download offsets %X to %X\n", startOffset, endOffset);
554  return 0;
555  }
556 
557  return 1;
558 }
559 
560 
561 static int bootloaderVerify(int lastPage, int checkSum, bootloader_state_t* state)
562 {
563  int verifyChunkSize = state->verifyChunkSize;
564  int chunkSize = bootloader_min(FLASH_PAGE_SIZE, verifyChunkSize);
565  int realCheckSum = 5381;
566  int totalCharCount = state->firstPageSkipBytes * 2;
567  int grandTotalCharCount = (lastPage + 1) * FLASH_PAGE_SIZE * 2; // char count
568  int i, pageOffset, readCount, actualPageOffset, pageChars, chunkIndex, lines;
569  int verifyByte = -1;
570  unsigned char chunkBuffer[(MAX_VERIFY_CHUNK_SIZE * 2) + 64]; // extra space for overhead
571  float percent = 0.0f;
572  unsigned char c=0;
573  FILE* verifyFile = 0;
574 
575  if (state->param->verifyFileName != 0)
576  {
577 
578 #ifdef _MSC_VER
579 
580  fopen_s(&verifyFile, state->param->verifyFileName, "wb");
581 
582 #else
583 
584  verifyFile = fopen(state->param->verifyFileName, "wb");
585 
586 #endif
587 
588  }
589 
590  for (i = 0; i <= lastPage; i++)
591  {
592  if (bootloaderSelectPage(state->param->port, i) == 0)
593  {
594  bootloader_perror(state->param->port, "Failure issuing select page command for verify\n");
595  return 0;
596  }
597  pageOffset = (i == 0 ? state->firstPageSkipBytes : 0);
598  while (pageOffset < FLASH_PAGE_SIZE)
599  {
600  readCount = bootloader_min(chunkSize, FLASH_PAGE_SIZE - pageOffset);
601 
602  // range is inclusive on the uINS, so subtract one
603  if (bootloaderDownloadData(state->param->port, pageOffset, pageOffset + readCount - 1) == 0)
604  {
605  bootloader_perror(state->param->port, "Failure issuing download data command\n");
606  return 0;
607  }
608 
609  // each line has 7 overhead bytes, plus two bytes (hex) for each byte on the page and max 255 bytes per line
610  lines = (int)ceilf((float)readCount / 255.0f);
611  readCount = serialPortReadTimeout(state->param->port, chunkBuffer, (7 * lines) + (readCount * 2), BOOTLOADER_TIMEOUT_DEFAULT);
612  chunkIndex = 0;
613 
614  while (chunkIndex < readCount)
615  {
616  if (chunkIndex > readCount - 5)
617  {
618  bootloader_perror(state->param->port, "Unexpected start line during validation\n");
619  return 0;
620  }
621 
622  // skip the first 5 chars, they are simply ####=
623  if (chunkBuffer[chunkIndex] == 'X')
624  {
625  bootloader_perror(state->param->port, "Invalid checksum during validation\n");
626  return 0;
627  }
628  else if (chunkBuffer[chunkIndex += 4] != '=')
629  {
630  bootloader_perror(state->param->port, "Unexpected start line during validation\n");
631  return 0;
632  }
633  chunkBuffer[chunkIndex] = '\0';
634  actualPageOffset = strtol((char*)(chunkBuffer + chunkIndex - 4), 0, 16);
635  if (actualPageOffset != pageOffset)
636  {
637  bootloader_perror(state->param->port, "Unexpected offset during validation\n");
638  return 0;
639  }
640  pageChars = 0;
641  chunkIndex++;
642  while (chunkIndex < readCount)
643  {
644  c = chunkBuffer[chunkIndex++];
645  if ((c >= '0' && c <= '9') || (c >= 'A' && c <= 'F'))
646  {
647  pageChars++;
648  totalCharCount++;
649  realCheckSum = ((realCheckSum << 5) + realCheckSum) + c;
650 
651  if (verifyFile != 0)
652  {
653  if (verifyByte == -1)
654  {
655  verifyByte = ((c >= '0' && c <= '9') ? c - '0' : c - 'A' + 10) << 4;
656  }
657  else
658  {
659  verifyByte |= (c >= '0' && c <= '9') ? c - '0' : c - 'A' + 10;
660  fputc(verifyByte, verifyFile);
661  verifyByte = -1;
662  }
663  }
664  }
665  else if (c == '\r')
666  {
667  continue;
668  }
669  else if (c == '\n')
670  {
671  break;
672  }
673  else
674  {
675  bootloader_perror(state->param->port, "Unexpected hex data during validation: 0x%02x [%c]\n", c, c);
676  return 0;
677  }
678  }
679 
680  if (c != '\n')
681  {
682  bootloader_perror(state->param->port, "Unexpected end line character found during validation: 0x%02x [%c]\n", c, c);
683  return 0;
684  }
685 
686  // increment page offset
687  pageOffset += (pageChars / 2);
688 
689  if (state->param->verifyProgress != 0)
690  {
691  percent = (float)totalCharCount / (float)grandTotalCharCount;
692  if (state->param->verifyProgress(state->param->obj, percent) == 0)
693  {
694  bootloader_perror(state->param->port, "Validate firmware cancelled\n");
695  return 0;
696  }
697  }
698  }
699  }
700  }
701 
702  if (verifyFile != 0)
703  {
704  fclose(verifyFile);
705  }
706 
707  if (realCheckSum != checkSum)
708  {
709  bootloader_perror(state->param->port, "Download checksum 0x%08x != calculated checksum 0x%08x\n", realCheckSum, checkSum);
710  return 0;
711  }
712 
713  return 1;
714 }
715 
716 
718 {
719 
720 #define BUFFER_SIZE 1024
721 
722  int currentPage = 0;
723  int currentOffset = state->firstPageSkipBytes;
724  int lastSubOffset = currentOffset;
725  int subOffset;
726  int totalBytes = state->firstPageSkipBytes;
727 
728  int verifyCheckSum = 5381;
729  int lineLength;
730  float percent = 0.0f;
731  char line[BUFFER_SIZE];
732  unsigned char output[BUFFER_SIZE * 2]; // big enough to store an entire extra line of buffer if needed
733  unsigned char* outputPtr = output;
734  const unsigned char* outputPtrEnd = output + (BUFFER_SIZE * 2);
735  int outputSize;
736  int page;
737  int pad;
738  int fileSize;
739  unsigned char tmp[5];
740  int i;
741 
742  fseek(file, 0, SEEK_END);
743  fileSize = ftell(file);
744  fseek(file, 0, SEEK_SET);
745 
746  while ((lineLength = bootloaderReadLine(file, line)) != 0)
747  {
748  if (lineLength > 12 && line[7] == '0' && line[8] == '0')
749  {
750  if (lineLength > BUFFER_SIZE * 4)
751  {
752  bootloader_perror(state->param->port, "Line length of %d was too large\n", lineLength);
753  return 0;
754  }
755 
756  // we need to know the offset that this line was supposed to be stored at so we can check if offsets are skipped
757  memcpy(tmp, line + 3, 4);
758  tmp[4] = '\0';
759  subOffset = strtol((char*)tmp, 0, 16);
760 
761  // check if we skipped an offset, the intel hex file format can do this, in which case we need to make sure
762  // that the bytes that were skipped get set to something
763  if (subOffset > lastSubOffset)
764  {
765  // pad with FF bytes, this is an internal implementation detail to how the device stores unused memory
766  pad = (subOffset - lastSubOffset);
767  if (outputPtr + pad >= outputPtrEnd)
768  {
769  bootloader_perror(state->param->port, "FF padding overflowed output buffer\n");
770  return 0;
771  }
772 
773  while (pad-- != 0)
774  {
775  *outputPtr++ = 'F';
776  *outputPtr++ = 'F';
777  }
778  }
779 
780  // skip the first 9 chars which are not data, then take everything else minus the last two chars which are a checksum
781  // check for overflow
782  pad = lineLength - 11;
783  if (outputPtr + pad >= outputPtrEnd)
784  {
785  bootloader_perror(state->param->port, "Line data overflowed output buffer\n");
786  return 0;
787  }
788 
789  for (i = 9; i < lineLength - 2; i++)
790  {
791  *outputPtr++ = line[i];
792  }
793 
794  // set the end offset so we can check later for skipped offsets
795  lastSubOffset = subOffset + ((lineLength - 11) / 2);
796  outputSize = (int)(outputPtr - output);
797 
798  // we try to send the most allowed by this hex file format
799  if (outputSize < MAX_SEND_COUNT)
800  {
801  // keep buffering
802  continue;
803  }
804 
805  // upload this chunk
806  else if (!bootloaderUploadHexData(state->param->port, output, (outputSize > MAX_SEND_COUNT ? MAX_SEND_COUNT : outputSize), &currentOffset, &currentPage, &totalBytes, &verifyCheckSum))
807  {
808  return 0;
809  }
810 
811  outputSize -= MAX_SEND_COUNT;
812 
813  if (outputSize < 0 || outputSize > BUFFER_SIZE)
814  {
815  bootloader_perror(state->param->port, "Output size of %d was too large\n", outputSize);
816  return 0;
817  }
818  else if (outputSize > 0)
819  {
820  // move the left-over data to the beginning
821  memmove(output, output + MAX_SEND_COUNT, outputSize);
822  }
823 
824  // reset output ptr back to the next chunk of data
825  outputPtr = output + outputSize;
826  }
827  else if (strncmp(line, ":020000048", 10) == 0 && strlen(line) >= 13)
828  {
829  memcpy(tmp, line + 10, 3);
830  tmp[3] = '\0';
831  page = strtol((char*)tmp, 0, 16);
832 
833  if (page != 0)
834  {
835  // we found a change page command beyond the first, let's finish up this page and fill it to the max
836  lastSubOffset = 0;
837  outputSize = (int)(outputPtr - output);
838 
839  if (outputSize < 0 || outputSize > BUFFER_SIZE)
840  {
841  bootloader_perror(state->param->port, "Output size of %d was too large\n", outputSize);
842  return 0;
843  }
844 
845  // flush the remainder of data to the page
846  else if (bootloaderUploadHexData(state->param->port, output, outputSize, &currentOffset, &currentPage, &totalBytes, &verifyCheckSum) == 0)
847  {
848  return 0;
849  }
850 
851  // fill the remainder of the current page, the next time that bytes try to be written the page will be automatically incremented
852  else if (bootloaderFillCurrentPage(state->param->port, &currentPage, &currentOffset, &totalBytes, &verifyCheckSum) == 0)
853  {
854  return 0;
855  }
856 
857  // set the output ptr back to the beginning, no more data is in the queue
858  outputPtr = output;
859  }
860  }
861 
862  if (state->param->uploadProgress != 0)
863  {
864  percent = (float)ftell(file) / (float)fileSize; // Dummy line to call ftell() once
865  percent = (float)ftell(file) / (float)fileSize;
866  if (state->param->uploadProgress(state->param->obj, percent) == 0)
867  {
868  bootloader_perror(state->param->port, "Upload firmware cancelled\n");
869  return 0;
870  }
871  }
872  }
873 
874  // upload any left over data
875  outputSize = (int)(outputPtr - output);
876  if (bootloaderUploadHexData(state->param->port, output, outputSize, &currentOffset, &currentPage, &totalBytes, &verifyCheckSum) == 0)
877  {
878  return 0;
879  }
880 
881  // pad the remainder of the page with fill bytes
882  if (currentOffset != 0 && bootloaderFillCurrentPage(state->param->port, &currentPage, &currentOffset, &totalBytes, &verifyCheckSum) == 0)
883  {
884  return 0;
885  }
886 
887  if (state->param->uploadProgress != 0 && percent != 1.0f)
888  {
889  state->param->uploadProgress(state->param->obj, 1.0f);
890  }
891 
892  if (state->param->flags.bitFields.enableVerify && state->param->verifyProgress != 0)
893  {
894  if (state->param->statusText)
895  state->param->statusText(state->param->obj, "Verifying flash...");
896 
897  if (state->param->verifyProgress != 0 && bootloaderVerify(currentPage, verifyCheckSum, state) == 0)
898  {
899  return 0;
900  }
901  }
902 
903  // send the "reboot to program mode" command and the device should start in program mode
904  if(state->param->statusText)
905  state->param->statusText(state->param->obj, "Rebooting unit...");
906  serialPortWrite(state->param->port, (unsigned char*)":020000040300F7", 15);
907  serialPortSleep(state->param->port, 250);
908 
909  return 1;
910 }
911 
913 {
914  bootloader_state_t state;
915  memset(&state, 0, sizeof(state));
916  unsigned char c;
917  int dataLength;
918  int verifyCheckSum;
919  int lastPage;
920  int commandCount;
921  int commandLength;
922  unsigned char buf[16];
923  unsigned char commandType;
924 
925  float percent = 0.0f;
926  fseek(file, 0, SEEK_END);
927  int fileSize = ftell(file);
928  fseek(file, 0, SEEK_SET);
929 
930  // verify checksum is first four bytes
931  verifyCheckSum = fgetc(file) | (fgetc(file) << 8) | (fgetc(file) << 16) | (fgetc(file) << 24);
932 
933  // last page is next two bytes
934  lastPage = fgetc(file) | (fgetc(file) << 8);
935 
936  // the file is formatted like this:
937  // 4 bytes : verify checksum
938  // 2 bytes : last page
939  // LOOP:
940  // 1 byte - command type (0 = data, 1 = raw)
941  // 2 bytes - number of commands
942  // n commands...
943  // Data command (0)
944  // 2 bytes : Offset
945  // 1 byte : Data Length
946  // n bytes : Data
947  // 1 byte : Checksum
948  // Raw command (1)
949  // 1 byte : Command length
950  // n bytes : Command characters
951  // 1 byte : wait for character, '\0' for none
952  // 1 byte : sleep time after command is sent, in 250 millisecond intervals, 0 for no sleep
953  // 1 byte : wait for character timeout time in 250 millisecond intervals, 0 for no wait
954  // if not EOF, go to LOOP
955 
956  while (ftell(file) != fileSize)
957  {
958  commandType = (unsigned char)fgetc(file);
959  commandCount = fgetc(file) | (fgetc(file) << 8);
960 
961  if (commandType == 0)
962  {
963  while (commandCount-- > 0)
964  {
965  // write the :, data length, offset and 00 (data command)
966  commandLength = (fgetc(file) | (fgetc(file) << 8));
967  dataLength = fgetc(file); // data length
968  bootloader_snprintf((char*)buf, 16, ":%.2X%.4X00", dataLength, commandLength);
969  serialPortWrite(p->port, buf, 9);
970 
971  // write the data - we use the fact that the checksum byte is after the data bytes to loop it in with this loop
972  while (dataLength-- > -1)
973  {
974  c = (unsigned char)fgetc(file);
975  buf[0] = hexLookupTable[(c >> 4) & 0x0F];
976  buf[1] = hexLookupTable[(c & 0x0F)];
977  serialPortWrite(p->port, buf, 2);
978  }
979 
980  serialPortWaitForTimeout(p->port, (unsigned char*)".\r\n", 3, BOOTLOADER_TIMEOUT_DEFAULT);
981 
982  if (p->uploadProgress != 0)
983  {
984  percent = (float)ftell(file) / (float)fileSize;
985  p->uploadProgress(p->obj, percent);
986  }
987  }
988  }
989  else if (commandType == 1)
990  {
991  // raw command, send it straight to the serial port as is
992  while (commandCount-- > 0)
993  {
994  commandLength = fgetc(file);
995  c = (unsigned char)fgetc(file);
996 
997  // handshake char, ignore
998  if (commandLength == 1 && c == 'U')
999  {
1000  // read sleep interval and timeout interval, ignored
1001  c = (unsigned char)fgetc(file);
1002  c = (unsigned char)fgetc(file);
1003  continue;
1004  }
1005 
1006  // write command to serial port
1007  serialPortWrite(p->port, &c, 1);
1008  while (--commandLength > 0)
1009  {
1010  c = (unsigned char)fgetc(file);
1011  serialPortWrite(p->port, &c, 1);
1012  }
1013 
1014  // read sleep interval and sleep
1015  c = (unsigned char)fgetc(file);
1016  commandLength = fgetc(file) * 250;
1017  if (commandLength != 0)
1018  {
1019  serialPortSleep(p->port, commandLength);
1020  }
1021 
1022  // read timeout interval
1023  commandLength = fgetc(file) * 250;
1024  if (commandLength != 0)
1025  {
1026  unsigned char waitFor[4];
1027  bootloader_snprintf((char*)waitFor, 4, "%c\r\n", c);
1028  serialPortWaitForTimeout(p->port, waitFor, 3, commandLength);
1029  }
1030  }
1031 
1032  if (p->uploadProgress != 0)
1033  {
1034  percent = (float)ftell(file) / (float)fileSize;
1035  p->uploadProgress(p->obj, percent);
1036  }
1037  }
1038  else
1039  {
1040  bootloader_perror(p->port, "Invalid data in .bin file\n");
1041  return 0;
1042  }
1043  }
1044 
1045  if (p->uploadProgress != 0 && percent != 1.0f)
1046  {
1047  p->uploadProgress(p->obj, 1.0f);
1048  }
1049 
1050  // re-purpose this variable for the return code
1051  dataLength = 1;
1052 
1053  if (state.param->flags.bitFields.enableVerify && state.param->verifyProgress != 0)
1054  {
1055  dataLength = bootloaderVerify(lastPage, verifyCheckSum, &state);
1056  }
1057 
1058  if (dataLength == 1)
1059  {
1060  // send the "reboot to program mode" command and the device should start in program mode
1061  serialPortWrite(state.param->port, (unsigned char*)":020000040300F7", 15);
1062  }
1063 
1064  serialPortSleep(state.param->port, 250);
1065 
1066  return dataLength;
1067 }
1068 
1070 {
1071  // USE WITH CAUTION! This will put in bootloader assist mode allowing a new bootloader to be put on, i.e. SAM-BA
1072 
1073  // restart bootloader assist command
1074  serialPortWrite(s, (unsigned char*)":020000040700F3", 15);
1075 
1076  // give the device time to start up
1078 }
1079 
1081 {
1082  // restart bootloader command
1083  serialPortWrite(s, (unsigned char*)":020000040500F5", 15);
1084 
1085  // give the device time to start up
1087 }
1088 
1090 {
1091  static const unsigned char handshakerChar = 'U';
1092 
1093  //Most usages of this function we do not know if we can communicate (still doing auto-baud or checking to see if the bootloader or application is running) so trying to reset unit here does not make sense.
1094  //This was probably added because the PC bootloader was doing multiple syncs in a row but the hardware bootloader only allowed one.
1095  //Will leave it just in case
1096  // reboot the device in case it is stuck
1097  bootloaderRestart(s);
1098 
1099  // write a 'U' to handshake with the boot loader - once we get a 'U' back we are ready to go
1100  for (int i = 0; i < BOOTLOADER_RETRIES; i++)
1101  {
1102  if (serialPortWriteAndWaitForTimeout(s, &handshakerChar, 1, &handshakerChar, 1, BOOTLOADER_RESPONSE_DELAY))
1103  {
1105  return 1;
1106  }
1107  }
1108 
1109  return 0;
1110 }
1111 
1113 {
1114  //Port should already be closed, but make sure
1115  serialPortClose(p->port);
1116 
1117 #if ENABLE_BOOTLOADER_BAUD_DETECTION
1118 
1119  // ensure that we start off with a valid baud rate
1120  if (p->baudRate == 0)
1121  {
1123  }
1124 
1125  // try handshaking at each baud rate
1126  for (unsigned int i = 0; i < _ARRAY_ELEMENT_COUNT(s_baudRateList) + 1; i++)
1127 
1128 #endif // ENABLE_BOOTLOADER_BAUD_DETECTION
1129 
1130  {
1132  {
1133  // can't open the port, fail
1134  return 0;
1135  }
1136  else if (bootloaderSync(p->port))
1137  {
1138  // success, reset baud rate for next round of handshaking
1139  p->baudRate = 0;
1140  return 1;
1141  }
1142 
1143 #if ENABLE_BOOTLOADER_BAUD_DETECTION
1144 
1145  // retry at a different baud rate
1146  serialPortClose(p->port);
1148 
1149 #endif // ENABLE_BOOTLOADER_BAUD_DETECTION
1150 
1151  }
1152 
1153  // failed to handshake, fatal error
1154  bootloader_perror(p->port, "Unable to handshake with bootloader\n");
1155  return 0;
1156 }
1157 
1158 static void bootloadGetVersion(serial_port_t* s, int* major, char* minor, int* sambaAvaliable)
1159 {
1160  //purge buffer
1161 #define BUF_SIZE 100
1162  unsigned char buf[BUF_SIZE];
1163  while (serialPortRead(s, buf, BUF_SIZE)){}
1164 
1165  //Send command
1166  serialPortWrite(s, (unsigned char*)":020000041000EA", 15);
1167 
1168  //Read Version, SAM-BA Available, and ok (.\r\n) response
1169  int count = serialPortReadTimeout(s, buf, 8, 1000);
1170 
1171  if (count != 8 || buf[0] != 0xAA || buf[1] != 0x55 || buf[5] != '.' || buf[6] != '\r' || buf[7] != '\n')
1172  {
1173  *major = 0;
1174  *minor = 0;
1175  *sambaAvaliable = 1;
1176  return;
1177  }
1178 
1179  *major = buf[2];
1180  *minor = buf[3];
1181  *sambaAvaliable = buf[4] == 0x1;
1182 }
1183 
1185 {
1186  if (p->statusText)
1187  p->statusText(p->obj, "Starting bootloader...");
1189  {
1190  //If we have an error, exit
1191  if (p->error[0] != 0)
1192  return 0;
1193 
1194  if (p->statusText)
1195  p->statusText(p->obj, "Unable to find bootloader.");
1196 
1197  if (p->bootName != 0)
1198  {
1199  if (p->statusText)
1200  p->statusText(p->obj, "Attempting to reload bootloader...");
1201 
1202  //Send file
1203  bootload_params_t params;
1204  memset(&params, 0, sizeof(params));
1205  params.fileName = p->bootName;
1206  params.port = p->port;
1207  memset(params.error, 0, sizeof(BOOTLOADER_ERROR_LENGTH));
1208  params.obj = p->obj;
1209  params.uploadProgress = p->uploadProgress;
1210  params.verifyProgress = p->verifyProgress;
1211  params.statusText = p->statusText;
1212  params.numberOfDevices = 1;
1213  params.flags.bitFields.enableVerify = 1;
1214 
1215  if (!bootloadUpdateBootloaderSendFile(&params))
1216  return 0;
1217 
1218  //Restart process now bootloader is updated
1219  SLEEP_MS(1000);
1220  return -1;
1221  }
1222 
1223  return 0;
1224  }
1225 
1226  // Sync with bootloader
1227  if (!bootloaderHandshake(p))
1228  {
1229  return 0;
1230  }
1231 
1232  int fileNameLength = (int)strnlen(p->fileName, 255);
1233  if (fileNameLength > 4 && strncmp(p->fileName + fileNameLength - 4, ".bin", 4) == 0)
1234  {
1235  //At this time, binary files are not supported for updating firmware
1236  bootloader_snprintf(p->error, BOOTLOADER_ERROR_LENGTH, "Binary firmware files are not supported.");
1237  return 0;
1238 
1239  // it's a .bin file, we will use a far more optimized and memory efficient uploader
1240  //return bootloaderProcessBinFile(file, p);
1241  }
1242  else
1243  {
1244 
1245 #if ENABLE_HEX_BOOT_LOADER
1246 
1247  bootloader_state_t state;
1248  memset(&state, 0, sizeof(state));
1249  state.param = p;
1250 
1251  if(!bootloaderNegotiateVersion(&state)) // negotiate version
1252  {
1253  return 0;
1254  }
1255 
1256  int blVerMajor, sambaSupport;
1257  char blVerMinor;
1258  bootloadGetVersion(p->port, &blVerMajor, &blVerMinor, &sambaSupport);
1259  if (blVerMajor > 0 && p->statusText)
1260  {
1261  char str[100];
1262  bootloader_snprintf(str, 100, "Bootloader version %d%c found. SAM-BA is %s on port.", blVerMajor, blVerMinor, sambaSupport == 1 ? "supported" : "NOT supported");
1263  p->statusText(p->obj, str);
1264  }
1265 
1266  if ((p->bootName != 0))
1267  {
1268  int fileVerMajor = 0;
1269  char fileVerMinor = 0;
1270  //Retrieve version from file
1271  //Only check if we find valid version info in file
1272  if (bootloadGetBootloaderVersionFromFile(p->bootName, &fileVerMajor, &fileVerMinor) || p->forceBootloaderUpdate > 0)
1273  {
1274  //printf("Bootloader file version: %d%c.\n", fileVerMajor, fileVerMinor);
1275 
1276  //Check bootloader version against file
1277  if (blVerMajor < fileVerMajor || blVerMinor < fileVerMinor || p->forceBootloaderUpdate > 0)
1278  {
1279  if (sambaSupport)
1280  {
1281  if (p->statusText)
1282  {
1283  char str[100];
1284  if(blVerMajor > 0)
1285  bootloader_snprintf(str, 100, "Updating bootloader to version %d%c...", fileVerMajor, fileVerMinor);
1286  else
1287  bootloader_snprintf(str, 100, "Updating bootloader...");
1288  p->statusText(p->obj, str);
1289  }
1290 
1291  //Start SAM-BA
1293 
1294  //Send file
1295  bootload_params_t params;
1296  memset(&params, 0, sizeof(params));
1297  params.fileName = p->bootName;
1298  params.port = p->port;
1299  memset(params.error, 0, sizeof(BOOTLOADER_ERROR_LENGTH));
1300  params.obj = p->obj;
1301  params.uploadProgress = p->uploadProgress;
1302  params.verifyProgress = p->verifyProgress;
1303  params.statusText = p->statusText;
1304  params.numberOfDevices = 1;
1305  params.flags.bitFields.enableVerify = 1;
1306 
1307  if (!bootloadUpdateBootloaderSendFile(&params))
1308  return 0;
1309 
1310  //Restart process now bootloader is updated
1311  SLEEP_MS(1000);
1312  return -1;
1313  }
1314  else
1315  { //Bootloader is out of date but SAM-BA is not supported on port
1316  if (p->statusText)
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.");
1318  bootloader_snprintf(p->error, BOOTLOADER_ERROR_LENGTH, "Bootloader is out of date but current port does not support updating bootloader. To force update, run firmware update without including the bootloader file.\n");
1319  return 0;
1320  }
1321  }
1322  }
1323  }
1324 
1325  if (p->statusText)
1326  p->statusText(p->obj, "Erasing flash...");
1327  if ( !bootloaderEraseFlash(p->port) /*erase all flash */ || !bootloaderSelectPage(p->port, 0) /*select the first page*/)
1328  return 0;
1329 
1330 
1331  if (p->statusText)
1332  p->statusText(p->obj, "Programming flash...");
1333  // begin programming the first page
1335  return 0;
1336 
1337  return bootloaderProcessHexFile(file, &state);
1338 
1339 #else
1340 
1341  bootloader_snprintf(lastError, ERROR_BUFFER_SIZE, "Hex bootloader is disabled");
1342  return 0;
1343 
1344 #endif
1345 
1346  }
1347 }
1348 
1349 static int samBaWriteWord(serial_port_t* port, uint32_t address, uint32_t value)
1350 {
1351  unsigned char buf[32];
1352  int count = SNPRINTF((char*)buf, sizeof(buf), "W%08x,%08x#", address, value);
1353  return (serialPortWrite(port, buf, count) == count);
1354 }
1355 
1356 static uint32_t samBaReadWord(serial_port_t* port, uint32_t address)
1357 {
1358  unsigned char buf[16];
1359  int count = SNPRINTF((char*)buf, sizeof(buf), "w%08x,#", address);
1360  if (serialPortWrite(port, buf, count) == count &&
1361  (serialPortReadTimeout(port, buf, sizeof(uint32_t), BOOTLOADER_TIMEOUT_DEFAULT)) == sizeof(uint32_t))
1362  {
1363  uint32_t val = (buf[3] << 24) | (buf[2] << 16) | (buf[1] << 8) | buf[0];
1364  return val;
1365  }
1366  return 0;
1367 }
1368 
1370 {
1371  uint32_t status = 0;
1372  for (int i = 0; i < 10; i++)
1373  {
1374  status = samBaReadWord(port, 0x400e0c08);
1375  if (status & 1)
1376  {
1377  break;
1378  }
1379  serialPortSleep(port, 20);
1380  }
1381  return status;
1382 }
1383 
1385 {
1386  // EEFC_FCR, EEFC_FCR_FKEY_PASSWD | EEFC_FCR_FARG_BOOT | EEFC_FCR_FCMD_SGPB
1387  if (samBaWriteWord(port, 0x400e0c04, 0x5a000000 | 0x00000100 | 0x0000000b))
1388  {
1389  return (int)samBaFlashWaitForReady(port);
1390  }
1391  return 0;
1392 }
1393 
1394 static int samBaFlashEraseWritePage(serial_port_t* port, size_t offset,
1395  unsigned char buf[SAM_BA_FLASH_PAGE_SIZE], int isUSB)
1396 {
1397  uint16_t page = (uint16_t)(offset / SAM_BA_FLASH_PAGE_SIZE);
1398  unsigned char _buf[32];
1399  int count;
1400 
1401  // start lots of data
1402  if (isUSB)
1403  {
1404  count = SNPRINTF((char*)_buf, sizeof(_buf), "S%08x,%08x#",
1405  (unsigned int)(SAM_BA_FLASH_START_ADDRESS + offset),
1406  (unsigned int)SAM_BA_FLASH_PAGE_SIZE);
1407  serialPortWrite(port, _buf, count);
1408  serialPortWrite(port, buf, SAM_BA_FLASH_PAGE_SIZE);
1409  }
1410  else
1411  {
1412  count = SNPRINTF((char*)_buf, sizeof(_buf), "S%08x,#", (unsigned int)(SAM_BA_FLASH_START_ADDRESS + offset));
1413  serialPortWrite(port, _buf, count);
1414 
1415  // send page data
1416  if (xModemSend(port, buf, SAM_BA_FLASH_PAGE_SIZE))
1417  {
1418  return 0;
1419  }
1420  }
1421 
1422  // EEFC FCR: finish write page
1423  count = SNPRINTF((char*)_buf, sizeof(_buf), "W%08x,5a%04x03#", 0x400e0c04, page);
1424  serialPortWrite(port, _buf, count);
1425  return samBaFlashWaitForReady(port);
1426 }
1427 
1428 static int samBaVerify(serial_port_t* port, uint32_t checksum, const void* obj, pfnBootloadProgress verifyProgress)
1429 {
1430  uint32_t checksum2 = 0;
1431  uint32_t nextAddress;
1432  unsigned char buf[512];
1433  int count;
1434 
1435  for (uint32_t address = SAM_BA_FLASH_START_ADDRESS; address < (SAM_BA_FLASH_START_ADDRESS + SAM_BA_BOOTLOADER_SIZE); )
1436  {
1437  nextAddress = address + SAM_BA_FLASH_PAGE_SIZE;
1438  while (address < nextAddress)
1439  {
1440  count = SNPRINTF((char*)buf, sizeof(buf), "w%08x,#", address);
1441  serialPortWrite(port, buf, count);
1442  address += sizeof(uint32_t);
1443  serialPortSleep(port, 2); // give device time to process command
1444  }
1445  count = serialPortReadTimeout(port, buf, SAM_BA_FLASH_PAGE_SIZE, BOOTLOADER_TIMEOUT_DEFAULT);
1446  if (count == SAM_BA_FLASH_PAGE_SIZE)
1447  {
1448  for (uint32_t* ptr = (uint32_t*)buf, *ptrEnd = (uint32_t*)(buf + sizeof(buf)); ptr < ptrEnd; ptr++)
1449  {
1450  checksum2 ^= *ptr;
1451  }
1452  }
1453  else
1454  {
1455  return -1;
1456  }
1457  if (verifyProgress != 0)
1458  {
1459  verifyProgress(obj, (float)(address - SAM_BA_FLASH_START_ADDRESS) / (float)SAM_BA_BOOTLOADER_SIZE);
1460  }
1461  }
1462  if (checksum != checksum2)
1463  {
1464  return -2;
1465  }
1466  return 0;
1467 }
1468 
1470 {
1471  // RSTC_CR, RSTC_CR_KEY_PASSWD | RSTC_CR_PROCRST
1472  uint32_t status;
1473  if (!samBaWriteWord(port, 0x400e1800, 0xa5000000 | 0x00000001))
1474  {
1475  return 0;
1476  }
1477  for (int i = 0; i < 100; i++)
1478  {
1479  status = samBaReadWord(port, 0x400e1804); // RSTC_SR
1480  if (!(status & 0x00020000)) // RSTC_SR_SRCMP
1481  {
1482  return 1;
1483  }
1484  serialPortSleep(port, 20);
1485  }
1486  return 0;
1487 }
1488 
1489 int bootloadFile(serial_port_t* port, const char* fileName, const char * bootName,
1490  const void* obj, pfnBootloadProgress uploadProgress, pfnBootloadProgress verifyProgress)
1491 {
1492  bootload_params_t params;
1493  memset(&params, 0, sizeof(params));
1494  params.fileName = fileName;
1495  params.bootName = bootName;
1496  params.forceBootloaderUpdate = 0;
1497  params.port = port;
1498  memset(params.error, 0, sizeof(BOOTLOADER_ERROR_LENGTH));
1499  params.obj = obj;
1500  params.uploadProgress = uploadProgress;
1501  params.verifyProgress = verifyProgress;
1502  params.numberOfDevices = 1;
1503  params.flags.bitFields.enableVerify = (verifyProgress != 0);
1504 
1505  return bootloadFileEx(&params);
1506 }
1507 
1509 {
1510  if (strstr(params->fileName, "EVB") != NULL)
1511  { // Enable EVB bootloader
1512  strncpy(params->bootloadEnableCmd, "EBLE", 4);
1513  }
1514  else
1515  { // Enable uINS bootloader
1516  strncpy(params->bootloadEnableCmd, "BLEN", 4);
1517  }
1518 
1519  int result = 0;
1520 
1521  if (params->error != 0 && BOOTLOADER_ERROR_LENGTH > 0)
1522  {
1523  *params->error = '\0';
1524  }
1525 
1526 
1527  // open the file
1528  FILE* file = 0;
1529 
1530 #ifdef _MSC_VER
1531 
1532  fopen_s(&file, params->fileName, "rb");
1533 
1534 #else
1535 
1536  file = fopen(params->fileName, "rb");
1537 
1538 #endif
1539 
1540  if (file == 0)
1541  {
1542  if (params->error != 0)
1543  {
1544  bootloader_snprintf(params->error, BOOTLOADER_ERROR_LENGTH, "Unable to open file: %s", params->fileName);
1545  }
1546  return result;
1547  }
1548 
1549  // If bootloader file was specified, check it is openable
1550  if (params->bootName && params->bootName[0] != 0)
1551  {
1552  FILE* blfile = 0;
1553 
1554 #ifdef _MSC_VER
1555 
1556  fopen_s(&blfile, params->bootName, "rb");
1557 
1558 #else
1559 
1560  blfile = fopen(params->bootName, "rb");
1561 
1562 #endif
1563  if (blfile == 0)
1564  {
1565  bootloader_snprintf(params->error, BOOTLOADER_ERROR_LENGTH, "Unable to open bootloader file: %s", params->bootName);
1566  return result;
1567  }
1568 
1569  fclose(blfile);
1570  }
1571 
1572  result = bootloadFileInternal(file, params);
1573 
1574  //Restart if we updated bootloader
1575  if (result == -1)
1576  {
1577  params->forceBootloaderUpdate = 0;
1578  result = bootloadFileInternal(file, params);
1579  }
1580 
1581  if (result == 0)
1582  {
1583  // reboot the device back into boot-loader mode
1584  serialPortWrite(params->port, (unsigned char*)":020000040500F5", 15);
1585  serialPortSleep(params->port, 500);
1586  }
1587 
1588  fclose(file);
1589  serialPortClose(params->port);
1590 
1591  return result;
1592 }
1593 
1594 int bootloadGetBootloaderVersionFromFile(const char* bootName, int* verMajor, char* verMinor)
1595 {
1596  FILE* blfile = 0;
1597 
1598 #ifdef _MSC_VER
1599 
1600  fopen_s(&blfile, bootName, "rb");
1601 
1602 #else
1603 
1604  blfile = fopen(bootName, "rb");
1605 
1606 #endif
1607 
1608  if (blfile == 0)
1609  return 0;
1610 
1611  fseek(blfile, 0x3DFC, SEEK_SET);
1612  unsigned char ver_info[4];
1613  size_t n = fread(ver_info, 1, 4, blfile);
1614  (void)n;
1615  fclose(blfile);
1616 
1617  //Check for marker for valid version info
1618  if (ver_info[0] == 0xAA && ver_info[1] == 0x55)
1619  {
1620  if (verMajor)
1621  *verMajor = ver_info[2];
1622  if (verMinor)
1623  *verMinor = ver_info[3];
1624  return 1;
1625  }
1626 
1627  //No version found
1628  return 0;
1629 }
1630 
1631 int bootloadUpdateBootloader(serial_port_t* port, const char* fileName,
1632  const void* obj, pfnBootloadProgress uploadProgress, pfnBootloadProgress verifyProgress)
1633 {
1634  bootload_params_t params;
1635  memset(&params, 0, sizeof(params));
1636  params.fileName = fileName;
1637  params.port = port;
1638  memset(params.error, 0, sizeof(BOOTLOADER_ERROR_LENGTH));
1639  params.obj = obj;
1640  params.uploadProgress = uploadProgress;
1641  params.verifyProgress = verifyProgress;
1642  params.numberOfDevices = 1;
1643  params.flags.bitFields.enableVerify = (verifyProgress != 0);
1644 
1645  return bootloadUpdateBootloaderEx(&params);
1646 }
1647 
1649 {
1650  //Setup serial port for correct baud rate
1651  serialPortClose(p->port);
1652  if (!serialPortOpenRetry(p->port, p->port->port, BAUDRATE_115200, 1))
1653  {
1654  bootloader_perror(p, "Failed to open port.\n");
1655  serialPortClose(p->port);
1656  return 0;
1657  }
1658 
1659  // https://github.com/atmelcorp/sam-ba/tree/master/src/plugins/connection/serial
1660  // https://sourceforge.net/p/lejos/wiki-nxt/SAM-BA%20Protocol/
1661  unsigned char buf[SAM_BA_FLASH_PAGE_SIZE];
1662  uint32_t checksum = 0;
1663 
1664  // try non-USB and then USB mode (0 and 1)
1665  for (int isUSB = 0; isUSB < 2; isUSB++)
1666  {
1667  serialPortSleep(p->port, 250);
1668  serialPortClose(p->port);
1669  if (!serialPortOpenRetry(p->port, p->port->port, SAM_BA_BAUDRATE, 1))
1670  {
1671  bootloader_perror(p, "Failed to open port.\n");
1672  serialPortClose(p->port);
1673  return 0;
1674  }
1675 
1676  // flush
1677  serialPortWrite(p->port, (void*)"#", 2);
1678  int count = serialPortReadTimeout(p->port, buf, sizeof(buf), 100);
1679 
1680  // non-interactive mode
1681  count = serialPortWriteAndWaitFor(p->port, (void*)"N#", 2, (void*)"\n\r", 2);
1682  if (!count)
1683  {
1684  bootloader_perror(p, "Failed to handshake with SAM-BA\n");
1685  serialPortClose(p->port);
1686  return 0;
1687  }
1688 
1689  // set flash mode register
1690  serialPortWrite(p->port, (const unsigned char*)"W400e0c00,04000600#", 19);
1691 
1692  FILE* file;
1693 
1694 #ifdef _MSC_VER
1695 
1696  fopen_s(&file, p->fileName, "rb");
1697 
1698 #else
1699 
1700  file = fopen(p->fileName, "rb");
1701 
1702 #endif
1703 
1704  if (file == 0)
1705  {
1706  bootloader_perror(p, "Unable to load bootloader file\n");
1707  serialPortClose(p->port);
1708  return 0;
1709  }
1710 
1711  fseek(file, 0, SEEK_END);
1712  int size = ftell(file);
1713  fseek(file, 0, SEEK_SET);
1714  checksum = 0;
1715 
1716  if (size != SAM_BA_BOOTLOADER_SIZE)
1717  {
1718  bootloader_perror(p, "Invalid bootloader file\n");
1719  serialPortClose(p->port);
1720  return 0;
1721  }
1722 
1723  if (p->statusText)
1724  p->statusText(p->obj, "Writing bootloader...");
1725 
1726  uint32_t offset = 0;
1727  while (fread(buf, 1, SAM_BA_FLASH_PAGE_SIZE, file) == SAM_BA_FLASH_PAGE_SIZE)
1728  {
1729  if (!samBaFlashEraseWritePage(p->port, offset, buf, isUSB))
1730  {
1731  if (!isUSB)
1732  {
1733  offset = 0;
1734  break; // try USB mode
1735  }
1736  bootloader_perror(p, "Failed to upload page at offset %d\n", (int)offset);
1737  serialPortClose(p->port);
1738  return 0;
1739  }
1740  for (uint32_t* ptr = (uint32_t*)buf, *ptrEnd = (uint32_t*)(buf + sizeof(buf)); ptr < ptrEnd; ptr++)
1741  {
1742  checksum ^= *ptr;
1743  }
1744  offset += SAM_BA_FLASH_PAGE_SIZE;
1745  if (p->uploadProgress != 0)
1746  {
1747  p->uploadProgress(p->obj, (float)offset / (float)SAM_BA_BOOTLOADER_SIZE);
1748  }
1749  }
1750  fclose(file);
1751  if (offset != 0)
1752  {
1753  break; // success!
1754  }
1755  }
1756 
1757  if (p->verifyProgress != 0)
1758  {
1759  if (p->statusText)
1760  p->statusText(p->obj, "Verifying bootloader...");
1761 
1762  switch (samBaVerify(p->port, checksum, p->obj, p->verifyProgress))
1763  {
1764  case -1: bootloader_perror(p, "Flash read error\n"); return 0;
1765  case -2: bootloader_perror(p, "Flash checksum error\n"); return 0;
1766  }
1767  }
1768 
1769  if (!samBaSetBootFromFlash(p->port))
1770  {
1771  bootloader_perror(p, "Failed to set boot from flash GPNVM bit\n");
1772  serialPortClose(p->port);
1773  return 0;
1774  }
1775 
1776  if (!samBaSoftReset(p->port))
1777  {
1778  bootloader_perror(p, "Failed to reset device\n");
1779  serialPortClose(p->port);
1780  return 0;
1781  }
1782 
1783  serialPortClose(p->port);
1784  return 1;
1785 }
1786 
1788 {
1789  strncpy(p->bootloadEnableCmd, "NELB,!!SAM-BA!!\0", 16);
1791  serialPortSleep(p->port, 250);
1792  serialPortClose(p->port);
1793 
1794  //Send command to enter SAM-BA mode across different baud rates
1796  {
1797  bootloader_perror(p, "Failed to open port.\n");
1798  serialPortClose(p->port);
1799  return 0;
1800  }
1802  serialPortSleep(p->port, 250);
1803 
1804  if (!serialPortOpenRetry(p->port, p->port->port, BAUDRATE_921600, 1))
1805  {
1806  bootloader_perror(p, "Failed to open port.\n");
1807  serialPortClose(p->port);
1808  return 0;
1809  }
1811  serialPortSleep(p->port, 250);
1812 
1813  if (!serialPortOpenRetry(p->port, p->port->port, BAUDRATE_460800, 1))
1814  {
1815  bootloader_perror(p, "Failed to open port.\n");
1816  serialPortClose(p->port);
1817  return 0;
1818  }
1820  serialPortSleep(p->port, 250);
1821 
1822  if (!serialPortOpenRetry(p->port, p->port->port, BAUDRATE_230400, 1))
1823  {
1824  bootloader_perror(p, "Failed to open port.\n");
1825  serialPortClose(p->port);
1826  return 0;
1827  }
1829  serialPortSleep(p->port, 250);
1830 
1831  serialPortClose(p->port);
1832  if (!serialPortOpenRetry(p->port, p->port->port, BAUDRATE_115200, 1))
1833  {
1834  bootloader_perror(p, "Failed to open port.\n");
1835  serialPortClose(p->port);
1836  return 0;
1837  }
1839 
1840  //Should be in SAM-BA mode, start sending data
1842 }
1843 
1844 int enableBootloader(serial_port_t* port, int baudRate, char* error, int errorLength, const char* bootloadEnableCmd)
1845 {
1847 
1848  // detect if device is already in bootloader mode
1850  memset(&p, 0, sizeof(p));
1851  p.port = port;
1852  p.baudRate = bootloaderClosestBaudRate(baudRate);
1853 
1854  // attempt to handshake in case we are in bootloader mode
1855  //When we handshake with legacy bootloader baudrate it prevents us from entering the bootloader when the uINS is running its firmware.
1856  //Instead of checking for the bootloader first, we will send the command to enter the bootloader without checking.
1857  //After the command is sent, it will try to handsake again and will find the bootloader even if the bootloader is alreay running before sending the command to enter.
1858  //if (!bootloaderHandshake(&p))
1859  {
1860  // in case we are in program mode, try and send the commands to go into bootloader mode
1861  unsigned char c = 0;
1862  for (size_t i = 0; i < _ARRAY_ELEMENT_COUNT(baudRates); i++)
1863  {
1864  if (baudRates[i] == 0)
1865  continue;
1866 
1867  serialPortClose(port);
1868  if (serialPortOpenInternal(port, baudRates[i], error, errorLength) == 0)
1869  {
1870  serialPortClose(port);
1871  return 0;
1872  }
1873  for (size_t loop = 0; loop < 10; loop++)
1874  {
1875  serialPortWriteAscii(port, "STPB", 4);
1876  serialPortWriteAscii(port, bootloadEnableCmd, 4);
1877  c = 0;
1878  if (serialPortReadCharTimeout(port, &c, 13) == 1)
1879  {
1880  if (c == '$')
1881  {
1882  // done, we got into bootloader mode
1883  i = 9999;
1884  break;
1885  }
1886  }
1887  else
1888  {
1889  serialPortFlush(port);
1890  }
1891  }
1892  }
1893 
1894  serialPortClose(port);
1896 
1897  // if we can't handshake at this point, bootloader enable has failed
1898  if (!bootloaderHandshake(&p))
1899  {
1900  // failure
1901  serialPortClose(port);
1902  return 0;
1903  }
1904  }
1905 
1906  // ensure bootloader restarts in fresh state
1907  bootloaderRestart(port);
1908 
1909  // by this point the bootloader should be enabled
1910  serialPortClose(port);
1911  return 1;
1912 }
1913 
1914 static int disableBootloaderInternal(serial_port_t* port, char* error, int errorLength, int baud)
1915 {
1916  // open the serial port
1917  if (serialPortOpenInternal(port, baud, error, errorLength) == 0)
1918  {
1919  return 0;
1920  }
1921 
1922  // send the "reboot to program mode" command and the device should start in program mode
1923  serialPortWrite(port, (unsigned char*)":020000040300F7", 15);
1924  serialPortSleep(port, 250);
1925  serialPortClose(port);
1926  return 1;
1927 }
1928 
1929 
1930 int disableBootloader(serial_port_t* port, char* error, int errorLength)
1931 {
1932  int result = 0;
1933  result |= disableBootloaderInternal(port, error, errorLength, IS_BAUD_RATE_BOOTLOADER);
1934  result |= disableBootloaderInternal(port, error, errorLength, IS_BAUD_RATE_BOOTLOADER_RS232);
1935  result |= disableBootloaderInternal(port, error, errorLength, IS_BAUD_RATE_BOOTLOADER_SLOW);
1936  return result;
1937 }
#define _MIN(a, b)
Definition: ISConstants.h:298
static int bootloaderProcessHexFile(FILE *file, bootloader_state_t *state)
#define CRC_POLY
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)
#define SAM_BA_BAUDRATE
static int bootloadFileInternal(FILE *file, bootload_params_t *p)
int serialPortOpenRetry(serial_port_t *serialPort, const char *port, int baudRate, int blocking)
Definition: serialPort.c:37
#define X_NAK
bootload_params_t param
static int bootloaderSelectPage(serial_port_t *s, int page)
int serialPortReadTimeout(serial_port_t *serialPort, unsigned char *buffer, int readCount, int timeoutMilliseconds)
Definition: serialPort.c:89
int serialPortWriteAndWaitFor(serial_port_t *serialPort, const unsigned char *buffer, int writeCount, const unsigned char *waitFor, int waitForLength)
Definition: serialPort.c:281
static void bootloaderRestart(serial_port_t *s)
#define BOOTLOADER_REFRESH_DELAY
static int serialPortOpenInternal(serial_port_t *s, int baudRate, char *error, int errorLength)
#define BAUDRATE_230400
Definition: serialPort.h:39
static uint32_t samBaReadWord(serial_port_t *port, uint32_t address)
static void bootloaderRestartAssist(serial_port_t *s)
not_this_one end(...)
uint8_t payload[XMODEM_PAYLOAD_SIZE]
#define X_ACK
GeneratorWrapper< T > value(T &&value)
Definition: catch.hpp:3589
GeneratorWrapper< std::vector< T > > chunk(size_t size, GeneratorWrapper< T > &&generator)
Definition: catch.hpp:3900
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)
#define BAUDRATE_115200
Definition: serialPort.h:38
size_t count(InputIterator first, InputIterator last, T const &item)
Definition: catch.hpp:3206
static int samBaVerify(serial_port_t *port, uint32_t checksum, const void *obj, pfnBootloadProgress verifyProgress)
int bootloaderCycleBaudRate(int baudRate)
#define PUSH_PACK_1
Definition: ISConstants.h:231
#define NULL
Definition: nm_bsp.h:52
#define IS_BAUD_RATE_BOOTLOADER_SLOW
#define SWAP16(v)
Definition: ISConstants.h:265
#define BAUDRATE_460800
Definition: serialPort.h:40
#define SLEEP_MS(timeMs)
Definition: ISUtilities.h:134
#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)
#define MAX_SEND_COUNT
int bootloaderClosestBaudRate(int baudRate)
#define X_EOT
static int samBaSoftReset(serial_port_t *port)
char port[MAX_SERIAL_PORT_NAME_LENGTH+1]
Definition: serialPort.h:70
#define IS_BAUD_RATE_BOOTLOADER_RS232
static int bootloaderDownloadData(serial_port_t *s, int startOffset, int endOffset)
#define bootloader_snprintf
char * error
Definition: serialPort.h:73
static int bootloaderProcessBinFile(FILE *file, bootload_params_t *p)
int serialPortWaitForTimeout(serial_port_t *serialPort, const unsigned char *waitFor, int waitForLength, int timeoutMilliseconds)
Definition: serialPort.c:308
pfnBootloadProgress uploadProgress
int serialPortWriteAndWaitForTimeout(serial_port_t *serialPort, const unsigned char *buffer, int writeCount, const unsigned char *waitFor, int waitForLength, const int timeoutMilliseconds)
Definition: serialPort.c:286
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)
Definition: serialPort.c:66
#define IS_BAUD_RATE_BOOTLOADER_LEGACY
#define MAX_VERIFY_CHUNK_SIZE
pfnBootloadStatus statusText
#define BUF_SIZE
int serialPortWrite(serial_port_t *serialPort, const unsigned char *buffer, int writeCount)
Definition: serialPort.c:201
int(* pfnBootloadProgress)(const void *obj, float percent)
#define BAUDRATE_3000000
Definition: serialPort.h:47
#define bootloader_min(a, b)
#define bootloader_perror(s,...)
static const unsigned char hexLookupTable[16]
#define SNPRINTF
Definition: ISConstants.h:146
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 EOF
Definition: ff.h:241
#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)
#define POP_PACK
Definition: ISConstants.h:234
static int bootloaderVerify(int lastPage, int checkSum, bootloader_state_t *state)
#define X_SOH
int serialPortReadChar(serial_port_t *serialPort, unsigned char *c)
Definition: serialPort.c:191
int serialPortReadCharTimeout(serial_port_t *serialPort, unsigned char *c, int timeoutMilliseconds)
Definition: serialPort.c:196
#define BOOTLOADER_TIMEOUT_DEFAULT
#define X_CAN
#define IS_BAUD_RATE_BOOTLOADER
static int xModemSend(serial_port_t *s, uint8_t *buf, size_t len)
int serialPortFlush(serial_port_t *serialPort)
Definition: serialPort.c:75
static int bootloaderHandshake(bootload_params_t *p)
static int samBaWriteWord(serial_port_t *port, uint32_t address, uint32_t value)
#define BAUDRATE_921600
Definition: serialPort.h:41
int serialPortWriteAscii(serial_port_t *serialPort, const char *buffer, int bufferLength)
Definition: serialPort.c:230
#define BUFFER_SIZE
static uint16_t crc_update(uint16_t crc_in, int incr)
#define _ARRAY_ELEMENT_COUNT(a)
Definition: ISConstants.h:326
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)
Definition: serialPort.c:84
#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)
Definition: serialPort.c:349
#define FLASH_PAGE_SIZE


inertial_sense_ros
Author(s):
autogenerated on Sun Feb 28 2021 03:17:57