Reverting serial_4way to 2.9 code

This commit is contained in:
blckmn 2016-07-16 13:32:54 +10:00
parent 19a814afbb
commit e40942366e
7 changed files with 999 additions and 836 deletions

File diff suppressed because it is too large Load Diff

View File

@ -15,127 +15,36 @@
* along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
* Author: 4712
*/
#pragma once
#ifdef USE_SERIAL_4WAY_BLHELI_INTERFACE
#include "serial_4way_impl.h"
#define USE_SERIAL_4WAY_BLHELI_BOOTLOADER
#define USE_SERIAL_4WAY_SK_BOOTLOADER
typedef enum {
imC2 = 0,
imSIL_BLB = 1,
imATM_BLB = 2,
imSK = 3,
} esc4wayInterfaceMode_e;
#define imC2 0
#define imSIL_BLB 1
#define imATM_BLB 2
#define imSK 3
typedef enum {
// Test Interface still present
cmd_InterfaceTestAlive = 0x30, // '0' alive
// RETURN: ACK
extern uint8_t selected_esc;
// get Protocol Version Number 01..255
cmd_ProtocolGetVersion = 0x31, // '1' version
// RETURN: uint8_t VersionNumber + ACK
extern ioMem_t ioMem;
// get Version String
cmd_InterfaceGetName = 0x32, // '2' name
// RETURN: String + ACK
typedef union __attribute__ ((packed)) {
uint8_t bytes[2];
uint16_t word;
} uint8_16_u;
//get Version Number 01..255
cmd_InterfaceGetVersion = 0x33, // '3' version
// RETURN: uint16_t VersionNumber + ACK
typedef union __attribute__ ((packed)) {
uint8_t bytes[4];
uint16_t words[2];
uint32_t dword;
} uint8_32_u;
// Exit / Restart Interface - can be used to switch to Box Mode
cmd_InterfaceExit = 0x34, // '4' exit
// RETURN: ACK
//extern uint8_32_u DeviceInfo;
// Reset the Device connected to the Interface
cmd_DeviceReset = 0x35, // '5' reset
// PARAM: uint8_t escId
// RETURN: ACK
// Get the Device ID connected
// cmd_DeviceGetID = 0x36, // '6' device id; removed since 06/106
// RETURN: uint8_t DeviceID + ACK
// Initialize Flash Access for Device connected
// Autodetects interface protocol; retruns device signature and protocol
cmd_DeviceInitFlash = 0x37, // '7' init flash access
// PARAM: uint8_t escId
// RETURN: uint8_t deviceInfo[4] + ACK
// Erase the whole Device Memory of connected Device
cmd_DeviceEraseAll = 0x38, // '8' erase all
// RETURN: ACK
// Erase one Page of Device Memory of connected Device
cmd_DevicePageErase = 0x39, // '9' page erase
// PARAM: uint8_t PageNumber (512B pages)
// RETURN: APageNumber ACK
// Read to Buffer from FLASH Memory of connected Device
// Buffer Len is Max 256 Bytes, 0 means 256 Bytes
cmd_DeviceRead = 0x3A, // ':' read Device
// PARAM: [ADRESS] uint8_t BuffLen
// RETURN: [ADRESS, len] Buffer[0..256] ACK
// Write Buffer to FLASH Memory of connected Device
// Buffer Len is Max 256 Bytes, 0 means 256 Bytes
cmd_DeviceWrite = 0x3B, // ';' write
// PARAM: [ADRESS + BuffLen] Buffer[1..256]
// RETURN: ACK
// Set C2CK low infinite - permanent Reset state (unimplemented)
cmd_DeviceC2CK_LOW = 0x3C, // '<'
// RETURN: ACK
// Read to Buffer from EEPROM Memory of connected Device
// Buffer Len is Max 256 Bytes, 0 means 256 Bytes
cmd_DeviceReadEEprom = 0x3D, // '=' read Device
// PARAM: [ADRESS] uint8_t BuffLen
// RETURN: [ADRESS + BuffLen] + Buffer[1..256] ACK
// Write Buffer to EEPROM Memory of connected Device
// Buffer Len is Max 256 Bytes, 0 means 256 Bytes
cmd_DeviceWriteEEprom = 0x3E, // '>' write
// PARAM: [ADRESS + BuffLen] Buffer[1..256]
// RETURN: ACK
// Set Interface Mode
cmd_InterfaceSetMode = 0x3F, // '?'
// PARAM: uint8_t Mode (interfaceMode_e)
// RETURN: ACK
} esc4wayCmd_e;
// responses
typedef enum {
esc4wayAck_OK = 0x00,
// esc4wayAck_I_UNKNOWN_ERROR = 0x01,
esc4wayAck_I_INVALID_CMD = 0x02,
esc4wayAck_I_INVALID_CRC = 0x03,
esc4wayAck_I_VERIFY_ERROR = 0x04,
// esc4wayAck_D_INVALID_COMMAND = 0x05,
// esc4wayAck_D_COMMAND_FAILED = 0x06,
// esc4wayAck_D_UNKNOWN_ERROR = 0x07,
esc4wayAck_I_INVALID_CHANNEL = 0x08,
esc4wayAck_I_INVALID_PARAM = 0x09,
esc4wayAck_D_GENERAL_ERROR = 0x0f,
} esc4wayAck_e;
typedef struct escDeviceInfo_s {
uint16_t signature; // lower 16 bit of signature
uint8_t signature2; // top 8 bit of signature for SK / BootMsg last char from BL
uint8_t interfaceMode;
} escDeviceInfo_t;
extern bool esc4wayExitRequested; // flag that exit was requested. Set by esc4wayProcessCmd, used internally by esc4wayProcess
int esc4wayInit(void);
void esc4wayStart(void);
bool isMcuConnected(void);
uint8_t esc4wayInit(void);
void esc4wayProcess(serialPort_t *mspPort);
void esc4wayRelease(void);
void esc4wayProcess(serialPort_t *serial);
esc4wayAck_e esc4wayProcessCmd(esc4wayCmd_e command, uint16_t addr, uint8_t *data, int inLen, int *outLen);
#endif

View File

@ -24,19 +24,17 @@
#include <stdlib.h>
#include "platform.h"
#include "common/utils.h"
#ifdef USE_SERIAL_4WAY_BLHELI_INTERFACE
#include "drivers/system.h"
#include "drivers/serial.h"
#include "drivers/buf_writer.h"
#include "drivers/pwm_mapping.h"
#include "drivers/gpio.h"
#include "io/serial.h"
#include "io/serial_msp.h"
#include "io/serial_4way.h"
#include "io/serial_4way_impl.h"
#include "io/serial_4way_avrootloader.h"
#ifdef USE_SERIAL_4WAY_BLHELI_BOOTLOADER
#if defined(USE_SERIAL_4WAY_BLHELI_INTERFACE) && defined(USE_SERIAL_4WAY_BLHELI_BOOTLOADER)
// Bootloader commands
// RunCmd
@ -61,231 +59,251 @@
// Bootloader result codes
#define BR_SUCCESS 0x30
#define BR_ERRORCOMMAND 0xC1
#define BR_ERRORCRC 0xC2
#define BR_NONE 0xFF
#define brSUCCESS 0x30
#define brERRORCOMMAND 0xC1
#define brERRORCRC 0xC2
#define brNONE 0xFF
#define START_BIT_TIMEOUT 2000 // 2ms
#define BIT_TIME 52 // 52uS
#define BIT_TIME_HALVE (BIT_TIME >> 1) // 26uS
#define BIT_TIME_3_4 (BIT_TIME_HALVE + (BIT_TIME_HALVE >> 1)) // 39uS
#define START_BIT_TIME (BIT_TIME_3_4)
#define START_BIT_TIMEOUT_MS 2
static int suart_getc(void)
#define BIT_TIME (52) //52uS
#define BIT_TIME_HALVE (BIT_TIME >> 1) //26uS
#define START_BIT_TIME (BIT_TIME_HALVE + 1)
//#define STOP_BIT_TIME ((BIT_TIME * 9) + BIT_TIME_HALVE)
static uint8_t suart_getc_(uint8_t *bt)
{
uint32_t btime;
uint32_t start_time;
uint32_t wait_time = micros() + START_BIT_TIMEOUT;
uint32_t wait_time = millis() + START_BIT_TIMEOUT_MS;
while (ESC_IS_HI) {
// check for startbit begin
if (micros() >= wait_time) {
return -1;
if (millis() >= wait_time) {
return 0;
}
}
// start bit
start_time = micros();
btime = start_time + START_BIT_TIME;
uint16_t bitmask = 0;
for(int bit = 0; bit < 10; bit++) {
while (cmp32(micros(), btime) < 0);
uint8_t bit = 0;
while (micros() < btime);
while(1) {
if (ESC_IS_HI)
{
bitmask |= (1 << bit);
}
btime = btime + BIT_TIME;
bit++;
if (bit == 10) break;
while (micros() < btime);
}
// check start bit and stop bit
if ((bitmask & (1 << 0)) || (!(bitmask & (1 << 9)))) {
return -1;
if ((bitmask & 1) || (!(bitmask & (1 << 9)))) {
return 0;
}
return bitmask >> 1;
*bt = bitmask >> 1;
return 1;
}
static void suart_putc(uint8_t byte)
static void suart_putc_(uint8_t *tx_b)
{
// send one idle bit first (stopbit from previous byte)
uint16_t bitmask = (byte << 2) | (1 << 0) | (1 << 10);
// shift out stopbit first
uint16_t bitmask = (*tx_b << 2) | 1 | (1 << 10);
uint32_t btime = micros();
while(1) {
if(bitmask & 1)
if(bitmask & 1) {
ESC_SET_HI; // 1
else
}
else {
ESC_SET_LO; // 0
}
btime = btime + BIT_TIME;
bitmask >>= 1;
if (bitmask == 0)
break; // stopbit shifted out - but don't wait
while (cmp32(micros(), btime) < 0);
bitmask = (bitmask >> 1);
if (bitmask == 0) break; // stopbit shifted out - but don't wait
while (micros() < btime);
}
}
static uint16_t crc16Byte(uint16_t from, uint8_t byte)
static uint8_16_u CRC_16;
static uint8_16_u LastCRC_16;
static void ByteCrc(uint8_t *bt)
{
uint16_t crc16 = from;
for (int i = 0; i < 8; i++) {
if (((byte & 0x01) ^ (crc16 & 0x0001)) != 0) {
crc16 >>= 1;
crc16 ^= 0xA001;
uint8_t xb = *bt;
for (uint8_t i = 0; i < 8; i++)
{
if (((xb & 0x01) ^ (CRC_16.word & 0x0001)) !=0 ) {
CRC_16.word = CRC_16.word >> 1;
CRC_16.word = CRC_16.word ^ 0xA001;
} else {
crc16 >>= 1;
CRC_16.word = CRC_16.word >> 1;
}
byte >>= 1;
xb = xb >> 1;
}
return crc16;
}
static uint8_t BL_ReadBuf(uint8_t *pstring, int len, bool checkCrc)
static uint8_t BL_ReadBuf(uint8_t *pstring, uint8_t len)
{
int crc = 0;
int c;
// len 0 means 256
CRC_16.word = 0;
LastCRC_16.word = 0;
uint8_t LastACK = brNONE;
do {
if(!suart_getc_(pstring)) goto timeout;
ByteCrc(pstring);
pstring++;
len--;
} while(len > 0);
uint8_t lastACK = BR_NONE;
for(int i = 0; i < len; i++) {
int c;
if ((c = suart_getc()) < 0) goto timeout;
crc = crc16Byte(crc, c);
pstring[i] = c;
if(isMcuConnected()) {
//With CRC read 3 more
if(!suart_getc_(&LastCRC_16.bytes[0])) goto timeout;
if(!suart_getc_(&LastCRC_16.bytes[1])) goto timeout;
if(!suart_getc_(&LastACK)) goto timeout;
if (CRC_16.word != LastCRC_16.word) {
LastACK = brERRORCRC;
}
if(checkCrc) {
// With CRC read 3 more
for(int i = 0; i < 2; i++) { // checksum 2 CRC bytes
if ((c = suart_getc()) < 0) goto timeout;
crc = crc16Byte(crc, c);
}
if((c = suart_getc()) < 0) goto timeout;
lastACK = c;
if (crc != 0) // CRC of correct message is 0
lastACK = BR_ERRORCRC;
} else {
if((c = suart_getc()) < 0) goto timeout;
lastACK = c;
if(!suart_getc_(&LastACK)) goto timeout;
}
timeout:
return (lastACK == BR_SUCCESS);
return (LastACK == brSUCCESS);
}
static void BL_SendBuf(uint8_t *pstring, int len, bool appendCrc)
static void BL_SendBuf(uint8_t *pstring, uint8_t len)
{
ESC_OUTPUT;
uint16_t crc = 0;
for(int i = 0; i < len; i++) {
suart_putc(pstring[i]);
crc = crc16Byte(crc, pstring[i]);
}
if (appendCrc) {
suart_putc(crc & 0xff);
suart_putc(crc >> 8);
CRC_16.word=0;
do {
suart_putc_(pstring);
ByteCrc(pstring);
pstring++;
len--;
} while (len > 0);
if (isMcuConnected()) {
suart_putc_(&CRC_16.bytes[0]);
suart_putc_(&CRC_16.bytes[1]);
}
ESC_INPUT;
}
uint8_t BL_ConnectEx(escDeviceInfo_t *pDeviceInfo)
uint8_t BL_ConnectEx(uint8_32_u *pDeviceInfo)
{
#define BOOT_MSG_LEN 4
#define DevSignHi (BOOT_MSG_LEN)
#define DevSignLo (BOOT_MSG_LEN + 1)
#define BootMsgLen 4
#define DevSignHi (BootMsgLen)
#define DevSignLo (BootMsgLen+1)
memset(pDeviceInfo, 0, sizeof(*pDeviceInfo));
uint8_t bootInfo[BOOT_MSG_LEN + 4];
static const uint8_t bootMsgCheck[BOOT_MSG_LEN - 1] = "471";
//DeviceInfo.dword=0; is set before
uint8_t BootInfo[9];
uint8_t BootMsg[BootMsgLen-1] = "471";
// x * 0 + 9
#if defined(USE_SERIAL_4WAY_SK_BOOTLOADER)
// SK message was sent during autodetection, use longer preamble
uint8_t bootInit[] = {0,0,0,0,0,0,0,0,0,0,0,0,0x0D,'B','L','H','e','l','i',0xF4,0x7D};
uint8_t BootInit[] = {0,0,0,0,0,0,0,0,0,0,0,0,0x0D,'B','L','H','e','l','i',0xF4,0x7D};
BL_SendBuf(BootInit, 21);
#else
uint8_t bootInit[] = { 0,0,0,0,0,0,0,0,0x0D,'B','L','H','e','l','i',0xF4,0x7D};
uint8_t BootInit[] = {0,0,0,0,0,0,0,0,0x0D,'B','L','H','e','l','i',0xF4,0x7D};
BL_SendBuf(BootInit, 17);
#endif
BL_SendBuf(bootInit, sizeof(bootInit), false);
if (!BL_ReadBuf(bootInfo, sizeof(bootInfo), false))
if (!BL_ReadBuf(BootInfo, BootMsgLen + 4)) {
return 0;
}
// BootInfo has no CRC (ACK byte already analyzed... )
// Format = BootMsg("471c") SIGNATURE_001, SIGNATURE_002, BootVersion (always 6), BootPages (,ACK)
if(memcmp(bootInfo, bootMsgCheck, sizeof(bootMsgCheck)) != 0) // Check only the first 3 letters -> 471x OK
return 0;
for (uint8_t i = 0; i < (BootMsgLen - 1); i++) { // Check only the first 3 letters -> 471x OK
if (BootInfo[i] != BootMsg[i]) {
return (0);
}
}
pDeviceInfo->signature2 = bootInfo[BOOT_MSG_LEN - 1]; // taken from bootloaderMsg part, ascii 'c' now
pDeviceInfo->signature = (bootInfo[DevSignHi] << 8) | bootInfo[DevSignLo]; // SIGNATURE_001, SIGNATURE_002
return 1;
//only 2 bytes used $1E9307 -> 0x9307
pDeviceInfo->bytes[2] = BootInfo[BootMsgLen - 1];
pDeviceInfo->bytes[1] = BootInfo[DevSignHi];
pDeviceInfo->bytes[0] = BootInfo[DevSignLo];
return (1);
}
static uint8_t BL_GetACK(int timeout)
static uint8_t BL_GetACK(uint32_t Timeout)
{
int c;
while ((c = suart_getc()) < 0)
if(--timeout < 0) // timeout=1 -> 1 retry
return BR_NONE;
return c;
uint8_t LastACK = brNONE;
while (!(suart_getc_(&LastACK)) && (Timeout)) {
Timeout--;
} ;
return (LastACK);
}
uint8_t BL_SendCMDKeepAlive(void)
{
uint8_t sCMD[] = {CMD_KEEP_ALIVE, 0};
BL_SendBuf(sCMD, sizeof(sCMD), true);
if (BL_GetACK(1) != BR_ERRORCOMMAND)
BL_SendBuf(sCMD, 2);
if (BL_GetACK(1) != brERRORCOMMAND) {
return 0;
}
return 1;
}
void BL_SendCMDRunRestartBootloader(void)
void BL_SendCMDRunRestartBootloader(uint8_32_u *pDeviceInfo)
{
uint8_t sCMD[] = {RestartBootloader, 0};
BL_SendBuf(sCMD, sizeof(sCMD), true); // sends simply 4 x 0x00 (CRC = 00)
pDeviceInfo->bytes[0] = 1;
BL_SendBuf(sCMD, 2); //sends simply 4 x 0x00 (CRC =00)
return;
}
static uint8_t BL_SendCMDSetAddress(ioMem_t *pMem) //supports only 16 bit Adr
{
// skip if adr == 0xFFFF
if(pMem->addr == 0xffff)
return 1;
uint8_t sCMD[] = {CMD_SET_ADDRESS, 0, pMem->addr >> 8, pMem->addr & 0xff };
BL_SendBuf(sCMD, sizeof(sCMD), true);
return BL_GetACK(2) == BR_SUCCESS;
if((pMem->D_FLASH_ADDR_H == 0xFF) && (pMem->D_FLASH_ADDR_L == 0xFF)) return 1;
uint8_t sCMD[] = {CMD_SET_ADDRESS, 0, pMem->D_FLASH_ADDR_H, pMem->D_FLASH_ADDR_L };
BL_SendBuf(sCMD, 4);
return (BL_GetACK(2) == brSUCCESS);
}
static uint8_t BL_SendCMDSetBuffer(ioMem_t *pMem)
{
uint16_t len = pMem->len;
uint8_t sCMD[] = {CMD_SET_BUFFER, 0, len >> 8, len & 0xff};
BL_SendBuf(sCMD, sizeof(sCMD), true);
if (BL_GetACK(2) != BR_NONE)
return 0;
BL_SendBuf(pMem->data, len, true);
return BL_GetACK(40) == BR_SUCCESS;
uint8_t sCMD[] = {CMD_SET_BUFFER, 0, 0, pMem->D_NUM_BYTES};
if (pMem->D_NUM_BYTES == 0) {
// set high byte
sCMD[2] = 1;
}
BL_SendBuf(sCMD, 4);
if (BL_GetACK(2) != brNONE) return 0;
BL_SendBuf(pMem->D_PTR_I, pMem->D_NUM_BYTES);
return (BL_GetACK(40) == brSUCCESS);
}
static uint8_t BL_ReadA(uint8_t cmd, ioMem_t *pMem)
{
if(!BL_SendCMDSetAddress(pMem))
if (BL_SendCMDSetAddress(pMem)) {
uint8_t sCMD[] = {cmd, pMem->D_NUM_BYTES};
BL_SendBuf(sCMD, 2);
return (BL_ReadBuf(pMem->D_PTR_I, pMem->D_NUM_BYTES ));
}
return 0;
unsigned len = pMem->len;
uint8_t sCMD[] = {cmd, len & 0xff}; // 0x100 is sent a 0x00 here
BL_SendBuf(sCMD, sizeof(sCMD), true);
return BL_ReadBuf(pMem->data, len, true);
}
static uint8_t BL_WriteA(uint8_t cmd, ioMem_t *pMem, uint32_t timeout)
{
if(!BL_SendCMDSetAddress(pMem))
return 0;
if (!BL_SendCMDSetBuffer(pMem))
return 0;
if (BL_SendCMDSetAddress(pMem)) {
if (!BL_SendCMDSetBuffer(pMem)) return 0;
uint8_t sCMD[] = {cmd, 0x01};
BL_SendBuf(sCMD, sizeof(sCMD), true);
return BL_GetACK(timeout) == BR_SUCCESS;
BL_SendBuf(sCMD, 2);
return (BL_GetACK(timeout) == brSUCCESS);
}
return 0;
}
uint8_t BL_ReadFlashATM(ioMem_t *pMem)
uint8_t BL_ReadFlash(uint8_t interface_mode, ioMem_t *pMem)
{
if(interface_mode == imATM_BLB) {
return BL_ReadA(CMD_READ_FLASH_ATM, pMem);
}
uint8_t BL_ReadFlashSIL(ioMem_t *pMem)
{
} else {
return BL_ReadA(CMD_READ_FLASH_SIL, pMem);
}
}
@ -296,22 +314,23 @@ uint8_t BL_ReadEEprom(ioMem_t *pMem)
uint8_t BL_PageErase(ioMem_t *pMem)
{
if(!BL_SendCMDSetAddress(pMem))
return 0;
if (BL_SendCMDSetAddress(pMem)) {
uint8_t sCMD[] = {CMD_ERASE_FLASH, 0x01};
BL_SendBuf(sCMD, sizeof(sCMD), true);
return BL_GetACK(40 * 1000 / START_BIT_TIMEOUT) == BR_SUCCESS;
BL_SendBuf(sCMD, 2);
return (BL_GetACK((40 / START_BIT_TIMEOUT_MS)) == brSUCCESS);
}
return 0;
}
uint8_t BL_WriteEEprom(ioMem_t *pMem)
{
return BL_WriteA(CMD_PROG_EEPROM, pMem, 3000 * 1000 / START_BIT_TIMEOUT);
return BL_WriteA(CMD_PROG_EEPROM, pMem, (3000 / START_BIT_TIMEOUT_MS));
}
uint8_t BL_WriteFlash(ioMem_t *pMem)
{
return BL_WriteA(CMD_PROG_FLASH, pMem, 40 * 1000 / START_BIT_TIMEOUT);
return BL_WriteA(CMD_PROG_FLASH, pMem, (40 / START_BIT_TIMEOUT_MS));
}
#endif
#endif

View File

@ -20,17 +20,12 @@
#pragma once
#ifdef USE_SERIAL_4WAY_BLHELI_BOOTLOADER
void BL_SendBootInit(void);
uint8_t BL_ConnectEx(escDeviceInfo_t *pDeviceInfo);
uint8_t BL_ConnectEx(uint8_32_u *pDeviceInfo);
uint8_t BL_SendCMDKeepAlive(void);
uint8_t BL_WriteEEprom(ioMem_t *pMem);
uint8_t BL_ReadEEprom(ioMem_t *pMem);
uint8_t BL_PageErase(ioMem_t *pMem);
uint8_t BL_ReadEEprom(ioMem_t *pMem);
uint8_t BL_WriteEEprom(ioMem_t *pMem);
uint8_t BL_WriteFlash(ioMem_t *pMem);
uint8_t BL_ReadFlashATM(ioMem_t *pMem);
uint8_t BL_ReadFlashSIL(ioMem_t *pMem);
void BL_SendCMDRunRestartBootloader(void);
#endif
uint8_t BL_ReadFlash(uint8_t interface_mode, ioMem_t *pMem);
void BL_SendCMDRunRestartBootloader(uint8_32_u *pDeviceInfo);

View File

@ -15,12 +15,15 @@
* along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
* Author: 4712
*/
#pragma once
#include "drivers/io.h"
typedef struct {
IO_t io;
} escHardware_t;
extern uint8_t escSelected;
extern uint8_t selected_esc;
bool isEscHi(uint8_t selEsc);
bool isEscLo(uint8_t selEsc);
@ -29,15 +32,17 @@ void setEscLo(uint8_t selEsc);
void setEscInput(uint8_t selEsc);
void setEscOutput(uint8_t selEsc);
#define ESC_IS_HI isEscHi(escSelected)
#define ESC_IS_LO isEscLo(escSelected)
#define ESC_SET_HI setEscHi(escSelected)
#define ESC_SET_LO setEscLo(escSelected)
#define ESC_INPUT setEscInput(escSelected)
#define ESC_OUTPUT setEscOutput(escSelected)
#define ESC_IS_HI isEscHi(selected_esc)
#define ESC_IS_LO isEscLo(selected_esc)
#define ESC_SET_HI setEscHi(selected_esc)
#define ESC_SET_LO setEscLo(selected_esc)
#define ESC_INPUT setEscInput(selected_esc)
#define ESC_OUTPUT setEscOutput(selected_esc)
typedef struct ioMem_s {
uint16_t len;
uint16_t addr;
uint8_t *data;
uint8_t D_NUM_BYTES;
uint8_t D_FLASH_ADDR_H;
uint8_t D_FLASH_ADDR_L;
uint8_t *D_PTR_I;
} ioMem_t;

View File

@ -23,38 +23,33 @@
#include <stdlib.h>
#include "platform.h"
#include "common/utils.h"
#include "drivers/gpio.h"
#include "drivers/buf_writer.h"
#include "drivers/pwm_mapping.h"
#ifdef USE_SERIAL_4WAY_BLHELI_INTERFACE
#include "drivers/serial.h"
#include "drivers/system.h"
#include "config/config.h"
#include "io/serial.h"
#include "io/serial_msp.h"
#include "io/serial_4way.h"
#include "io/serial_4way_impl.h"
#include "io/serial_4way_stk500v2.h"
#include "drivers/system.h"
#ifdef USE_SERIAL_4WAY_SK_BOOTLOADER
#if defined(USE_SERIAL_4WAY_BLHELI_INTERFACE) && defined(USE_SERIAL_4WAY_SK_BOOTLOADER)
#define BIT_LO_US (32) //32uS
#define BIT_HI_US (2*BIT_LO_US)
#define BIT_LO_US 32 //32uS
#define BIT_HI_US (2 * BIT_LO_US)
static uint8_t stkInBuf[16];
static uint8_t StkInBuf[16];
#define STK_BIT_TIMEOUT 250 // micro seconds
#define STK_WAIT_TICKS (1000 / STK_BIT_TIMEOUT) // per ms
#define STK_WAITCYLCES (STK_WAIT_TICKS * 35) // 35ms
#define STK_WAITCYLCES_START (STK_WAIT_TICKS / 2) // 0.5ms
#define STK_WAITCYLCES_EXT (STK_WAIT_TICKS * 5000) // 5s
#define STK_WAITCYLCES_START (STK_WAIT_TICKS / 2) // 0.5 ms
#define STK_WAITCYLCES_EXT (STK_WAIT_TICKS * 5000) //5 s
#define WaitPinLo while (ESC_IS_HI) { if (cmp32(micros(), timeout_timer) > 0) goto timeout; }
#define WaitPinHi while (ESC_IS_LO) { if (cmp32(micros(), timeout_timer) > 0) goto timeout; }
#define WaitPinLo while (ESC_IS_HI) {if (micros() > timeout_timer) goto timeout;}
#define WaitPinHi while (ESC_IS_LO) {if (micros() > timeout_timer) goto timeout;}
static uint32_t lastBitTime;
static uint32_t hiLoTsh;
static uint32_t LastBitTime;
static uint32_t HiLoTsh;
static uint8_t SeqNumber;
static uint8_t StkCmd;
@ -80,7 +75,7 @@ static uint8_t ckSumOut;
#define CmdFlashEepromRead 0xA0
#define EnterIspCmd1 0xAC
#define EnterIspCmd2 0x53
#define SPI_SIGNATURE_READ 0x30
#define signature_r 0x30
#define delay_us(x) delayMicroseconds(x)
#define IRQ_OFF // dummy
@ -111,7 +106,7 @@ static void StkSendByte(uint8_t dat)
}
}
static void StkSendPacketHeader(uint16_t len)
static void StkSendPacketHeader(void)
{
IRQ_OFF;
ESC_OUTPUT;
@ -121,9 +116,6 @@ static void StkSendPacketHeader(uint16_t len)
ckSumOut = 0;
StkSendByte(MESSAGE_START);
StkSendByte(++SeqNumber);
StkSendByte(len >> 8);
StkSendByte(len & 0xff);
StkSendByte(TOKEN);
}
static void StkSendPacketFooter(void)
@ -135,14 +127,16 @@ static void StkSendPacketFooter(void)
IRQ_ON;
}
static int8_t ReadBit(void)
{
uint32_t btimer = micros();
uint32_t timeout_timer = btimer + STK_BIT_TIMEOUT;
WaitPinLo;
WaitPinHi;
lastBitTime = micros() - btimer;
if (lastBitTime <= hiLoTsh) {
LastBitTime = micros() - btimer;
if (LastBitTime <= HiLoTsh) {
timeout_timer = timeout_timer + STK_BIT_TIMEOUT;
WaitPinLo;
WaitPinHi;
@ -155,27 +149,30 @@ timeout:
return -1;
}
static int ReadByte(void)
static uint8_t ReadByte(uint8_t *bt)
{
uint8_t byte = 0;
for (int i = 0; i < 8; i++) {
*bt = 0;
for (uint8_t i = 0; i < 8; i++) {
int8_t bit = ReadBit();
if (bit < 0)
return -1; // timeout
byte |= bit << i;
if (bit == -1) goto timeout;
if (bit == 1) {
*bt |= (1 << i);
}
ckSumIn ^= byte;
return byte;
}
ckSumIn ^=*bt;
return 1;
timeout:
return 0;
}
static uint8_t StkReadLeader(void)
{
// Reset learned timing
hiLoTsh = BIT_HI_US + BIT_LO_US;
HiLoTsh = BIT_HI_US + BIT_LO_US;
// Wait for the first bit
int waitcycl; //250uS each
uint32_t waitcycl; //250uS each
if((StkCmd == CMD_PROGRAM_EEPROM_ISP) || (StkCmd == CMD_CHIP_ERASE_ISP)) {
waitcycl = STK_WAITCYLCES_EXT;
@ -184,54 +181,57 @@ static uint8_t StkReadLeader(void)
} else {
waitcycl= STK_WAITCYLCES;
}
while(ReadBit() < 0 && --waitcycl > 0);
if (waitcycl <= 0)
goto timeout;
for ( ; waitcycl >0 ; waitcycl--) {
//check is not timeout
if (ReadBit() >- 1) break;
}
// Skip the first bits
for (int i = 0; i < 10; i++) {
if (ReadBit() < 0)
//Skip the first bits
if (waitcycl == 0){
goto timeout;
}
// learn timing (0.75 * lastBitTime)
hiLoTsh = (lastBitTime >> 1) + (lastBitTime >> 2);
for (uint8_t i = 0; i < 10; i++) {
if (ReadBit() == -1) goto timeout;
}
// learn timing
HiLoTsh = (LastBitTime >> 1) + (LastBitTime >> 2);
// Read until we get a 0 bit
int bit;
int8_t bit;
do {
bit = ReadBit();
if (bit < 0)
goto timeout;
if (bit == -1) goto timeout;
} while (bit > 0);
return 1;
timeout:
return 0;
}
static uint8_t StkRcvPacket(uint8_t *pstring, int maxLen)
static uint8_t StkRcvPacket(uint8_t *pstring)
{
int byte;
int len;
uint8_t bt = 0;
uint8_16_u Len;
IRQ_OFF;
if (!StkReadLeader()) goto Err;
ckSumIn=0;
if ((byte = ReadByte()) < 0 || (byte != MESSAGE_START)) goto Err;
if ((byte = ReadByte()) < 0 || (byte != SeqNumber)) goto Err;
len = ReadByte() << 8;
len |= ReadByte();
if(len < 1 || len >= 256 + 4) // will catch timeout too; limit length to max expected size
goto Err;
if ((byte = ReadByte()) < 0 || (byte != TOKEN)) goto Err;
if ((byte = ReadByte()) < 0 || (byte != StkCmd)) goto Err;
if ((byte = ReadByte()) < 0 || (byte != STATUS_CMD_OK)) goto Err;
for (int i = 0; i < len - 2; i++) {
if ((byte = ReadByte()) < 0) goto Err;
if(i < maxLen) // limit saved length (buffer is only 256B, but memory read reply contains additional status + 1 unknown byte)
pstring[i] = byte;
if (!ReadByte(&bt) || (bt != MESSAGE_START)) goto Err;
if (!ReadByte(&bt) || (bt != SeqNumber)) goto Err;
ReadByte(&Len.bytes[1]);
if (Len.bytes[1] > 1) goto Err;
ReadByte(&Len.bytes[0]);
if (Len.bytes[0] < 1) goto Err;
if (!ReadByte(&bt) || (bt != TOKEN)) goto Err;
if (!ReadByte(&bt) || (bt != StkCmd)) goto Err;
if (!ReadByte(&bt) || (bt != STATUS_CMD_OK)) goto Err;
for (uint16_t i = 0; i < (Len.word - 2); i++)
{
if (!ReadByte(pstring)) goto Err;
pstring++;
}
ReadByte(); // read checksum
ReadByte(&bt);
if (ckSumIn != 0) goto Err;
IRQ_ON;
return 1;
@ -240,24 +240,25 @@ Err:
return 0;
}
static uint8_t _CMD_SPI_MULTI_EX(uint8_t * resByte, uint8_t subcmd, uint16_t addr)
static uint8_t _CMD_SPI_MULTI_EX(volatile uint8_t * ResByte,uint8_t Cmd,uint8_t AdrHi,uint8_t AdrLo)
{
StkCmd = CMD_SPI_MULTI;
StkSendPacketHeader(8);
StkCmd= CMD_SPI_MULTI;
StkSendPacketHeader();
StkSendByte(0); // hi byte Msg len
StkSendByte(8); // lo byte Msg len
StkSendByte(TOKEN);
StkSendByte(CMD_SPI_MULTI);
StkSendByte(4); // NumTX
StkSendByte(4); // NumRX
StkSendByte(0); // RxStartAdr
StkSendByte(subcmd); // {TxData} Cmd
StkSendByte(addr >> 8); // {TxData} AdrHi
StkSendByte(addr & 0xff); // {TxData} AdrLow
StkSendByte(Cmd); // {TxData} Cmd
StkSendByte(AdrHi); // {TxData} AdrHi
StkSendByte(AdrLo); // {TxData} AdrLoch
StkSendByte(0); // {TxData} 0
StkSendPacketFooter();
if (StkRcvPacket(stkInBuf, sizeof(stkInBuf))) { // NumRX + 3
if ((stkInBuf[0] == 0x00)
&& ((stkInBuf[1] == subcmd) || (stkInBuf[1] == 0x00 /* ignore zero returns */))
&& (stkInBuf[2] == 0x00)) {
*resByte = stkInBuf[3];
if (StkRcvPacket((void *)StkInBuf)) { // NumRX + 3
if ((StkInBuf[0] == 0x00) && ((StkInBuf[1] == Cmd)||(StkInBuf[1] == 0x00)/* ignore zero returns */) &&(StkInBuf[2] == 0x00)) {
*ResByte = StkInBuf[3];
}
return 1;
}
@ -267,37 +268,61 @@ static uint8_t _CMD_SPI_MULTI_EX(uint8_t * resByte, uint8_t subcmd, uint16_t add
static uint8_t _CMD_LOAD_ADDRESS(ioMem_t *pMem)
{
// ignore 0xFFFF
// assume address is set before and we read or write the immediately following memory
if((pMem->addr == 0xffff))
return 1;
// assume address is set before and we read or write the immediately following package
if((pMem->D_FLASH_ADDR_H == 0xFF) && (pMem->D_FLASH_ADDR_L == 0xFF)) return 1;
StkCmd = CMD_LOAD_ADDRESS;
StkSendPacketHeader(5);
StkSendPacketHeader();
StkSendByte(0); // hi byte Msg len
StkSendByte(5); // lo byte Msg len
StkSendByte(TOKEN);
StkSendByte(CMD_LOAD_ADDRESS);
StkSendByte(0);
StkSendByte(0);
StkSendByte(pMem->addr >> 8);
StkSendByte(pMem->addr & 0xff);
StkSendByte(pMem->D_FLASH_ADDR_H);
StkSendByte(pMem->D_FLASH_ADDR_L);
StkSendPacketFooter();
return StkRcvPacket(stkInBuf, sizeof(stkInBuf));
return (StkRcvPacket((void *)StkInBuf));
}
static uint8_t _CMD_READ_MEM_ISP(ioMem_t *pMem)
{
StkSendPacketHeader(4);
uint8_t LenHi;
if (pMem->D_NUM_BYTES>0) {
LenHi=0;
} else {
LenHi=1;
}
StkSendPacketHeader();
StkSendByte(0); // hi byte Msg len
StkSendByte(4); // lo byte Msg len
StkSendByte(TOKEN);
StkSendByte(StkCmd);
StkSendByte(pMem->len >> 8);
StkSendByte(pMem->len & 0xff);
StkSendByte(LenHi);
StkSendByte(pMem->D_NUM_BYTES);
StkSendByte(CmdFlashEepromRead);
StkSendPacketFooter();
return StkRcvPacket(pMem->data, pMem->len);
return (StkRcvPacket(pMem->D_PTR_I));
}
static uint8_t _CMD_PROGRAM_MEM_ISP(ioMem_t *pMem)
{
StkSendPacketHeader(pMem->len + 10);
uint8_16_u Len;
uint8_t LenLo = pMem->D_NUM_BYTES;
uint8_t LenHi;
if (LenLo) {
LenHi = 0;
Len.word = LenLo + 10;
} else {
LenHi = 1;
Len.word = 256 + 10;
}
StkSendPacketHeader();
StkSendByte(Len.bytes[1]); // high byte Msg len
StkSendByte(Len.bytes[0]); // low byte Msg len
StkSendByte(TOKEN);
StkSendByte(StkCmd);
StkSendByte(pMem->len >> 8);
StkSendByte(pMem->len & 0xff);
StkSendByte(LenHi);
StkSendByte(LenLo);
StkSendByte(0); // mode
StkSendByte(0); // delay
StkSendByte(0); // cmd1
@ -305,41 +330,47 @@ static uint8_t _CMD_PROGRAM_MEM_ISP(ioMem_t *pMem)
StkSendByte(0); // cmd3
StkSendByte(0); // poll1
StkSendByte(0); // poll2
for(int i = 0; i < pMem->len; i++)
StkSendByte(pMem->data[i]);
do {
StkSendByte(*pMem->D_PTR_I);
pMem->D_PTR_I++;
LenLo--;
} while (LenLo);
StkSendPacketFooter();
return StkRcvPacket(stkInBuf, sizeof(stkInBuf));
return StkRcvPacket((void *)StkInBuf);
}
uint8_t Stk_SignOn(void)
{
StkCmd = CMD_SIGN_ON;
StkSendPacketHeader(1);
StkCmd=CMD_SIGN_ON;
StkSendPacketHeader();
StkSendByte(0); // hi byte Msg len
StkSendByte(1); // lo byte Msg len
StkSendByte(TOKEN);
StkSendByte(CMD_SIGN_ON);
StkSendPacketFooter();
return StkRcvPacket(stkInBuf, sizeof(stkInBuf));
return (StkRcvPacket((void *) StkInBuf));
}
uint8_t Stk_ConnectEx(escDeviceInfo_t *pDeviceInfo)
uint8_t Stk_ConnectEx(uint8_32_u *pDeviceInfo)
{
if (!Stk_SignOn())
return 0;
uint8_t signature[3]; // device signature, MSB first
for(unsigned i = 0; i < sizeof(signature); i++) {
if (!_CMD_SPI_MULTI_EX(&signature[i], SPI_SIGNATURE_READ, i))
return 0;
}
// convert signature to little endian
pDeviceInfo->signature = (signature[1] << 8) | signature[2];
pDeviceInfo->signature2 = signature[0];
if (Stk_SignOn()) {
if (_CMD_SPI_MULTI_EX(&pDeviceInfo->bytes[1], signature_r,0,1)) {
if (_CMD_SPI_MULTI_EX(&pDeviceInfo->bytes[0], signature_r,0,2)) {
return 1;
}
}
}
return 0;
}
uint8_t Stk_Chip_Erase(void)
{
StkCmd = CMD_CHIP_ERASE_ISP;
StkSendPacketHeader(7);
StkSendByte(StkCmd);
StkSendPacketHeader();
StkSendByte(0); // high byte Msg len
StkSendByte(7); // low byte Msg len
StkSendByte(TOKEN);
StkSendByte(CMD_CHIP_ERASE_ISP);
StkSendByte(20); // ChipErase_eraseDelay atmega8
StkSendByte(0); // ChipErase_pollMethod atmega8
StkSendByte(0xAC);
@ -347,40 +378,44 @@ uint8_t Stk_Chip_Erase(void)
StkSendByte(0x13);
StkSendByte(0x76);
StkSendPacketFooter();
return StkRcvPacket(stkInBuf, sizeof(stkInBuf));
return (StkRcvPacket(StkInBuf));
}
uint8_t Stk_ReadFlash(ioMem_t *pMem)
{
if (!_CMD_LOAD_ADDRESS(pMem))
return 0;
if (_CMD_LOAD_ADDRESS(pMem)) {
StkCmd = CMD_READ_FLASH_ISP;
return _CMD_READ_MEM_ISP(pMem);
return (_CMD_READ_MEM_ISP(pMem));
}
return 0;
}
uint8_t Stk_ReadEEprom(ioMem_t *pMem)
{
if (!_CMD_LOAD_ADDRESS(pMem))
return 0;
if (_CMD_LOAD_ADDRESS(pMem)) {
StkCmd = CMD_READ_EEPROM_ISP;
return _CMD_READ_MEM_ISP(pMem);
return (_CMD_READ_MEM_ISP(pMem));
}
return 0;
}
uint8_t Stk_WriteFlash(ioMem_t *pMem)
{
if (!_CMD_LOAD_ADDRESS(pMem))
return 0;
if (_CMD_LOAD_ADDRESS(pMem)) {
StkCmd = CMD_PROGRAM_FLASH_ISP;
return _CMD_PROGRAM_MEM_ISP(pMem);
return (_CMD_PROGRAM_MEM_ISP(pMem));
}
return 0;
}
uint8_t Stk_WriteEEprom(ioMem_t *pMem)
{
if (!_CMD_LOAD_ADDRESS(pMem))
return 0;
if (_CMD_LOAD_ADDRESS(pMem)) {
StkCmd = CMD_PROGRAM_EEPROM_ISP;
return _CMD_PROGRAM_MEM_ISP(pMem);
return (_CMD_PROGRAM_MEM_ISP(pMem));
}
return 0;
}
#endif
#endif

View File

@ -17,14 +17,11 @@
*/
#pragma once
#ifdef USE_SERIAL_4WAY_SK_BOOTLOADER
uint8_t Stk_SignOn(void);
uint8_t Stk_ConnectEx(escDeviceInfo_t *pDeviceInfo);
uint8_t Stk_ConnectEx(uint8_32_u *pDeviceInfo);
uint8_t Stk_ReadEEprom(ioMem_t *pMem);
uint8_t Stk_WriteEEprom(ioMem_t *pMem);
uint8_t Stk_ReadFlash(ioMem_t *pMem);
uint8_t Stk_WriteFlash(ioMem_t *pMem);
uint8_t Stk_Chip_Erase(void);
#endif