#include <stdio.h>#include <math.h>#include "inertialSenseBootLoader.h"#include "ISConstants.h"#include "ISUtilities.h"
Go to the source code of this file.
Classes | |
| struct | bootloader_state_t |
| struct | xmodem_chunk_t |
Macros | |
| #define | bootloader_max(a, b) (a > b ? a : b) |
| #define | bootloader_min(a, b) (a < b ? a : b) |
| #define | bootloader_perror(s, ...) |
| #define | bootloader_snprintf snprintf |
| #define | BOOTLOADER_TIMEOUT_DEFAULT 1000 |
| #define | BUF_SIZE 100 |
| #define | BUFFER_SIZE 1024 |
| #define | CRC_POLY 0x1021 |
| #define | ENABLE_HEX_BOOT_LOADER 1 |
| #define | FLASH_PAGE_SIZE 65536 |
| #define | MAX_SEND_COUNT 510 |
| #define | MAX_VERIFY_CHUNK_SIZE 1024 |
| #define | SAM_BA_BAUDRATE 115200 |
| #define | SAM_BA_BOOTLOADER_SIZE 16384 |
| #define | SAM_BA_FLASH_PAGE_SIZE 512 |
| #define | SAM_BA_FLASH_START_ADDRESS 0x00400000 |
| #define | X_ACK 0x06 |
| #define | X_CAN 0x18 |
| #define | X_EOT 0x04 |
| #define | X_NAK 0x15 |
| #define | X_SOH 0x01 |
| #define | XMODEM_PAYLOAD_SIZE 128 |
Functions | |
| static int | bootloaderBeginProgramForCurrentPage (serial_port_t *s, int startOffset, int endOffset) |
| static int | bootloaderChecksum (int checkSum, unsigned char *ptr, int start, int end, int checkSumPosition, int finalCheckSum) |
| int | bootloaderClosestBaudRate (int baudRate) |
| int | bootloaderCycleBaudRate (int baudRate) |
| static int | bootloaderDownloadData (serial_port_t *s, int startOffset, int endOffset) |
| static int | bootloaderEraseFlash (serial_port_t *s) |
| static int | bootloaderFillCurrentPage (serial_port_t *s, int *currentPage, int *currentOffset, int *totalBytes, int *verifyCheckSum) |
| static int | bootloaderHandshake (bootload_params_t *p) |
| static int | bootloaderNegotiateVersion (bootloader_state_t *state) |
| static int | bootloaderProcessBinFile (FILE *file, bootload_params_t *p) |
| static int | bootloaderProcessHexFile (FILE *file, bootloader_state_t *state) |
| static int | bootloaderReadLine (FILE *file, char line[1024]) |
| static void | bootloaderRestart (serial_port_t *s) |
| static void | bootloaderRestartAssist (serial_port_t *s) |
| static int | bootloaderSelectPage (serial_port_t *s, int page) |
| static int | bootloaderSync (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 int | bootloaderUploadHexDataPage (serial_port_t *s, unsigned char *hexData, int byteCount, int *currentOffset, int *totalBytes, int *verifyCheckSum) |
| static int | bootloaderVerify (int lastPage, int checkSum, bootloader_state_t *state) |
| int | bootloadFile (serial_port_t *port, const char *fileName, const char *bootName, const void *obj, pfnBootloadProgress uploadProgress, pfnBootloadProgress verifyProgress) |
| int | bootloadFileEx (bootload_params_t *params) |
| static int | bootloadFileInternal (FILE *file, bootload_params_t *p) |
| int | bootloadGetBootloaderVersionFromFile (const char *bootName, int *verMajor, char *verMinor) |
| static void | bootloadGetVersion (serial_port_t *s, int *major, char *minor, int *sambaAvaliable) |
| int | bootloadUpdateBootloader (serial_port_t *port, const char *fileName, const void *obj, pfnBootloadProgress uploadProgress, pfnBootloadProgress verifyProgress) |
| int | bootloadUpdateBootloaderEx (bootload_params_t *p) |
| static int | bootloadUpdateBootloaderSendFile (bootload_params_t *p) |
| static uint16_t | crc16 (uint8_t *data, uint16_t size) |
| static uint16_t | crc_update (uint16_t crc_in, int incr) |
| int | disableBootloader (serial_port_t *port, char *error, int errorLength) |
| static int | disableBootloaderInternal (serial_port_t *port, char *error, int errorLength, int baud) |
| int | enableBootloader (serial_port_t *port, int baudRate, char *error, int errorLength, const char *bootloadEnableCmd) |
| static int | samBaFlashEraseWritePage (serial_port_t *port, size_t offset, unsigned char buf[SAM_BA_FLASH_PAGE_SIZE], int isUSB) |
| static uint32_t | samBaFlashWaitForReady (serial_port_t *port) |
| static uint32_t | samBaReadWord (serial_port_t *port, uint32_t address) |
| static int | samBaSetBootFromFlash (serial_port_t *port) |
| static int | samBaSoftReset (serial_port_t *port) |
| static int | samBaVerify (serial_port_t *port, uint32_t checksum, const void *obj, pfnBootloadProgress verifyProgress) |
| static int | samBaWriteWord (serial_port_t *port, uint32_t address, uint32_t value) |
| static int | serialPortOpenInternal (serial_port_t *s, int baudRate, char *error, int errorLength) |
| static int | xModemSend (serial_port_t *s, uint8_t *buf, size_t len) |
Variables | |
| static const unsigned char | hexLookupTable [16] = { '0', '1', '2', '3', '4', '5', '6', '7', '8', '9', 'A', 'B', 'C', 'D', 'E', 'F' } |
| static const int | s_baudRateList [] = { IS_BAUD_RATE_BOOTLOADER, IS_BAUD_RATE_BOOTLOADER_LEGACY, IS_BAUD_RATE_BOOTLOADER_RS232, IS_BAUD_RATE_BOOTLOADER_SLOW } |
| #define bootloader_max | ( | a, | |
| b | |||
| ) | (a > b ? a : b) |
Definition at line 79 of file inertialSenseBootLoader.c.
| #define bootloader_min | ( | a, | |
| b | |||
| ) | (a < b ? a : b) |
Definition at line 78 of file inertialSenseBootLoader.c.
| #define bootloader_perror | ( | s, | |
| ... | |||
| ) |
Definition at line 72 of file inertialSenseBootLoader.c.
| #define bootloader_snprintf snprintf |
Definition at line 68 of file inertialSenseBootLoader.c.
| #define BOOTLOADER_TIMEOUT_DEFAULT 1000 |
Definition at line 22 of file inertialSenseBootLoader.c.
| #define BUF_SIZE 100 |
| #define BUFFER_SIZE 1024 |
| #define CRC_POLY 0x1021 |
Definition at line 33 of file inertialSenseBootLoader.c.
| #define ENABLE_HEX_BOOT_LOADER 1 |
Definition at line 19 of file inertialSenseBootLoader.c.
| #define FLASH_PAGE_SIZE 65536 |
Definition at line 37 of file inertialSenseBootLoader.c.
| #define MAX_SEND_COUNT 510 |
Definition at line 20 of file inertialSenseBootLoader.c.
| #define MAX_VERIFY_CHUNK_SIZE 1024 |
Definition at line 21 of file inertialSenseBootLoader.c.
| #define SAM_BA_BAUDRATE 115200 |
Definition at line 23 of file inertialSenseBootLoader.c.
| #define SAM_BA_BOOTLOADER_SIZE 16384 |
Definition at line 26 of file inertialSenseBootLoader.c.
| #define SAM_BA_FLASH_PAGE_SIZE 512 |
Definition at line 24 of file inertialSenseBootLoader.c.
| #define SAM_BA_FLASH_START_ADDRESS 0x00400000 |
Definition at line 25 of file inertialSenseBootLoader.c.
| #define X_ACK 0x06 |
Definition at line 30 of file inertialSenseBootLoader.c.
| #define X_CAN 0x18 |
Definition at line 32 of file inertialSenseBootLoader.c.
| #define X_EOT 0x04 |
Definition at line 29 of file inertialSenseBootLoader.c.
| #define X_NAK 0x15 |
Definition at line 31 of file inertialSenseBootLoader.c.
| #define X_SOH 0x01 |
Definition at line 28 of file inertialSenseBootLoader.c.
| #define XMODEM_PAYLOAD_SIZE 128 |
Definition at line 34 of file inertialSenseBootLoader.c.
|
static |
Definition at line 369 of file inertialSenseBootLoader.c.
|
static |
Definition at line 298 of file inertialSenseBootLoader.c.
| int bootloaderClosestBaudRate | ( | int | baudRate | ) |
Definition at line 221 of file inertialSenseBootLoader.c.
| int bootloaderCycleBaudRate | ( | int | baudRate | ) |
Definition at line 203 of file inertialSenseBootLoader.c.
|
static |
Definition at line 543 of file inertialSenseBootLoader.c.
|
static |
Definition at line 327 of file inertialSenseBootLoader.c.
|
static |
Definition at line 516 of file inertialSenseBootLoader.c.
|
static |
Definition at line 1112 of file inertialSenseBootLoader.c.
|
static |
Definition at line 236 of file inertialSenseBootLoader.c.
|
static |
Definition at line 912 of file inertialSenseBootLoader.c.
|
static |
Definition at line 717 of file inertialSenseBootLoader.c.
|
static |
Definition at line 388 of file inertialSenseBootLoader.c.
|
static |
Definition at line 1080 of file inertialSenseBootLoader.c.
|
static |
Definition at line 1069 of file inertialSenseBootLoader.c.
|
static |
Definition at line 353 of file inertialSenseBootLoader.c.
|
static |
Definition at line 1089 of file inertialSenseBootLoader.c.
|
static |
Definition at line 471 of file inertialSenseBootLoader.c.
|
static |
Definition at line 421 of file inertialSenseBootLoader.c.
|
static |
Definition at line 561 of file inertialSenseBootLoader.c.
| int bootloadFile | ( | serial_port_t * | port, |
| const char * | fileName, | ||
| const char * | bootName, | ||
| const void * | obj, | ||
| pfnBootloadProgress | uploadProgress, | ||
| pfnBootloadProgress | verifyProgress | ||
| ) |
Boot load a .hex or .bin file to a device
| port | the serial port to bootload to, will be opened and closed, must have port set |
| error | a buffer to store any error messages in - can be NULL |
| errorLength | the number of bytes available in error |
| obj | custom user object that will be passed in the callback |
| uploadProgress | called periodically during firmware upload - can be NULL |
| verifyProgress | called periodically during firmware verification - can be NULL |
Definition at line 1489 of file inertialSenseBootLoader.c.
| int bootloadFileEx | ( | bootload_params_t * | params | ) |
Definition at line 1508 of file inertialSenseBootLoader.c.
|
static |
Definition at line 1184 of file inertialSenseBootLoader.c.
| int bootloadGetBootloaderVersionFromFile | ( | const char * | bootName, |
| int * | verMajor, | ||
| char * | verMinor | ||
| ) |
Retrieve the bootloader version from .bin file
| fileName | for the new bootloader .bin file |
| pointer | to int to store major version |
| pointer | to char to store minor version |
Definition at line 1594 of file inertialSenseBootLoader.c.
|
static |
Definition at line 1158 of file inertialSenseBootLoader.c.
| int bootloadUpdateBootloader | ( | serial_port_t * | port, |
| const char * | fileName, | ||
| const void * | obj, | ||
| pfnBootloadProgress | uploadProgress, | ||
| pfnBootloadProgress | verifyProgress | ||
| ) |
Boot load a new bootloader .bin file to device. Device must be in application or bootloader assist mode, not bootloader mode.
| port | the serial port, must be initialized and have the port set |
| fileName | the new bootloader .bin file |
| error | a buffer to store any error messages in - can be NULL |
| errorLength | the number of bytes available in error |
| obj | custom user object that will be passed in the callback |
| uploadProgress | called periodically during firmware upload - can be NULL |
| verifyProgress | called periodically during firmware verification - can be NULL 0 if failure, non-zero if success |
Definition at line 1631 of file inertialSenseBootLoader.c.
| int bootloadUpdateBootloaderEx | ( | bootload_params_t * | p | ) |
Definition at line 1787 of file inertialSenseBootLoader.c.
|
static |
Definition at line 1648 of file inertialSenseBootLoader.c.
|
static |
Definition at line 105 of file inertialSenseBootLoader.c.
|
static |
Definition at line 86 of file inertialSenseBootLoader.c.
| int disableBootloader | ( | serial_port_t * | port, |
| char * | error, | ||
| int | errorLength | ||
| ) |
Disables the bootloader and goes back to program mode
the port to go back to program mode on a buffer to store any error messages - can be NULL the number of bytes available in error
Definition at line 1930 of file inertialSenseBootLoader.c.
|
static |
Definition at line 1914 of file inertialSenseBootLoader.c.
| int enableBootloader | ( | serial_port_t * | port, |
| int | baudRate, | ||
| char * | error, | ||
| int | errorLength, | ||
| const char * | bootloadEnableCmd | ||
| ) |
Enable bootloader mode for a device
| port | the port to enable the bootloader on |
| baudRate | the baud rate to communicate with, IS_BAUD_RATE_BOOTLOADER or IS_BAUD_RATE_BOOTLOADER_RS232 |
| error | a buffer to store any error messages - can be NULL |
| errorLength | the number of bytes available in error |
Definition at line 1844 of file inertialSenseBootLoader.c.
|
static |
Definition at line 1394 of file inertialSenseBootLoader.c.
|
static |
Definition at line 1369 of file inertialSenseBootLoader.c.
|
static |
Definition at line 1356 of file inertialSenseBootLoader.c.
|
static |
Definition at line 1384 of file inertialSenseBootLoader.c.
|
static |
Definition at line 1469 of file inertialSenseBootLoader.c.
|
static |
Definition at line 1428 of file inertialSenseBootLoader.c.
|
static |
Definition at line 1349 of file inertialSenseBootLoader.c.
|
static |
Definition at line 279 of file inertialSenseBootLoader.c.
|
static |
Definition at line 125 of file inertialSenseBootLoader.c.
|
static |
Definition at line 81 of file inertialSenseBootLoader.c.
|
static |
Definition at line 84 of file inertialSenseBootLoader.c.