Fix unused param, add PERIPH_DRIVER flag for F4, tidied up F1 and F3 in prep.
[betaflight.git] / src / main / io / serial_4way_stk500v2.c
blob8bd8739603e962a541bb036965200a906f6df148
1 /*
2 * This file is part of Cleanflight.
4 * Cleanflight is free software: you can redistribute it and/or modify
5 * it under the terms of the GNU General Public License as published by
6 * the Free Software Foundation, either version 3 of the License, or
7 * (at your option) any later version.
9 * Cleanflight is distributed in the hope that it will be useful,
10 * but WITHOUT ANY WARRANTY; without even the implied warranty of
11 * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
12 * GNU General Public License for more details.
14 * You should have received a copy of the GNU General Public License
15 * along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
16 * Author: 4712
17 * have a look at https://github.com/sim-/tgy/blob/master/boot.inc
18 * for info about the stk500v2 implementation
21 #include <stdbool.h>
22 #include <stdint.h>
24 #include "platform.h"
26 #ifdef USE_SERIAL_4WAY_BLHELI_INTERFACE
28 #include "drivers/io.h"
29 #include "drivers/serial.h"
30 #include "drivers/time.h"
32 #include "io/serial.h"
33 #include "io/serial_4way.h"
34 #include "io/serial_4way_impl.h"
35 #include "io/serial_4way_stk500v2.h"
37 #ifdef USE_SERIAL_4WAY_SK_BOOTLOADER
39 #define BIT_LO_US (32) //32uS
40 #define BIT_HI_US (2*BIT_LO_US)
42 static uint8_t StkInBuf[16];
44 #define STK_BIT_TIMEOUT 250 // micro seconds
45 #define STK_WAIT_TICKS (1000 / STK_BIT_TIMEOUT) // per ms
46 #define STK_WAITCYLCES (STK_WAIT_TICKS * 35) // 35ms
47 #define STK_WAITCYLCES_START (STK_WAIT_TICKS / 2) // 0.5 ms
48 #define STK_WAITCYLCES_EXT (STK_WAIT_TICKS * 5000) //5 s
50 #define WaitPinLo while (ESC_IS_HI) {if (micros() > timeout_timer) goto timeout;}
51 #define WaitPinHi while (ESC_IS_LO) {if (micros() > timeout_timer) goto timeout;}
53 static uint32_t LastBitTime;
54 static uint32_t HiLoTsh;
56 static uint8_t SeqNumber;
57 static uint8_t StkCmd;
58 static uint8_t ckSumIn;
59 static uint8_t ckSumOut;
61 // used STK message constants from ATMEL AVR - Application note
62 #define MESSAGE_START 0x1B
63 #define TOKEN 0x0E
65 #define CMD_SIGN_ON 0x01
66 #define CMD_LOAD_ADDRESS 0x06
67 #define CMD_CHIP_ERASE_ISP 0x12
68 #define CMD_PROGRAM_FLASH_ISP 0x13
69 #define CMD_READ_FLASH_ISP 0x14
70 #define CMD_PROGRAM_EEPROM_ISP 0x15
71 #define CMD_READ_EEPROM_ISP 0x16
72 #define CMD_READ_SIGNATURE_ISP 0x1B
73 #define CMD_SPI_MULTI 0x1D
75 #define STATUS_CMD_OK 0x00
77 #define CmdFlashEepromRead 0xA0
78 #define EnterIspCmd1 0xAC
79 #define EnterIspCmd2 0x53
80 #define signature_r 0x30
82 #define delay_us(x) delayMicroseconds(x)
83 #define IRQ_OFF // dummy
84 #define IRQ_ON // dummy
86 static void StkSendByte(uint8_t dat)
88 ckSumOut ^= dat;
89 for (uint8_t i = 0; i < 8; i++) {
90 if (dat & 0x01) {
91 // 1-bits are encoded as 64.0us high, 72.8us low (135.8us total).
92 ESC_SET_HI;
93 delay_us(BIT_HI_US);
94 ESC_SET_LO;
95 delay_us(BIT_HI_US);
96 } else {
97 // 0-bits are encoded as 27.8us high, 34.5us low, 34.4us high, 37.9 low (134.6us total)
98 ESC_SET_HI;
99 delay_us(BIT_LO_US);
100 ESC_SET_LO;
101 delay_us(BIT_LO_US);
102 ESC_SET_HI;
103 delay_us(BIT_LO_US);
104 ESC_SET_LO;
105 delay_us(BIT_LO_US);
107 dat >>= 1;
111 static void StkSendPacketHeader(void)
113 IRQ_OFF;
114 ESC_OUTPUT;
115 StkSendByte(0xFF);
116 StkSendByte(0xFF);
117 StkSendByte(0x7F);
118 ckSumOut = 0;
119 StkSendByte(MESSAGE_START);
120 StkSendByte(++SeqNumber);
123 static void StkSendPacketFooter(void)
125 StkSendByte(ckSumOut);
126 ESC_SET_HI;
127 delay_us(BIT_LO_US);
128 ESC_INPUT;
129 IRQ_ON;
134 static int8_t ReadBit(void)
136 uint32_t btimer = micros();
137 uint32_t timeout_timer = btimer + STK_BIT_TIMEOUT;
138 WaitPinLo;
139 WaitPinHi;
140 LastBitTime = micros() - btimer;
141 if (LastBitTime <= HiLoTsh) {
142 timeout_timer = timeout_timer + STK_BIT_TIMEOUT;
143 WaitPinLo;
144 WaitPinHi;
145 //lo-bit
146 return 0;
147 } else {
148 return 1;
150 timeout:
151 return -1;
154 static uint8_t ReadByte(uint8_t *bt)
156 *bt = 0;
157 for (uint8_t i = 0; i < 8; i++) {
158 int8_t bit = ReadBit();
159 if (bit == -1) goto timeout;
160 if (bit == 1) {
161 *bt |= (1 << i);
164 ckSumIn ^=*bt;
165 return 1;
166 timeout:
167 return 0;
170 static uint8_t StkReadLeader(void)
173 // Reset learned timing
174 HiLoTsh = BIT_HI_US + BIT_LO_US;
176 // Wait for the first bit
177 uint32_t waitcycl; //250uS each
179 if ((StkCmd == CMD_PROGRAM_EEPROM_ISP) || (StkCmd == CMD_CHIP_ERASE_ISP)) {
180 waitcycl = STK_WAITCYLCES_EXT;
181 } else if (StkCmd == CMD_SIGN_ON) {
182 waitcycl = STK_WAITCYLCES_START;
183 } else {
184 waitcycl= STK_WAITCYLCES;
186 for ( ; waitcycl >0 ; waitcycl--) {
187 //check is not timeout
188 if (ReadBit() >- 1) break;
191 //Skip the first bits
192 if (waitcycl == 0) {
193 goto timeout;
196 for (uint8_t i = 0; i < 10; i++) {
197 if (ReadBit() == -1) goto timeout;
200 // learn timing
201 HiLoTsh = (LastBitTime >> 1) + (LastBitTime >> 2);
203 // Read until we get a 0 bit
204 int8_t bit;
205 do {
206 bit = ReadBit();
207 if (bit == -1) goto timeout;
208 } while (bit > 0);
209 return 1;
210 timeout:
211 return 0;
214 static uint8_t StkRcvPacket(uint8_t *pstring)
216 uint8_t bt = 0;
217 uint8_16_u Len;
219 IRQ_OFF;
220 if (!StkReadLeader()) goto Err;
221 ckSumIn=0;
222 if (!ReadByte(&bt) || (bt != MESSAGE_START)) goto Err;
223 if (!ReadByte(&bt) || (bt != SeqNumber)) goto Err;
224 ReadByte(&Len.bytes[1]);
225 if (Len.bytes[1] > 1) goto Err;
226 ReadByte(&Len.bytes[0]);
227 if (Len.bytes[0] < 1) goto Err;
228 if (!ReadByte(&bt) || (bt != TOKEN)) goto Err;
229 if (!ReadByte(&bt) || (bt != StkCmd)) goto Err;
230 if (!ReadByte(&bt) || (bt != STATUS_CMD_OK)) goto Err;
231 for (uint16_t i = 0; i < (Len.word - 2); i++)
233 if (!ReadByte(pstring)) goto Err;
234 pstring++;
236 ReadByte(&bt);
237 if (ckSumIn != 0) goto Err;
238 IRQ_ON;
239 return 1;
240 Err:
241 IRQ_ON;
242 return 0;
245 static uint8_t _CMD_SPI_MULTI_EX(volatile uint8_t * ResByte,uint8_t Cmd,uint8_t AdrHi,uint8_t AdrLo)
247 StkCmd= CMD_SPI_MULTI;
248 StkSendPacketHeader();
249 StkSendByte(0); // hi byte Msg len
250 StkSendByte(8); // lo byte Msg len
251 StkSendByte(TOKEN);
252 StkSendByte(CMD_SPI_MULTI);
253 StkSendByte(4); // NumTX
254 StkSendByte(4); // NumRX
255 StkSendByte(0); // RxStartAdr
256 StkSendByte(Cmd); // {TxData} Cmd
257 StkSendByte(AdrHi); // {TxData} AdrHi
258 StkSendByte(AdrLo); // {TxData} AdrLoch
259 StkSendByte(0); // {TxData} 0
260 StkSendPacketFooter();
261 if (StkRcvPacket((void *)StkInBuf)) { // NumRX + 3
262 if ((StkInBuf[0] == 0x00) && ((StkInBuf[1] == Cmd)||(StkInBuf[1] == 0x00)/* ignore zero returns */) &&(StkInBuf[2] == 0x00)) {
263 *ResByte = StkInBuf[3];
265 return 1;
267 return 0;
270 static uint8_t _CMD_LOAD_ADDRESS(ioMem_t *pMem)
272 // ignore 0xFFFF
273 // assume address is set before and we read or write the immediately following package
274 if ((pMem->D_FLASH_ADDR_H == 0xFF) && (pMem->D_FLASH_ADDR_L == 0xFF)) return 1;
275 StkCmd = CMD_LOAD_ADDRESS;
276 StkSendPacketHeader();
277 StkSendByte(0); // hi byte Msg len
278 StkSendByte(5); // lo byte Msg len
279 StkSendByte(TOKEN);
280 StkSendByte(CMD_LOAD_ADDRESS);
281 StkSendByte(0);
282 StkSendByte(0);
283 StkSendByte(pMem->D_FLASH_ADDR_H);
284 StkSendByte(pMem->D_FLASH_ADDR_L);
285 StkSendPacketFooter();
286 return (StkRcvPacket((void *)StkInBuf));
289 static uint8_t _CMD_READ_MEM_ISP(ioMem_t *pMem)
291 uint8_t LenHi;
292 if (pMem->D_NUM_BYTES>0) {
293 LenHi=0;
294 } else {
295 LenHi=1;
297 StkSendPacketHeader();
298 StkSendByte(0); // hi byte Msg len
299 StkSendByte(4); // lo byte Msg len
300 StkSendByte(TOKEN);
301 StkSendByte(StkCmd);
302 StkSendByte(LenHi);
303 StkSendByte(pMem->D_NUM_BYTES);
304 StkSendByte(CmdFlashEepromRead);
305 StkSendPacketFooter();
306 return (StkRcvPacket(pMem->D_PTR_I));
309 static uint8_t _CMD_PROGRAM_MEM_ISP(ioMem_t *pMem)
311 uint8_16_u Len;
312 uint8_t LenLo = pMem->D_NUM_BYTES;
313 uint8_t LenHi;
314 if (LenLo) {
315 LenHi = 0;
316 Len.word = LenLo + 10;
317 } else {
318 LenHi = 1;
319 Len.word = 256 + 10;
321 StkSendPacketHeader();
322 StkSendByte(Len.bytes[1]); // high byte Msg len
323 StkSendByte(Len.bytes[0]); // low byte Msg len
324 StkSendByte(TOKEN);
325 StkSendByte(StkCmd);
326 StkSendByte(LenHi);
327 StkSendByte(LenLo);
328 StkSendByte(0); // mode
329 StkSendByte(0); // delay
330 StkSendByte(0); // cmd1
331 StkSendByte(0); // cmd2
332 StkSendByte(0); // cmd3
333 StkSendByte(0); // poll1
334 StkSendByte(0); // poll2
335 do {
336 StkSendByte(*pMem->D_PTR_I);
337 pMem->D_PTR_I++;
338 LenLo--;
339 } while (LenLo);
340 StkSendPacketFooter();
341 return StkRcvPacket((void *)StkInBuf);
344 uint8_t Stk_SignOn(void)
346 StkCmd=CMD_SIGN_ON;
347 StkSendPacketHeader();
348 StkSendByte(0); // hi byte Msg len
349 StkSendByte(1); // lo byte Msg len
350 StkSendByte(TOKEN);
351 StkSendByte(CMD_SIGN_ON);
352 StkSendPacketFooter();
353 return (StkRcvPacket((void *) StkInBuf));
356 uint8_t Stk_ConnectEx(uint8_32_u *pDeviceInfo)
358 if (Stk_SignOn()) {
359 if (_CMD_SPI_MULTI_EX(&pDeviceInfo->bytes[1], signature_r,0,1)) {
360 if (_CMD_SPI_MULTI_EX(&pDeviceInfo->bytes[0], signature_r,0,2)) {
361 return 1;
365 return 0;
368 uint8_t Stk_Chip_Erase(void)
370 StkCmd = CMD_CHIP_ERASE_ISP;
371 StkSendPacketHeader();
372 StkSendByte(0); // high byte Msg len
373 StkSendByte(7); // low byte Msg len
374 StkSendByte(TOKEN);
375 StkSendByte(CMD_CHIP_ERASE_ISP);
376 StkSendByte(20); // ChipErase_eraseDelay atmega8
377 StkSendByte(0); // ChipErase_pollMethod atmega8
378 StkSendByte(0xAC);
379 StkSendByte(0x88);
380 StkSendByte(0x13);
381 StkSendByte(0x76);
382 StkSendPacketFooter();
383 return (StkRcvPacket(StkInBuf));
386 uint8_t Stk_ReadFlash(ioMem_t *pMem)
388 if (_CMD_LOAD_ADDRESS(pMem)) {
389 StkCmd = CMD_READ_FLASH_ISP;
390 return (_CMD_READ_MEM_ISP(pMem));
392 return 0;
396 uint8_t Stk_ReadEEprom(ioMem_t *pMem)
398 if (_CMD_LOAD_ADDRESS(pMem)) {
399 StkCmd = CMD_READ_EEPROM_ISP;
400 return (_CMD_READ_MEM_ISP(pMem));
402 return 0;
405 uint8_t Stk_WriteFlash(ioMem_t *pMem)
407 if (_CMD_LOAD_ADDRESS(pMem)) {
408 StkCmd = CMD_PROGRAM_FLASH_ISP;
409 return (_CMD_PROGRAM_MEM_ISP(pMem));
411 return 0;
414 uint8_t Stk_WriteEEprom(ioMem_t *pMem)
416 if (_CMD_LOAD_ADDRESS(pMem)) {
417 StkCmd = CMD_PROGRAM_EEPROM_ISP;
418 return (_CMD_PROGRAM_MEM_ISP(pMem));
420 return 0;
422 #endif
423 #endif