Browse Source

added windows batch file to make uploading firmware easier. it calls command line version of STMFlashLoader.

added stmloader modified w/sending 'R' at start.

git-svn-id: https://afrodevices.googlecode.com/svn/trunk/baseflight@135 7c89a4a9-59b9-e629-4cfe-3a2d53b20e61
master
timecop 13 years ago
parent
commit
97cdebfb13
  1. 26
      support/flash.bat
  2. 14
      support/stmloader/Makefile
  3. 116
      support/stmloader/loader.c
  4. 179
      support/stmloader/serial.c
  5. 38
      support/stmloader/serial.h
  6. 341
      support/stmloader/stmbootloader.c
  7. 27
      support/stmloader/stmbootloader.h

26
support/flash.bat

@ -0,0 +1,26 @@
@@echo OFF
:: User configuration
:: set your port number. ie: for COM6 , port is 6
set PORT=2
:: location of stmflashloader.exe, this is default
set FLASH_LOADER="C:\Program Files (x86)\STMicroelectronics\Software\Flash Loader Demonstrator\STMFlashLoader.exe"
:: path to firmware
set FIRMWARE="D:\baseflight.hex"
:: ----------------------------------------------
mode COM%PORT% BAUD=115200 PARITY=N DATA=8 STOP=1 XON=OFF DTR=OFF RTS=OFF
echo/|set /p ="R" > COM%PORT%:
TIMEOUT /T 3
cd %LOADER_PATH%
%FLASH_LOADER% ^
-c --pn %PORT% --br 115200 --db 8 ^
-i STM32_Med-density_128K ^
-e --all ^
-d --fn %FIRMWARE% ^
-r --a 0x8000000

14
support/stmloader/Makefile

@ -0,0 +1,14 @@
CC = $(CROSS_COMPILE)gcc
AR = $(CROSS_COMPILE)ar
export CC
export AR
all:
$(CC) -g -o stmloader -I./ \
loader.c \
serial.c \
stmbootloader.c \
-Wall
clean:
rm -f stmloader

116
support/stmloader/loader.c

@ -0,0 +1,116 @@
/*
This file is part of AutoQuad.
AutoQuad is free software: you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation, either version 3 of the License, or
(at your option) any later version.
AutoQuad is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details.
You should have received a copy of the GNU General Public License
along with AutoQuad. If not, see <http://www.gnu.org/licenses/>.
Copyright © 2011 Bill Nesbitt
*/
#include "serial.h"
#include "stmbootloader.h"
#include <stdio.h>
#include <unistd.h>
#include <string.h>
#include <termios.h>
#include <fcntl.h>
#include <getopt.h>
#include <stdlib.h>
#define DEFAULT_PORT "/dev/ttyUSB0"
#define DEFAULT_BAUD 115200
#define FIRMWARE_FILENAME "STM32.hex"
serialStruct_t *s;
char port[256];
unsigned int baud;
unsigned char overrideParity;
char firmFile[256];
void loaderUsage(void) {
fprintf(stderr, "usage: loader <-h> <-p device_file> <-b baud_rate> <-f firmware_file> <-o>\n");
}
unsigned int loaderOptions(int argc, char **argv) {
int ch;
strncpy(port, DEFAULT_PORT, sizeof(port));
baud = DEFAULT_BAUD;
overrideParity = 0;
strncpy(firmFile, FIRMWARE_FILENAME, sizeof(firmFile));
/* options descriptor */
static struct option longopts[] = {
{ "help", required_argument, NULL, 'h' },
{ "port", required_argument, NULL, 'p' },
{ "baud", required_argument, NULL, 's' },
{ "firm_file", required_argument, NULL, 'f' },
{ "overide_party",no_argument, NULL, 'o' },
{ NULL, 0, NULL, 0 }
};
while ((ch = getopt_long(argc, argv, "hp:b:f:o", longopts, NULL)) != -1)
switch (ch) {
case 'h':
loaderUsage();
exit(0);
break;
case 'p':
strncpy(port, optarg, sizeof(port));
break;
case 'b':
baud = atoi(optarg);
break;
case 'f':
strncpy(firmFile, optarg, sizeof(firmFile));
break;
case 'o':
overrideParity = 1;
break;
default:
loaderUsage();
return 0;
}
argc -= optind;
argv += optind;
return 1;
}
int main(int argc, char **argv) {
FILE *fw;
// init
if (!loaderOptions(argc, argv)) {
fprintf(stderr, "Init failed, aborting\n");
return 1;
}
s = initSerial(port, baud, 0);
if (!s) {
fprintf(stderr, "Cannot open serial port '%s', aborting.\n", port);
return 1;
}
fw = fopen(firmFile, "r");
if (!fw) {
fprintf(stderr, "Cannot open firmware file '%s', aborting.\n", firmFile);
return 1;
}
else {
printf("Upgrading STM on port %s from %s...\n", port, firmFile);
stmLoader(s, fw, overrideParity);
}
return 0;
}

179
support/stmloader/serial.c

@ -0,0 +1,179 @@
/*
This file is part of AutoQuad.
AutoQuad is free software: you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation, either version 3 of the License, or
(at your option) any later version.
AutoQuad is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details.
You should have received a copy of the GNU General Public License
along with AutoQuad. If not, see <http://www.gnu.org/licenses/>.
Copyright © 2011 Bill Nesbitt
*/
#ifndef _GNU_SOURCE
#define _GNU_SOURCE
#endif
#include "serial.h"
#include <stdio.h>
#include <unistd.h>
#include <termios.h>
#include <fcntl.h>
#include <stdlib.h>
#include <sys/select.h>
#include <string.h>
serialStruct_t *initSerial(const char *port, unsigned int baud, char ctsRts) {
serialStruct_t *s;
struct termios options;
unsigned int brate;
s = (serialStruct_t *)calloc(1, sizeof(serialStruct_t));
s->fd = open(port, O_RDWR | O_NOCTTY | O_NDELAY);
if (s->fd == -1) {
free(s);
return 0;
}
fcntl(s->fd, F_SETFL, 0); // clear all flags on descriptor, enable direct I/O
// bzero(&options, sizeof(options));
// memset(&options, 0, sizeof(options));
tcgetattr(s->fd, &options);
#ifdef B921600
switch (baud) {
case 9600:
brate = B9600;
break;
case 19200:
brate = B19200;
break;
case 38400:
brate = B38400;
break;
case 57600:
brate = B57600;
break;
case 115200:
brate = B115200;
break;
case 230400:
brate = B230400;
break;
case 460800:
brate = B460800;
break;
case 921600:
brate = B921600;
break;
default:
brate = B115200;
break;
}
options.c_cflag = brate;
#else // APPLE
cfsetispeed(&options, baud);
cfsetospeed(&options, baud);
#endif
options.c_cflag = CRTSCTS | CS8 | CLOCAL | CREAD;
options.c_iflag = IGNPAR;
options.c_iflag &= (~(IXON|IXOFF|IXANY)); // turn off software flow control
options.c_oflag = 0;
/* set input mode (non-canonical, no echo,...) */
options.c_lflag = 0;
options.c_cc[VTIME] = 0; /* inter-character timer unused */
options.c_cc[VMIN] = 1; /* blocking read until 1 chars received */
#ifdef CCTS_OFLOW
options.c_cflag |= CCTS_OFLOW;
#endif
if (!ctsRts)
options.c_cflag &= ~(CRTSCTS); // turn off hardware flow control
// set the new port options
tcsetattr(s->fd, TCSANOW, &options);
return s;
}
void serialFree(serialStruct_t *s) {
if (s) {
if (s->fd)
close(s->fd);
free (s);
}
}
void serialNoParity(serialStruct_t *s) {
struct termios options;
tcgetattr(s->fd, &options); // read serial port options
options.c_cflag &= ~(PARENB | CSTOPB);
tcsetattr(s->fd, TCSANOW, &options);
}
void serialEvenParity(serialStruct_t *s) {
struct termios options;
tcgetattr(s->fd, &options); // read serial port options
options.c_cflag |= (PARENB);
options.c_cflag &= ~(PARODD | CSTOPB);
tcsetattr(s->fd, TCSANOW, &options);
}
void serialWriteChar(serialStruct_t *s, unsigned char c) {
char ret;
ret = write(s->fd, &c, 1);
}
void serialWrite(serialStruct_t *s, const char *str, unsigned int len) {
char ret;
ret = write(s->fd, str, len);
}
unsigned char serialAvailable(serialStruct_t *s) {
fd_set fdSet;
struct timeval timeout;
FD_ZERO(&fdSet);
FD_SET(s->fd, &fdSet);
memset((char *)&timeout, 0, sizeof(timeout));
if (select(s->fd+1, &fdSet, 0, 0, &timeout) == 1)
return 1;
else
return 0;
}
void serialFlush(serialStruct_t *s) {
while (serialAvailable(s))
serialRead(s);
}
unsigned char serialRead(serialStruct_t *s) {
char ret;
unsigned char c;
ret = read(s->fd, &c, 1);
return c;
}

38
support/stmloader/serial.h

@ -0,0 +1,38 @@
/*
This file is part of AutoQuad.
AutoQuad is free software: you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation, either version 3 of the License, or
(at your option) any later version.
AutoQuad is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details.
You should have received a copy of the GNU General Public License
along with AutoQuad. If not, see <http://www.gnu.org/licenses/>.
Copyright © 2011 Bill Nesbitt
*/
#ifndef _serial_h
#define _serial_h
#define INPUT_BUFFER_SIZE 1024
typedef struct {
int fd;
} serialStruct_t;
extern serialStruct_t *initSerial(const char *port, unsigned int baud, char ctsRts);
extern void serialWrite(serialStruct_t *s, const char *str, unsigned int len);
extern void serialWriteChar(serialStruct_t *s, unsigned char c);
extern unsigned char serialAvailable(serialStruct_t *s);
extern void serialFlush(serialStruct_t *s);
extern unsigned char serialRead(serialStruct_t *s);
extern void serialEvenParity(serialStruct_t *s);
extern void serialNoParity(serialStruct_t *s);
extern void serialFree(serialStruct_t *s);
#endif

341
support/stmloader/stmbootloader.c

@ -0,0 +1,341 @@
/*
This file is part of AutoQuad.
AutoQuad is free software: you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation, either version 3 of the License, or
(at your option) any later version.
AutoQuad is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details.
You should have received a copy of the GNU General Public License
along with AutoQuad. If not, see <http://www.gnu.org/licenses/>.
Copyright © 2011 Bill Nesbitt
*/
#ifndef _GNU_SOURCE
#define _GNU_SOURCE
#endif
#include "serial.h"
#include <stdio.h>
#include <unistd.h>
#include <string.h>
#include <ctype.h>
#define STM_RETRIES_SHORT 1000
#define STM_RETRIES_LONG 50000
unsigned char getResults[11];
unsigned char stmHexToChar(const char *hex) {
char hex1, hex2;
unsigned char nibble1, nibble2;
// force data to upper case
hex1 = toupper(hex[0]);
hex2 = toupper(hex[1]);
if (hex1 < 65)
nibble1 = hex1 - 48;
else
nibble1 = hex1 - 55;
if (hex2 < 65)
nibble2 = hex2 - 48;
else
nibble2 = hex2 - 55;
return (nibble1 << 4 | nibble2);
}
unsigned char stmWaitAck(serialStruct_t *s, int retries) {
unsigned char c;
unsigned int i;
for (i = 0; i < retries; i++) {
if (serialAvailable(s)) {
c = serialRead(s);
if (c == 0x79) {
// putchar('+'); fflush(stdout);
return 1;
}
if (c == 0x1f) {
putchar('-'); fflush(stdout);
return 0;
}
else {
printf("?%x?", c); fflush(stdout);
return 0;
}
}
usleep(500);
}
return 0;
}
unsigned char stmWrite(serialStruct_t *s, const char *hex) {
unsigned char c;
unsigned char ck;
unsigned char i;
ck = 0;
i = 0;
while (*hex) {
c = stmHexToChar(hex);
serialWrite(s, (char *)&c, 1);
ck ^= c;
hex += 2;
i++;
}
if (i == 1)
ck = 0xff ^ c;
// send checksum
serialWrite(s, (char *)&ck, 1);
return stmWaitAck(s, STM_RETRIES_LONG);
}
void stmWriteCommand(serialStruct_t *s, char *msb, char *lsb, char *len, char *data) {
char startAddress[9];
char lenPlusData[128];
char c;
strncpy(startAddress, msb, sizeof(startAddress));
strcat(startAddress, lsb);
sprintf(lenPlusData, "%02x%s", stmHexToChar(len) - 1, data);
write:
// send WRITE MEMORY command
do {
c = getResults[5];
serialWrite(s, &c, 1);
c = 0xff ^ c;
serialWrite(s, &c, 1);
} while (!stmWaitAck(s, STM_RETRIES_LONG));
// send address
if (!stmWrite(s, startAddress)) {
putchar('A');
goto write;
}
// send len + data
if (!stmWrite(s, lenPlusData)) {
putchar('D');
goto write;
}
putchar('='); fflush(stdout);
}
char *stmHexLoader(serialStruct_t *s, FILE *fp) {
char hexByteCount[3], hexAddressLSB[5], hexRecordType[3], hexData[128];
char addressMSB[5];
static char addressJump[9];
// bzero(addressJump, sizeof(addressJump));
// bzero(addressMSB, sizeof(addressMSB));
memset(addressJump, 0, sizeof(addressJump));
memset(addressMSB, 0, sizeof(addressMSB));
while (fscanf(fp, ":%2s%4s%2s%s\n", hexByteCount, hexAddressLSB, hexRecordType, hexData) != EOF) {
unsigned int byteCount, addressLSB, recordType;
recordType = stmHexToChar(hexRecordType);
hexData[stmHexToChar(hexByteCount) * 2] = 0; // terminate at CHKSUM
// printf("Record Type: %d\n", recordType);
switch (recordType) {
case 0x00:
stmWriteCommand(s, addressMSB, hexAddressLSB, hexByteCount, hexData);
break;
case 0x01:
// EOF
return addressJump;
break;
case 0x04:
// MSB of destination 32 bit address
strncpy(addressMSB, hexData, 4);
break;
case 0x05:
// 32 bit address to run after load
strncpy(addressJump, hexData, 8);
break;
}
}
return 0;
}
void stmLoader(serialStruct_t *s, FILE *fp, unsigned char overrideParity) {
char c;
unsigned char b1, b2, b3;
unsigned char i, n;
char *jumpAddress;
// turn on parity generation
if (!overrideParity)
serialEvenParity(s);
top:
printf("Sending R to place Baseflight in bootloader, press a key to continue");
serialFlush(s);
c = 'R';
serialWrite(s, &c, 1);
getchar();
printf("\n");
serialFlush(s);
printf("Poking the MCU to check whether bootloader is alive...");
// poke the MCU
do {
printf("p"); fflush(stdout);
c = 0x7f;
serialWrite(s, &c, 1);
} while (!stmWaitAck(s, STM_RETRIES_SHORT));
printf("STM bootloader alive...\n");
// send GET command
do {
c = 0x00;
serialWrite(s, &c, 1);
c = 0xff;
serialWrite(s, &c, 1);
} while (!stmWaitAck(s, STM_RETRIES_LONG));
b1 = serialRead(s); // number of bytes
b2 = serialRead(s); // bootloader version
for (i = 0; i < b1; i++)
getResults[i] = serialRead(s);
stmWaitAck(s, STM_RETRIES_LONG);
printf("Received commands.\n");
// send GET VERSION command
do {
c = getResults[1];
serialWrite(s, &c, 1);
c = 0xff ^ c;
serialWrite(s, &c, 1);
} while (!stmWaitAck(s, STM_RETRIES_LONG));
b1 = serialRead(s);
b2 = serialRead(s);
b3 = serialRead(s);
stmWaitAck(s, STM_RETRIES_LONG);
printf("STM Bootloader version: %d.%d\n", (b1 & 0xf0) >> 4, (b1 & 0x0f));
// send GET ID command
do {
c = getResults[2];
serialWrite(s, &c, 1);
c = 0xff ^ c;
serialWrite(s, &c, 1);
} while (!stmWaitAck(s, STM_RETRIES_LONG));
n = serialRead(s);
printf("STM Device ID: 0x");
for (i = 0; i <= n; i++) {
b1 = serialRead(s);
printf("%02x", b1);
}
stmWaitAck(s, STM_RETRIES_LONG);
printf("\n");
/*
flash_size:
// read Flash size
c = getResults[3];
serialWrite(s, &c, 1);
c = 0xff ^ c;
serialWrite(s, &c, 1);
// if read not allowed, unprotect (which also erases)
if (!stmWaitAck(s, STM_RETRIES_LONG)) {
// unprotect command
do {
c = getResults[10];
serialWrite(s, &c, 1);
c = 0xff ^ c;
serialWrite(s, &c, 1);
} while (!stmWaitAck(s, STM_RETRIES_LONG));
// wait for results
if (stmWaitAck(s, STM_RETRIES_LONG))
goto top;
}
// send address
if (!stmWrite(s, "1FFFF7E0"))
goto flash_size;
// send # bytes (N-1 = 1)
if (!stmWrite(s, "01"))
goto flash_size;
b1 = serialRead(s);
b2 = serialRead(s);
printf("STM Flash Size: %dKB\n", b2<<8 | b1);
*/
// erase flash
erase_flash:
printf("Global flash erase [command 0x%x]...", getResults[6]); fflush(stdout);
do {
c = getResults[6];
serialWrite(s, &c, 1);
c = 0xff ^ c;
serialWrite(s, &c, 1);
} while (!stmWaitAck(s, STM_RETRIES_LONG));
// global erase
if (getResults[6] == 0x44) {
// mass erase
if (!stmWrite(s, "FFFF"))
goto erase_flash;
}
else {
c = 0xff;
serialWrite(s, &c, 1);
c = 0x00;
serialWrite(s, &c, 1);
if (!stmWaitAck(s, STM_RETRIES_LONG))
goto erase_flash;
}
printf("Done.\n");
// upload hex file
printf("Flashing device...\n");
jumpAddress = stmHexLoader(s, fp);
if (jumpAddress) {
printf("\nFlash complete, cylce power\n");
go:
// send GO command
do {
c = getResults[4];
serialWrite(s, &c, 1);
c = 0xff ^ c;
serialWrite(s, &c, 1);
} while (!stmWaitAck(s, STM_RETRIES_LONG));
// send address
if (!stmWrite(s, jumpAddress))
goto go;
}
else {
printf("\nFlash complete.\n");
}
}

27
support/stmloader/stmbootloader.h

@ -0,0 +1,27 @@
/*
This file is part of AutoQuad.
AutoQuad is free software: you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation, either version 3 of the License, or
(at your option) any later version.
AutoQuad is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details.
You should have received a copy of the GNU General Public License
along with AutoQuad. If not, see <http://www.gnu.org/licenses/>.
Copyright © 2011 Bill Nesbitt
*/
#ifndef _stmbootloader_h
#define _stmbootloader_h
#include <stdio.h>
#include "serial.h"
extern void stmLoader(serialStruct_t *s, FILE *fp, unsigned char overrideParity);
#endif
Loading…
Cancel
Save