add h7 support to spi ll driver, drop hal version
[inav.git] / src / main / io / serial_4way_stk500v2.c
blobce0a57b2ebefc17140382abae31d304658713bac
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/system.h"
31 #include "drivers/time.h"
33 #include "io/serial.h"
34 #include "io/serial_4way.h"
35 #include "io/serial_4way_impl.h"
36 #include "io/serial_4way_stk500v2.h"
38 #ifdef USE_SERIAL_4WAY_SK_BOOTLOADER
40 #define BIT_LO_US (32) //32uS
41 #define BIT_HI_US (2*BIT_LO_US)
43 static uint8_t StkInBuf[16];
45 #define STK_BIT_TIMEOUT 250 // micro seconds
46 #define STK_WAIT_TICKS (1000 / STK_BIT_TIMEOUT) // per ms
47 #define STK_WAITCYLCES (STK_WAIT_TICKS * 35) // 35ms
48 #define STK_WAITCYLCES_START (STK_WAIT_TICKS / 2) // 0.5 ms
49 #define STK_WAITCYLCES_EXT (STK_WAIT_TICKS * 5000) //5 s
51 #define WaitPinLo while (ESC_IS_HI) {if (micros() > timeout_timer) goto timeout;}
52 #define WaitPinHi while (ESC_IS_LO) {if (micros() > timeout_timer) goto timeout;}
54 static uint32_t LastBitTime;
55 static uint32_t HiLoTsh;
57 static uint8_t SeqNumber;
58 static uint8_t StkCmd;
59 static uint8_t ckSumIn;
60 static uint8_t ckSumOut;
62 // used STK message constants from ATMEL AVR - Application note
63 #define MESSAGE_START 0x1B
64 #define TOKEN 0x0E
66 #define CMD_SIGN_ON 0x01
67 #define CMD_LOAD_ADDRESS 0x06
68 #define CMD_CHIP_ERASE_ISP 0x12
69 #define CMD_PROGRAM_FLASH_ISP 0x13
70 #define CMD_READ_FLASH_ISP 0x14
71 #define CMD_PROGRAM_EEPROM_ISP 0x15
72 #define CMD_READ_EEPROM_ISP 0x16
73 #define CMD_READ_SIGNATURE_ISP 0x1B
74 #define CMD_SPI_MULTI 0x1D
76 #define STATUS_CMD_OK 0x00
78 #define CmdFlashEepromRead 0xA0
79 #define EnterIspCmd1 0xAC
80 #define EnterIspCmd2 0x53
81 #define signature_r 0x30
83 #define delay_us(x) delayMicroseconds(x)
84 #define IRQ_OFF // dummy
85 #define IRQ_ON // dummy
87 static void StkSendByte(uint8_t dat)
89 ckSumOut ^= dat;
90 for (uint8_t i = 0; i < 8; i++) {
91 if (dat & 0x01) {
92 // 1-bits are encoded as 64.0us high, 72.8us low (135.8us total).
93 ESC_SET_HI;
94 delay_us(BIT_HI_US);
95 ESC_SET_LO;
96 delay_us(BIT_HI_US);
97 } else {
98 // 0-bits are encoded as 27.8us high, 34.5us low, 34.4us high, 37.9 low (134.6us total)
99 ESC_SET_HI;
100 delay_us(BIT_LO_US);
101 ESC_SET_LO;
102 delay_us(BIT_LO_US);
103 ESC_SET_HI;
104 delay_us(BIT_LO_US);
105 ESC_SET_LO;
106 delay_us(BIT_LO_US);
108 dat >>= 1;
112 static void StkSendPacketHeader(void)
114 IRQ_OFF;
115 ESC_OUTPUT;
116 StkSendByte(0xFF);
117 StkSendByte(0xFF);
118 StkSendByte(0x7F);
119 ckSumOut = 0;
120 StkSendByte(MESSAGE_START);
121 StkSendByte(++SeqNumber);
124 static void StkSendPacketFooter(void)
126 StkSendByte(ckSumOut);
127 ESC_SET_HI;
128 delay_us(BIT_LO_US);
129 ESC_INPUT;
130 IRQ_ON;
135 static int8_t ReadBit(void)
137 uint32_t btimer = micros();
138 uint32_t timeout_timer = btimer + STK_BIT_TIMEOUT;
139 WaitPinLo;
140 WaitPinHi;
141 LastBitTime = micros() - btimer;
142 if (LastBitTime <= HiLoTsh) {
143 timeout_timer = timeout_timer + STK_BIT_TIMEOUT;
144 WaitPinLo;
145 WaitPinHi;
146 //lo-bit
147 return 0;
148 } else {
149 return 1;
151 timeout:
152 return -1;
155 static uint8_t ReadByte(uint8_t *bt)
157 *bt = 0;
158 for (uint8_t i = 0; i < 8; i++) {
159 int8_t bit = ReadBit();
160 if (bit == -1) goto timeout;
161 if (bit == 1) {
162 *bt |= (1 << i);
165 ckSumIn ^=*bt;
166 return 1;
167 timeout:
168 return 0;
171 static uint8_t StkReadLeader(void)
174 // Reset learned timing
175 HiLoTsh = BIT_HI_US + BIT_LO_US;
177 // Wait for the first bit
178 uint32_t waitcycl; //250uS each
180 if ((StkCmd == CMD_PROGRAM_EEPROM_ISP) || (StkCmd == CMD_CHIP_ERASE_ISP)) {
181 waitcycl = STK_WAITCYLCES_EXT;
182 } else if (StkCmd == CMD_SIGN_ON) {
183 waitcycl = STK_WAITCYLCES_START;
184 } else {
185 waitcycl= STK_WAITCYLCES;
187 for ( ; waitcycl >0 ; waitcycl--) {
188 //check is not timeout
189 if (ReadBit() >- 1) break;
192 //Skip the first bits
193 if (waitcycl == 0){
194 goto timeout;
197 for (uint8_t i = 0; i < 10; i++) {
198 if (ReadBit() == -1) goto timeout;
201 // learn timing
202 HiLoTsh = (LastBitTime >> 1) + (LastBitTime >> 2);
204 // Read until we get a 0 bit
205 int8_t bit;
206 do {
207 bit = ReadBit();
208 if (bit == -1) goto timeout;
209 } while (bit > 0);
210 return 1;
211 timeout:
212 return 0;
215 static uint8_t StkRcvPacket(uint8_t *pstring)
217 uint8_t bt = 0;
218 uint8_16_u Len;
220 IRQ_OFF;
221 if (!StkReadLeader()) goto Err;
222 ckSumIn=0;
223 if (!ReadByte(&bt) || (bt != MESSAGE_START)) goto Err;
224 if (!ReadByte(&bt) || (bt != SeqNumber)) goto Err;
225 ReadByte(&Len.bytes[1]);
226 if (Len.bytes[1] > 1) goto Err;
227 ReadByte(&Len.bytes[0]);
228 if (Len.bytes[0] < 1) goto Err;
229 if (!ReadByte(&bt) || (bt != TOKEN)) goto Err;
230 if (!ReadByte(&bt) || (bt != StkCmd)) goto Err;
231 if (!ReadByte(&bt) || (bt != STATUS_CMD_OK)) goto Err;
232 for (uint16_t i = 0; i < (Len.word - 2); i++)
234 if (!ReadByte(pstring)) goto Err;
235 pstring++;
237 ReadByte(&bt);
238 if (ckSumIn != 0) goto Err;
239 IRQ_ON;
240 return 1;
241 Err:
242 IRQ_ON;
243 return 0;
246 static uint8_t _CMD_SPI_MULTI_EX(volatile uint8_t * ResByte,uint8_t Cmd,uint8_t AdrHi,uint8_t AdrLo)
248 StkCmd= CMD_SPI_MULTI;
249 StkSendPacketHeader();
250 StkSendByte(0); // hi byte Msg len
251 StkSendByte(8); // lo byte Msg len
252 StkSendByte(TOKEN);
253 StkSendByte(CMD_SPI_MULTI);
254 StkSendByte(4); // NumTX
255 StkSendByte(4); // NumRX
256 StkSendByte(0); // RxStartAdr
257 StkSendByte(Cmd); // {TxData} Cmd
258 StkSendByte(AdrHi); // {TxData} AdrHi
259 StkSendByte(AdrLo); // {TxData} AdrLoch
260 StkSendByte(0); // {TxData} 0
261 StkSendPacketFooter();
262 if (StkRcvPacket((void *)StkInBuf)) { // NumRX + 3
263 if ((StkInBuf[0] == 0x00) && ((StkInBuf[1] == Cmd)||(StkInBuf[1] == 0x00)/* ignore zero returns */) &&(StkInBuf[2] == 0x00)) {
264 *ResByte = StkInBuf[3];
266 return 1;
268 return 0;
271 static uint8_t _CMD_LOAD_ADDRESS(ioMem_t *pMem)
273 // ignore 0xFFFF
274 // assume address is set before and we read or write the immediately following package
275 if ((pMem->D_FLASH_ADDR_H == 0xFF) && (pMem->D_FLASH_ADDR_L == 0xFF)) return 1;
276 StkCmd = CMD_LOAD_ADDRESS;
277 StkSendPacketHeader();
278 StkSendByte(0); // hi byte Msg len
279 StkSendByte(5); // lo byte Msg len
280 StkSendByte(TOKEN);
281 StkSendByte(CMD_LOAD_ADDRESS);
282 StkSendByte(0);
283 StkSendByte(0);
284 StkSendByte(pMem->D_FLASH_ADDR_H);
285 StkSendByte(pMem->D_FLASH_ADDR_L);
286 StkSendPacketFooter();
287 return (StkRcvPacket((void *)StkInBuf));
290 static uint8_t _CMD_READ_MEM_ISP(ioMem_t *pMem)
292 uint8_t LenHi;
293 if (pMem->D_NUM_BYTES>0) {
294 LenHi=0;
295 } else {
296 LenHi=1;
298 StkSendPacketHeader();
299 StkSendByte(0); // hi byte Msg len
300 StkSendByte(4); // lo byte Msg len
301 StkSendByte(TOKEN);
302 StkSendByte(StkCmd);
303 StkSendByte(LenHi);
304 StkSendByte(pMem->D_NUM_BYTES);
305 StkSendByte(CmdFlashEepromRead);
306 StkSendPacketFooter();
307 return (StkRcvPacket(pMem->D_PTR_I));
310 static uint8_t _CMD_PROGRAM_MEM_ISP(ioMem_t *pMem)
312 uint8_16_u Len;
313 uint8_t LenLo = pMem->D_NUM_BYTES;
314 uint8_t LenHi;
315 if (LenLo) {
316 LenHi = 0;
317 Len.word = LenLo + 10;
318 } else {
319 LenHi = 1;
320 Len.word = 256 + 10;
322 StkSendPacketHeader();
323 StkSendByte(Len.bytes[1]); // high byte Msg len
324 StkSendByte(Len.bytes[0]); // low byte Msg len
325 StkSendByte(TOKEN);
326 StkSendByte(StkCmd);
327 StkSendByte(LenHi);
328 StkSendByte(LenLo);
329 StkSendByte(0); // mode
330 StkSendByte(0); // delay
331 StkSendByte(0); // cmd1
332 StkSendByte(0); // cmd2
333 StkSendByte(0); // cmd3
334 StkSendByte(0); // poll1
335 StkSendByte(0); // poll2
336 do {
337 StkSendByte(*pMem->D_PTR_I);
338 pMem->D_PTR_I++;
339 LenLo--;
340 } while (LenLo);
341 StkSendPacketFooter();
342 return StkRcvPacket((void *)StkInBuf);
345 uint8_t Stk_SignOn(void)
347 StkCmd=CMD_SIGN_ON;
348 StkSendPacketHeader();
349 StkSendByte(0); // hi byte Msg len
350 StkSendByte(1); // lo byte Msg len
351 StkSendByte(TOKEN);
352 StkSendByte(CMD_SIGN_ON);
353 StkSendPacketFooter();
354 return (StkRcvPacket((void *) StkInBuf));
357 uint8_t Stk_ConnectEx(uint8_32_u *pDeviceInfo)
359 if (Stk_SignOn()) {
360 if (_CMD_SPI_MULTI_EX(&pDeviceInfo->bytes[1], signature_r,0,1)) {
361 if (_CMD_SPI_MULTI_EX(&pDeviceInfo->bytes[0], signature_r,0,2)) {
362 return 1;
366 return 0;
369 uint8_t Stk_Chip_Erase(void)
371 StkCmd = CMD_CHIP_ERASE_ISP;
372 StkSendPacketHeader();
373 StkSendByte(0); // high byte Msg len
374 StkSendByte(7); // low byte Msg len
375 StkSendByte(TOKEN);
376 StkSendByte(CMD_CHIP_ERASE_ISP);
377 StkSendByte(20); // ChipErase_eraseDelay atmega8
378 StkSendByte(0); // ChipErase_pollMethod atmega8
379 StkSendByte(0xAC);
380 StkSendByte(0x88);
381 StkSendByte(0x13);
382 StkSendByte(0x76);
383 StkSendPacketFooter();
384 return (StkRcvPacket(StkInBuf));
387 uint8_t Stk_ReadFlash(ioMem_t *pMem)
389 if (_CMD_LOAD_ADDRESS(pMem)) {
390 StkCmd = CMD_READ_FLASH_ISP;
391 return (_CMD_READ_MEM_ISP(pMem));
393 return 0;
397 uint8_t Stk_ReadEEprom(ioMem_t *pMem)
399 if (_CMD_LOAD_ADDRESS(pMem)) {
400 StkCmd = CMD_READ_EEPROM_ISP;
401 return (_CMD_READ_MEM_ISP(pMem));
403 return 0;
406 uint8_t Stk_WriteFlash(ioMem_t *pMem)
408 if (_CMD_LOAD_ADDRESS(pMem)) {
409 StkCmd = CMD_PROGRAM_FLASH_ISP;
410 return (_CMD_PROGRAM_MEM_ISP(pMem));
412 return 0;
415 uint8_t Stk_WriteEEprom(ioMem_t *pMem)
417 if (_CMD_LOAD_ADDRESS(pMem)) {
418 StkCmd = CMD_PROGRAM_EEPROM_ISP;
419 return (_CMD_PROGRAM_MEM_ISP(pMem));
421 return 0;
423 #endif
424 #endif